From 34ec89c0414c12cd14f4a4fc0749ea40a858948c Mon Sep 17 00:00:00 2001 From: Peter Johnson Date: Thu, 24 Nov 2022 09:05:37 -0800 Subject: [PATCH] [wpilibc] Shuffleboard SimpleWidget: Return pointer instead of reference (#4703) Based on beta test feedback, returning a pointer is more intuitive, as typically the return value is late bound to an instance variable. --- .../shuffleboard/ShuffleboardContainer.cpp | 4 +- .../native/cpp/shuffleboard/SimpleWidget.cpp | 8 ++-- .../include/frc/shuffleboard/SimpleWidget.h | 10 +++-- .../shuffleboard/ShuffleboardInstanceTest.cpp | 38 +++++++++---------- .../cpp/examples/ShuffleBoard/cpp/Robot.cpp | 8 ++-- 5 files changed, 35 insertions(+), 33 deletions(-) diff --git a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp index 03c8549e94..ca3c6d69de 100644 --- a/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp +++ b/wpilibc/src/main/native/cpp/shuffleboard/ShuffleboardContainer.cpp @@ -83,7 +83,7 @@ SimpleWidget& ShuffleboardContainer::Add(std::string_view title, auto ptr = widget.get(); m_components.emplace_back(std::move(widget)); ptr->GetEntry(nt::GetStringFromType(defaultValue.type())) - .SetDefault(defaultValue); + ->SetDefault(defaultValue); return *ptr; } @@ -322,7 +322,7 @@ SimpleWidget& ShuffleboardContainer::AddPersistent( std::string_view title, const nt::Value& defaultValue) { auto& widget = Add(title, defaultValue); widget.GetEntry(nt::GetStringFromType(defaultValue.type())) - .GetTopic() + ->GetTopic() .SetPersistent(true); return widget; } diff --git a/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp b/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp index 2305bd1353..c62b76de92 100644 --- a/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp +++ b/wpilibc/src/main/native/cpp/shuffleboard/SimpleWidget.cpp @@ -14,19 +14,19 @@ SimpleWidget::SimpleWidget(ShuffleboardContainer& parent, std::string_view title) : ShuffleboardValue(title), ShuffleboardWidget(parent, title), m_entry() {} -nt::GenericEntry& SimpleWidget::GetEntry() { +nt::GenericEntry* SimpleWidget::GetEntry() { if (!m_entry) { ForceGenerate(); } - return m_entry; + return &m_entry; } -nt::GenericEntry& SimpleWidget::GetEntry(std::string_view typeString) { +nt::GenericEntry* SimpleWidget::GetEntry(std::string_view typeString) { if (!m_entry) { m_typeString = typeString; ForceGenerate(); } - return m_entry; + return &m_entry; } void SimpleWidget::BuildInto(std::shared_ptr parentTable, diff --git a/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h b/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h index 8653549ff2..97502be5ad 100644 --- a/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h +++ b/wpilibc/src/main/native/include/frc/shuffleboard/SimpleWidget.h @@ -27,17 +27,19 @@ class SimpleWidget final : public ShuffleboardWidget { /** * Gets the NetworkTable entry that contains the data for this widget. - * The widget owns the entry. + * The widget owns the entry; the returned pointer's lifetime is the same as + * that of the widget. */ - nt::GenericEntry& GetEntry(); + nt::GenericEntry* GetEntry(); /** * Gets the NetworkTable entry that contains the data for this widget. - * The widget owns the entry. + * The widget owns the entry; the returned pointer's lifetime is the same as + * that of the widget. * * @param typeString NT type string */ - nt::GenericEntry& GetEntry(std::string_view typeString); + nt::GenericEntry* GetEntry(std::string_view typeString); void BuildInto(std::shared_ptr parentTable, std::shared_ptr metaTable) override; diff --git a/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp index 606b8f06eb..0b0c8dfb7e 100644 --- a/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp +++ b/wpilibc/src/test/native/cpp/shuffleboard/ShuffleboardInstanceTest.cpp @@ -25,14 +25,14 @@ TEST(ShuffleboardInstanceTest, PathFluent) { NTWrapper ntInst; frc::detail::ShuffleboardInstance shuffleboardInst{ntInst.inst}; - auto& entry = shuffleboardInst.GetTab("Tab Title") - .GetLayout("List", "List Layout") - .Add("Data", "string") - .WithWidget("Text View") - .GetEntry(); + auto entry = shuffleboardInst.GetTab("Tab Title") + .GetLayout("List", "List Layout") + .Add("Data", "string") + .WithWidget("Text View") + .GetEntry(); - EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value"; - EXPECT_EQ("/Shuffleboard/Tab Title/List/Data", entry.GetTopic().GetName()) + EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value"; + EXPECT_EQ("/Shuffleboard/Tab Title/List/Data", entry->GetTopic().GetName()) << "Entry path generated incorrectly"; } @@ -40,17 +40,17 @@ TEST(ShuffleboardInstanceTest, NestedLayoutsFluent) { NTWrapper ntInst; frc::detail::ShuffleboardInstance shuffleboardInst{ntInst.inst}; - auto& entry = shuffleboardInst.GetTab("Tab") - .GetLayout("First", "List") - .GetLayout("Second", "List") - .GetLayout("Third", "List") - .GetLayout("Fourth", "List") - .Add("Value", "string") - .GetEntry(); + auto entry = shuffleboardInst.GetTab("Tab") + .GetLayout("First", "List") + .GetLayout("Second", "List") + .GetLayout("Third", "List") + .GetLayout("Fourth", "List") + .Add("Value", "string") + .GetEntry(); - EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value"; + EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value"; EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value", - entry.GetTopic().GetName()) + entry->GetTopic().GetName()) << "Entry path generated incorrectly"; } @@ -64,11 +64,11 @@ TEST(ShuffleboardInstanceTest, NestedLayoutsOop) { frc::ShuffleboardLayout& third = second.GetLayout("Third", "List"); frc::ShuffleboardLayout& fourth = third.GetLayout("Fourth", "List"); frc::SimpleWidget& widget = fourth.Add("Value", "string"); - auto& entry = widget.GetEntry(); + auto entry = widget.GetEntry(); - EXPECT_EQ("string", entry.GetString("")) << "Wrong entry value"; + EXPECT_EQ("string", entry->GetString("")) << "Wrong entry value"; EXPECT_EQ("/Shuffleboard/Tab/First/Second/Third/Fourth/Value", - entry.GetTopic().GetName()) + entry->GetTopic().GetName()) << "Entry path generated incorrectly"; } diff --git a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp index 6cb97938f6..141780182c 100644 --- a/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/ShuffleBoard/cpp/Robot.cpp @@ -31,10 +31,10 @@ class Robot : public frc::TimedRobot { public: void RobotInit() override { // Add a widget titled 'Max Speed' with a number slider. - m_maxSpeed = &frc::Shuffleboard::GetTab("Configuration") - .Add("Max Speed", 1) - .WithWidget("Number Slider") - .GetEntry(); + m_maxSpeed = frc::Shuffleboard::GetTab("Configuration") + .Add("Max Speed", 1) + .WithWidget("Number Slider") + .GetEntry(); // Create a 'DriveBase' tab and add the drivetrain object to it. frc::ShuffleboardTab& driveBaseTab = frc::Shuffleboard::GetTab("DriveBase");