diff --git a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h index 40588dd58ab..bf7fff55630 100644 --- a/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h +++ b/wpilibc/src/main/native/include/frc/smartdashboard/SendableChooser.h @@ -37,7 +37,7 @@ template requires std::copy_constructible && std::default_initializable class SendableChooser : public SendableChooserBase { wpi::StringMap m_choices; - std::function m_listener; + std::function m_listener; template static U _unwrap_smart_ptr(const U& value) { return value; @@ -95,13 +95,7 @@ class SendableChooser : public SendableChooserBase { * @return The option selected */ CopyType GetSelected() const { - std::string selected = m_defaultChoice; - { - std::scoped_lock lock(m_mutex); - if (m_haveSelected) { - selected = m_selected; - } - } + std::string selected = GetSelectedName(); if (selected.empty()) { return CopyType{}; } else { @@ -113,17 +107,47 @@ class SendableChooser : public SendableChooserBase { } } + /** + * Returns the name of the selected option. + * + * If there is none selected, it will return the default option's name. If + * there is none selected and no default, it will return an empty string. + * + * @return The name of the option selected + */ + std::string GetSelectedName() const { + std::scoped_lock lock(m_mutex); + if (m_haveSelected) { + return m_selected; + } else { + return m_defaultChoice; + } + } + /** * Bind a listener that's called when the selected value changes. * Only one listener can be bound. Calling this function will replace the * previous listener. - * @param listener The function to call that accepts the new value + * @param listener The function to call that accepts the new name and new + * value */ - void OnChange(std::function listener) { + void OnChange(std::function listener) { std::scoped_lock lock(m_mutex); m_listener = listener; } + /** + * Bind a listener that's called when the selected value changes. + * Only one listener can be bound. Calling this function will replace the + * previous listener. + * @param listener The function to call that accepts the new value + */ + void OnChange(std::function listener) { + OnChange([listener = std::move(listener)](std::string_view val, T choice) { + listener(choice); + }); + } + void InitSendable(wpi::SendableBuilder& builder) override { builder.SetSmartDashboardType("String Chooser"); builder.PublishConstInteger(kInstance, m_instance); @@ -155,24 +179,24 @@ class SendableChooser : public SendableChooserBase { } }, nullptr); - builder.AddStringProperty(kSelected, nullptr, - [=, this](std::string_view val) { - T choice{}; - std::function listener; - { - std::scoped_lock lock(m_mutex); - m_haveSelected = true; - m_selected = val; - if (m_previousVal != val && m_listener) { - choice = m_choices[val]; - listener = m_listener; - } - m_previousVal = val; - } - if (listener) { - listener(choice); - } - }); + builder.AddStringProperty( + kSelected, nullptr, [=, this](std::string_view val) { + T choice{}; + std::function listener; + { + std::scoped_lock lock(m_mutex); + m_haveSelected = true; + m_selected = val; + if (m_previousVal != val && m_listener) { + choice = m_choices[val]; + listener = m_listener; + } + m_previousVal = val; + } + if (listener) { + listener(val, choice); + } + }); } }; diff --git a/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp b/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp index 702735c3eaf..824ab416491 100644 --- a/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp +++ b/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp @@ -31,6 +31,7 @@ TEST_P(SendableChooserTest, ReturnsSelected) { chooserSim.SetSelected(std::to_string(GetParam())); frc::SmartDashboard::UpdateValues(); EXPECT_EQ(GetParam(), chooser.GetSelected()); + EXPECT_EQ(std::to_string(GetParam()), chooser.GetSelectedName()); } TEST(SendableChooserTest, DefaultIsReturnedOnNoSelect) { @@ -44,6 +45,7 @@ TEST(SendableChooserTest, DefaultIsReturnedOnNoSelect) { chooser.SetDefaultOption("4", 4); EXPECT_EQ(4, chooser.GetSelected()); + EXPECT_EQ("4", chooser.GetSelectedName()); } TEST(SendableChooserTest, @@ -55,6 +57,7 @@ TEST(SendableChooserTest, } EXPECT_EQ(0, chooser.GetSelected()); + EXPECT_EQ("", chooser.GetSelectedName()); } TEST(SendableChooserTest, ChangeListener) { @@ -65,8 +68,13 @@ TEST(SendableChooserTest, ChangeListener) { for (int i = 1; i <= 3; i++) { chooser.AddOption(std::to_string(i), i); } + + std::string currentName = ""; int currentVal = 0; - chooser.OnChange([&](int val) { currentVal = val; }); + chooser.OnChange([&](std::string_view name, int val) { + currentName = std::string(name); + currentVal = val; + }); frc::SmartDashboard::PutData("ChangeListenerChooser", &chooser); frc::SmartDashboard::UpdateValues(); @@ -74,6 +82,7 @@ TEST(SendableChooserTest, ChangeListener) { frc::SmartDashboard::UpdateValues(); EXPECT_EQ(3, currentVal); + EXPECT_EQ("3", currentName); } INSTANTIATE_TEST_SUITE_P(SendableChooserTests, SendableChooserTest, diff --git a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java index e905ebc6350..a73b7eea5c5 100644 --- a/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java +++ b/wpilibj/src/main/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooser.java @@ -13,6 +13,7 @@ import java.util.Map; import java.util.concurrent.atomic.AtomicInteger; import java.util.concurrent.locks.ReentrantLock; +import java.util.function.BiConsumer; import java.util.function.Consumer; /** @@ -49,7 +50,7 @@ public class SendableChooser implements Sendable, AutoCloseable { private String m_defaultChoice = ""; private final int m_instance; private String m_previousVal; - private Consumer m_listener; + private BiConsumer m_listener; private static final AtomicInteger s_instances = new AtomicInteger(); /** Instantiates a {@link SendableChooser}. */ @@ -97,12 +98,22 @@ public void setDefaultOption(String name, V object) { * @return the option selected */ public V getSelected() { + return m_map.get(getSelectedName()); + } + + /** + * Returns the name of the selected option. If there is none selected, it will return the default. + * If there is none selected and no default, it will return an empty String. + * + * @return the name of the option selected + */ + public String getSelectedName() { m_mutex.lock(); try { if (m_selected != null) { - return m_map.get(m_selected); + return m_selected; } else { - return m_map.get(m_defaultChoice); + return m_defaultChoice; } } finally { m_mutex.unlock(); @@ -113,15 +124,25 @@ public V getSelected() { * Bind a listener that's called when the selected value changes. Only one listener can be bound. * Calling this function will replace the previous listener. * - * @param listener The function to call that accepts the new value + * @param listener The function to call that accepts the new name and new value */ - public void onChange(Consumer listener) { + public void onChange(BiConsumer listener) { requireNonNullParam(listener, "listener", "onChange"); m_mutex.lock(); m_listener = listener; m_mutex.unlock(); } + /** + * Bind a listener that's called when the selected value changes. Only one listener can be bound. + * Calling this function will replace the previous listener. + * + * @param listener The function to call that accepts the new value + */ + public void onChange(Consumer listener) { + onChange((String value, V choice) -> listener.accept(choice)); + } + private String m_selected; private final ReentrantLock m_mutex = new ReentrantLock(); @@ -151,7 +172,7 @@ public void initSendable(SendableBuilder builder) { null, val -> { V choice; - Consumer listener; + BiConsumer listener; m_mutex.lock(); try { m_selected = val; @@ -167,7 +188,7 @@ public void initSendable(SendableBuilder builder) { m_mutex.unlock(); } if (listener != null) { - listener.accept(choice); + listener.accept(val, choice); } }); } diff --git a/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooserTest.java b/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooserTest.java index d8e3f8fbb98..4846bbc85a2 100644 --- a/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooserTest.java +++ b/wpilibj/src/test/java/edu/wpi/first/wpilibj/smartdashboard/SendableChooserTest.java @@ -10,6 +10,7 @@ import edu.wpi.first.networktables.NetworkTableInstance; import edu.wpi.first.wpilibj.simulation.SendableChooserSim; import java.util.concurrent.atomic.AtomicInteger; +import java.util.concurrent.atomic.AtomicReference; import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; @@ -42,6 +43,7 @@ void returnsSelected(int toSelect) { chooserSim.setSelected(String.valueOf(toSelect)); SmartDashboard.updateValues(); assertEquals(toSelect, chooser.getSelected()); + assertEquals(String.valueOf(toSelect), chooser.getSelectedName()); } } @@ -54,6 +56,7 @@ void defaultIsReturnedOnNoSelect() { chooser.setDefaultOption(String.valueOf(0), 0); assertEquals(0, chooser.getSelected()); + assertEquals(String.valueOf(0), chooser.getSelectedName()); } } @@ -65,6 +68,7 @@ void nullIsReturnedOnNoSelectAndNoDefault() { } assertNull(chooser.getSelected()); + assertEquals("", chooser.getSelectedName()); } } @@ -75,14 +79,21 @@ void testChangeListener() { for (int i = 1; i <= 3; i++) { chooser.addOption(String.valueOf(i), i); } + + AtomicReference currentName = new AtomicReference<>(""); AtomicInteger currentVal = new AtomicInteger(); - chooser.onChange(currentVal::set); + chooser.onChange( + (String name, Integer value) -> { + currentName.set(name); + currentVal.set(value); + }); SmartDashboard.putData("changeListenerChooser", chooser); SmartDashboard.updateValues(); chooserSim.setSelected("3"); SmartDashboard.updateValues(); assertEquals(3, currentVal.get()); + assertEquals("3", currentName.get()); } }