From 05e36cf34ef6ae8befa457de2d91d01ceb45f190 Mon Sep 17 00:00:00 2001 From: Jonah <47046556+jwbonner@users.noreply.github.com> Date: Thu, 2 Nov 2023 12:34:36 -0400 Subject: [PATCH] Add `LoggedDashboarChooser` constructor that copies from a `SendableChooser` --- docs/CODE-STRUCTURE.md | 13 +++++ .../main/java/frc/robot/RobotContainer.java | 6 +- .../networktables/LoggedDashboardChooser.java | 58 +++++++++++++++++-- 3 files changed, 69 insertions(+), 8 deletions(-) diff --git a/docs/CODE-STRUCTURE.md b/docs/CODE-STRUCTURE.md index a28149da..cb236a9d 100644 --- a/docs/CODE-STRUCTURE.md +++ b/docs/CODE-STRUCTURE.md @@ -119,6 +119,19 @@ public Command getAutonomousCommand() { } ``` +A `LoggedDashboardChooser` can also be constructed using an existing `SendableChooser`, which allows for compatibility PathPlanner's `AutoBuilder` API: + +```java +private final LoggedDashboardChooser autoChooser; + +public RobotContainer() { + // ... + + // buildAutoChooser() returns a SendableChooser + autoChooser = new LoggedDashboardChooser<>("Auto Routine", AutoBuilder.buildAutoChooser()); +} +``` + ## Logging Outputs Output data consists of any calculated values which could be recreated in the simulator, including... diff --git a/example_projects/swerve_drive/src/main/java/frc/robot/RobotContainer.java b/example_projects/swerve_drive/src/main/java/frc/robot/RobotContainer.java index 4b4d1d16..05bcc418 100644 --- a/example_projects/swerve_drive/src/main/java/frc/robot/RobotContainer.java +++ b/example_projects/swerve_drive/src/main/java/frc/robot/RobotContainer.java @@ -39,8 +39,7 @@ public class RobotContainer { private final CommandXboxController controller = new CommandXboxController(0); // Dashboard inputs - private final LoggedDashboardChooser autoChooser = - new LoggedDashboardChooser<>("Auto Choices"); + private final LoggedDashboardChooser autoChooser; private final LoggedDashboardNumber flywheelSpeedInput = new LoggedDashboardNumber("Flywheel Speed", 1500.0); @@ -98,8 +97,7 @@ public RobotContainer() { () -> flywheel.runVelocity(flywheelSpeedInput.get()), flywheel::stop, flywheel)); // Set up auto routines - autoChooser.addDefaultOption("Do Nothing", Commands.none()); - autoChooser.addOption("Example Auto", new PathPlannerAuto("Example Auto")); + autoChooser = new LoggedDashboardChooser<>("Auto Choices", AutoBuilder.buildAutoChooser()); // Set up FF characterization routines autoChooser.addOption( diff --git a/junction/core/src/org/littletonrobotics/junction/networktables/LoggedDashboardChooser.java b/junction/core/src/org/littletonrobotics/junction/networktables/LoggedDashboardChooser.java index 992b389c..b56def63 100644 --- a/junction/core/src/org/littletonrobotics/junction/networktables/LoggedDashboardChooser.java +++ b/junction/core/src/org/littletonrobotics/junction/networktables/LoggedDashboardChooser.java @@ -1,5 +1,6 @@ package org.littletonrobotics.junction.networktables; +import java.lang.reflect.Field; import java.util.HashMap; import java.util.Map; @@ -27,11 +28,11 @@ public void fromLog(LogTable table) { }; /** - * Creates a new LoggedDashboardString, for handling a string input sent via + * Creates a new LoggedDashboardChooser, for handling a chooser input sent via * NetworkTables. - * - * @param key The key for the chooser, published to - * "/SmartDashboard/{key}" for NT or + * + * @param key The key for the chooser, published to "/SmartDashboard/{key}" for + * NT or * "/DashboardInputs/{key}" when logged. */ public LoggedDashboardChooser(String key) { @@ -41,6 +42,55 @@ public LoggedDashboardChooser(String key) { Logger.registerDashboardInput(this); } + /** + * Creates a new LoggedDashboardChooser, for handling a chooser input sent via + * NetworkTables. This constructor copies the options from a SendableChooser. + * Note that updates to the original SendableChooser will not affect this + * object. + * + * @param key The key for the chooser, published to "/SmartDashboard/{key}" for + * NT or "/DashboardInputs/{key}" when logged. + */ + @SuppressWarnings("unchecked") + public LoggedDashboardChooser(String key, SendableChooser chooser) { + this(key); + + // Get options map + Map options = new HashMap<>(); + try { + Field mapField = SendableChooser.class.getDeclaredField("m_map"); + mapField.setAccessible(true); + options = (Map) mapField.get(chooser); + } catch (NoSuchFieldException + | SecurityException + | IllegalArgumentException + | IllegalAccessException e) { + e.printStackTrace(); + } + + // Get default option + String defaultString = ""; + try { + Field defaultField = SendableChooser.class.getDeclaredField("m_defaultChoice"); + defaultField.setAccessible(true); + defaultString = (String) defaultField.get(chooser); + } catch (NoSuchFieldException + | SecurityException + | IllegalArgumentException + | IllegalAccessException e) { + e.printStackTrace(); + } + + // Add options + for (String optionKey : options.keySet()) { + if (optionKey.equals(defaultString)) { + addDefaultOption(optionKey, options.get(optionKey)); + } else { + addOption(optionKey, options.get(optionKey)); + } + } + } + /** Adds a new option to the chooser. */ public void addOption(String key, V value) { sendableChooser.addOption(key, key);