Skip to content
Merged
Show file tree
Hide file tree
Changes from 2 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions src/main/deploy/elastic-layout.json
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,7 @@
"height": 136.0,
"type": "ComboBox Chooser",
"properties": {
"topic": "/SmartDashboard/SendableChooser[1]",
"topic": "/SmartDashboard/AutoChooser[1]",
"period": 0.06,
"sort_options": false
}
Expand All @@ -225,7 +225,7 @@
"height": 136.0,
"type": "Large Text Display",
"properties": {
"topic": "/SmartDashboard/SendableChooser[1]/active",
"topic": "/SmartDashboard/AutoChooser[1]/active",
"period": 0.06,
"data_type": "string"
}
Expand Down
20 changes: 11 additions & 9 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,13 @@

import com.frcteam3255.joystick.SN_XboxController;

import choreo.auto.AutoChooser;
import choreo.auto.AutoFactory;
import edu.wpi.first.epilogue.Logged;
import edu.wpi.first.epilogue.NotLogged;
import edu.wpi.first.math.geometry.Pose2d;
import edu.wpi.first.wpilibj.GenericHID.RumbleType;
import edu.wpi.first.wpilibj.RobotController;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
Expand Down Expand Up @@ -45,7 +45,7 @@
public class RobotContainer {

@NotLogged
SendableChooser<Command> autoChooser = new SendableChooser<>();
AutoChooser autoChooser = new AutoChooser();

private AutoFactory autoFactory;

Expand Down Expand Up @@ -288,10 +288,10 @@ public void configAutos() {
CleanAndScore("net_ef", "ef_net", TRY_CLEAN_HIGH),
runPath("net_off_startingline").asProxy()); // FORGOT TO DO AS PROXY ON RUNPATH

autoChooser.setDefaultOption("4 Coral - Processor Side", procSide4Coral);
autoChooser.addOption("4 Coral - Non-Processor Side", nonProcSide4Coral);
autoChooser.addOption("1 Coral - Mid", mid1Coral);
autoChooser.addOption("1 Algae - Mid", midAlgae);
autoChooser.addCmd("4 Coral - Processor Side", () -> procSide4Coral);
autoChooser.addCmd("4 Coral - Non-Processor Side", () -> nonProcSide4Coral);
autoChooser.addCmd("1 Coral - Mid", () -> mid1Coral);
autoChooser.addCmd("1 Algae - Mid", () -> midAlgae);

SmartDashboard.putData(autoChooser);
}
Expand Down Expand Up @@ -417,7 +417,7 @@ private void configDriverBindings() {
}

public Command getAutonomousCommand() {
return autoChooser.getSelected();
return autoChooser.selectedCommand();

}

Expand Down Expand Up @@ -524,12 +524,14 @@ private void configOperatorBindings() {
public void configFeedback() {
isReadyToScoreReefFeedback
.onTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0)))
.whileTrue(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,constControllers.OPERATOR_RUMBLE)))
.whileTrue(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE)))
.onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0)))
.onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
isReadyToScoreNetFeedback
.whileTrue(Commands.runOnce(() -> subLED.setLED(constLED.READY_TO_SHOOT_ANIMATION, 0)))
.whileTrue(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble,constControllers.OPERATOR_RUMBLE)))
.whileTrue(
Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, constControllers.OPERATOR_RUMBLE)))
.onFalse(Commands.runOnce(() -> conOperator.setRumble(RumbleType.kBothRumble, 0)))
.onFalse(Commands.runOnce(() -> subLED.clearAnimation()));
}
Expand Down