|
9 | 9 |
|
10 | 10 | import com.frcteam3255.joystick.SN_XboxController; |
11 | 11 |
|
| 12 | +import choreo.auto.AutoChooser; |
12 | 13 | import choreo.auto.AutoFactory; |
13 | 14 | import edu.wpi.first.epilogue.Logged; |
14 | 15 | import edu.wpi.first.epilogue.NotLogged; |
15 | 16 | import edu.wpi.first.math.geometry.Pose2d; |
16 | 17 | import edu.wpi.first.wpilibj.GenericHID.RumbleType; |
17 | 18 | import edu.wpi.first.wpilibj.RobotController; |
18 | | -import edu.wpi.first.wpilibj.smartdashboard.SendableChooser; |
19 | 19 | import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; |
20 | 20 | import edu.wpi.first.wpilibj2.command.Command; |
21 | 21 | import edu.wpi.first.wpilibj2.command.Commands; |
|
45 | 45 | public class RobotContainer { |
46 | 46 |
|
47 | 47 | @NotLogged |
48 | | - SendableChooser<Command> autoChooser = new SendableChooser<>(); |
| 48 | + AutoChooser autoChooser = new AutoChooser(); |
49 | 49 |
|
50 | 50 | private AutoFactory autoFactory; |
51 | 51 |
|
@@ -288,12 +288,12 @@ public void configAutos() { |
288 | 288 | CleanAndScore("net_ef", "ef_net", TRY_CLEAN_HIGH), |
289 | 289 | runPath("net_off_startingline").asProxy()); // FORGOT TO DO AS PROXY ON RUNPATH |
290 | 290 |
|
291 | | - autoChooser.setDefaultOption("4 Coral - Processor Side", procSide4Coral); |
292 | | - autoChooser.addOption("4 Coral - Non-Processor Side", nonProcSide4Coral); |
293 | | - autoChooser.addOption("1 Coral - Mid", mid1Coral); |
294 | | - autoChooser.addOption("1 Algae - Mid", midAlgae); |
| 291 | + autoChooser.addCmd("4 Coral - Processor Side", () -> procSide4Coral); |
| 292 | + autoChooser.addCmd("4 Coral - Non-Processor Side", () -> nonProcSide4Coral); |
| 293 | + autoChooser.addCmd("1 Coral - Mid", () -> mid1Coral); |
| 294 | + autoChooser.addCmd("1 Algae - Mid", () -> midAlgae); |
295 | 295 |
|
296 | | - SmartDashboard.putData(autoChooser); |
| 296 | + SmartDashboard.putData("AutoChooser", autoChooser); |
297 | 297 | } |
298 | 298 |
|
299 | 299 | Command ScoreAndCollect(String startPath, String endPath, Command reef_auto_drive_branch, Command try_prep_coral_l) { |
@@ -417,7 +417,7 @@ private void configDriverBindings() { |
417 | 417 | } |
418 | 418 |
|
419 | 419 | public Command getAutonomousCommand() { |
420 | | - return autoChooser.getSelected(); |
| 420 | + return autoChooser.selectedCommand(); |
421 | 421 |
|
422 | 422 | } |
423 | 423 |
|
@@ -524,12 +524,14 @@ private void configOperatorBindings() { |
524 | 524 | public void configFeedback() { |
525 | 525 | isReadyToScoreReefFeedback |
526 | 526 | .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0))) |
527 | | - .whileTrue(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,constControllers.OPERATOR_RUMBLE))) |
| 527 | + .whileTrue( |
| 528 | + Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE))) |
528 | 529 | .onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0))) |
529 | 530 | .onFalse(Commands.runOnce(() -> subLED.clearAnimation())); |
530 | 531 | isReadyToScoreNetFeedback |
531 | 532 | .onTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0))) |
532 | | - .whileTrue(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,constControllers.OPERATOR_RUMBLE))) |
| 533 | + .whileTrue( |
| 534 | + Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE))) |
533 | 535 | .onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0))) |
534 | 536 | .onFalse(Commands.runOnce(() -> subLED.clearAnimation())); |
535 | 537 | } |
|
0 commit comments