Choosing an Autonomous Program

Often teams have more than one autonomous program, either for competitive reasons or for testing new software. Programs often vary by adding things like time delays, different strategies, etc. The methods to choose the strategy to run usually involves switches, joystick buttons, knobs or other hardware based inputs.

With the SmartDashboard you can simply display a widget on the screen to choose the autonomous program that you would like to run. And with command based programs, that program is encapsulated in one of several commands. This article shows how to select an autonomous program with only a few lines of code and a nice looking user interface, with examples for both TimedRobot and Command-Based Robots.

TimedRobot

Note

The code snippets shown below are part of the TimedRobot template (Java, C++):

Creating SendableChooser Object

In Robot.java / Robot.h, create a variable to hold a reference to a SendableChooser object. Two or more auto modes can be added by creating strings to send to the chooser. Using the SendableChooser, one can choose between them. In this example, Default and My Auto are shown as options. You will also need a variable to store which auto has been chosen, m_autoSelected.

  private static final String kDefaultAuto = "Default";
  private static final String kCustomAuto = "My Auto";
  private String m_autoSelected;
  private final SendableChooser<String> m_chooser = new SendableChooser<>();
  frc::SendableChooser<std::string> m_chooser;
  const std::string kAutoNameDefault = "Default";
  const std::string kAutoNameCustom = "My Auto";
  std::string m_autoSelected;
import wpilib
self.defaultAuto = "Default"
self.customAuto = "My Auto";
self.chooser = wpilib.SendableChooser()

Setting Up Options

The chooser allows you to pick from a list of defined elements, in this case the strings we defined above. In the Robot constructor, add your options created as strings above using setDefaultOption or addOption. setDefaultOption will be the one selected by default when the dashboard starts. The putData function will push it to the dashboard on your driver station computer.

  public Robot() {
    m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
    m_chooser.addOption("My Auto", kCustomAuto);
    SmartDashboard.putData("Auto choices", m_chooser);
  }
Robot::Robot() {
  m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
  m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
  frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
from wpilib import SmartDashboard
self.chooser.setDefaultOption("Default Auto", self.defaultAuto)
self.chooser.addOption("My Auto", self.customAuto)
SmartDashboard.putData("Auto choices", self.chooser)

Running Autonomous Code

Now, in autonomousInit and autonomousPeriodic, you can use the m_autoSelected variable to read which option was chosen, and change what happens during the autonomous period.

  @Override
  public void autonomousInit() {
    m_autoSelected = m_chooser.getSelected();
    System.out.println("Auto selected: " + m_autoSelected);
  }

  /** This function is called periodically during autonomous. */
  @Override
  public void autonomousPeriodic() {
    switch (m_autoSelected) {
      case kCustomAuto:
        // Put custom auto code here
        break;
      case kDefaultAuto:
      default:
        // Put default auto code here
        break;
    }
  }
void Robot::AutonomousInit() {
  m_autoSelected = m_chooser.GetSelected();
  wpi::print("Auto selected: {}\n", m_autoSelected);

  if (m_autoSelected == kAutoNameCustom) {
    // Custom Auto goes here
  } else {
    // Default Auto goes here
  }
}

void Robot::AutonomousPeriodic() {
  if (m_autoSelected == kAutoNameCustom) {
    // Custom Auto goes here
  } else {
    // Default Auto goes here
  }
}
def autonomousInit(self):
   self.autoSelected = self.chooser.getSelected()
   print("Auto selected: " + self.autoSelected)
def autonomousPeriodic(self):
   match self.autoSelected:
      case self.customAuto:
         # Put custom auto code here
      case _:
         # Put default auto code here

Command-Based

Note

The code snippets shown below are part of the HatchbotTraditional example project (Java, C++, Python):

Creating the SendableChooser Object

In RobotContainer, create a variable to hold a reference to a SendableChooser object. Two or more commands can be created and stored in new variables. Using the SendableChooser, one can choose between them. In this example, SimpleAuto and ComplexAuto are shown as options.

  // A simple auto routine that drives forward a specified distance, and then stops.
  private final Command m_simpleAuto =
      new DriveDistance(
          AutoConstants.kAutoDriveDistanceInches, AutoConstants.kAutoDriveSpeed, m_robotDrive);

  // A complex auto routine that drives forward, drops a hatch, and then drives backward.
  private final Command m_complexAuto = new ComplexAuto(m_robotDrive, m_hatchSubsystem);

  // A chooser for autonomous commands
  SendableChooser<Command> m_chooser = new SendableChooser<>();
  // The autonomous routines
  DriveDistance m_simpleAuto{AutoConstants::kAutoDriveDistanceInches,
                             AutoConstants::kAutoDriveSpeed, &m_drive};
  ComplexAuto m_complexAuto{&m_drive, &m_hatch};

  // The chooser for the autonomous routines
  frc::SendableChooser<frc2::Command*> m_chooser;
  // The autonomous routines
  frc2::CommandPtr m_simpleAuto = autos::SimpleAuto(&m_drive);
  frc2::CommandPtr m_complexAuto = autos::ComplexAuto(&m_drive, &m_hatch);

  // The chooser for the autonomous routines
  frc::SendableChooser<frc2::Command*> m_chooser;
        # A simple auto routine that drives forward a specified distance, and then stops.
        self.simpleAuto = DriveDistance(
            constants.kAutoDriveDistanceInches, constants.kAutoDriveSpeed, self.drive
        )

        # A complex auto routine that drives forward, drops a hatch, and then drives backward.
        self.complexAuto = ComplexAuto(self.drive, self.hatch)

        # Chooser
        self.chooser = wpilib.SendableChooser()

Setting up SendableChooser

Imagine that you have two autonomous programs to choose between and they are encapsulated in commands SimpleAuto and ComplexAuto. To choose between them:

In RobotContainer, create a SendableChooser object and add instances of the two commands to it. There can be any number of commands, and the one added as a default (setDefaultOption), becomes the one that is initially selected. Notice that each command is included in an setDefaultOption() or addOption() method call on the SendableChooser instance.

    // Add commands to the autonomous command chooser
    m_chooser.setDefaultOption("Simple Auto", m_simpleAuto);
    m_chooser.addOption("Complex Auto", m_complexAuto);
  // Add commands to the autonomous command chooser
  m_chooser.SetDefaultOption("Simple Auto", &m_simpleAuto);
  m_chooser.AddOption("Complex Auto", &m_complexAuto);
  // Add commands to the autonomous command chooser
  // Note that we do *not* move ownership into the chooser
  m_chooser.SetDefaultOption("Simple Auto", m_simpleAuto.get());
  m_chooser.AddOption("Complex Auto", m_complexAuto.get());
        # Add commands to the autonomous command chooser
        self.chooser.setDefaultOption("Simple Auto", self.simpleAuto)
        self.chooser.addOption("Complex Auto", self.complexAuto)

Then, publish the chooser to the dashboard:

// Put the chooser on the dashboard
SmartDashboard.putData(m_chooser);
// Put the chooser on the dashboard
frc::SmartDashboard::PutData(&m_chooser);
from wpilib import SmartDashboard
# Put the chooser on the dashboard
SmartDashboard.putData(chooser)

Starting an Autonomous Command

In Robot.java, when the autonomous period starts, the SendableChooser object is polled to get the selected command and that command must be scheduled.

  public Command getAutonomousCommand() {
    return m_chooser.getSelected();
  }
  public void autonomousInit() {
    m_autonomousCommand = m_robotContainer.getAutonomousCommand();

    // schedule the autonomous command (example)
    if (m_autonomousCommand != null) {
      m_autonomousCommand.schedule();
    }
  }
frc2::Command* RobotContainer::GetAutonomousCommand() {
  // Runs the chosen command in autonomous
  return m_chooser.GetSelected();
}
void Robot::AutonomousInit() {
  m_autonomousCommand = m_container.GetAutonomousCommand();

  if (m_autonomousCommand != nullptr) {
    m_autonomousCommand->Schedule();
  }
}
    def getAutonomousCommand(self) -> commands2.Command:
        return self.chooser.getSelected()
    def autonomousInit(self) -> None:
        """This autonomous runs the autonomous command selected by your RobotContainer class."""
        self.autonomousCommand = self.container.getAutonomousCommand()

        if self.autonomousCommand:
            self.autonomousCommand.schedule()

Running the Scheduler during Autonomous

In Robot.java, this will run the scheduler every driver station update period (about every 20ms) and cause the selected autonomous command to run. In Python the scheduler runs automatically when TimedCommandRobot is used.

Note

Running the scheduler can occur in the autonomousPeriodic() function or robotPeriodic(), both will function similarly in autonomous mode.

49  @Override
50  public void robotPeriodic() {
51    CommandScheduler.getInstance().run();
52  }
29void Robot::RobotPeriodic() {
30  frc2::CommandScheduler::GetInstance().Run();
31}

Canceling the Autonomous Command

In Robot.java, when the teleop period begins, the autonomous command will be canceled.

87  @Override
88  public void teleopInit() {
89    // This makes sure that the autonomous stops running when
90    // teleop starts running. If you want the autonomous to
91    // continue until interrupted by another command, remove
92    // this line or comment it out.
93    if (m_autonomousCommand != null) {
94      m_autonomousCommand.cancel();
95    }
96  }
56void Robot::TeleopInit() {
57  // This makes sure that the autonomous stops running when
58  // teleop starts running. If you want the autonomous to
59  // continue until interrupted by another command, remove
60  // this line or comment it out.
61  if (m_autonomousCommand != nullptr) {
62    m_autonomousCommand->Cancel();
63    m_autonomousCommand = nullptr;
64  }
65}
51    def teleopInit(self) -> None:
52        # This makes sure that the autonomous stops running when
53        # teleop starts running. If you want the autonomous to
54        # continue until interrupted by another command, remove
55        # this line or comment it out.
56        if self.autonomousCommand:
57            self.autonomousCommand.cancel()

SmartDashboard Display

SendableChooser shows two selectable autos: Simple Auto and Complex Auto.

When the SmartDashboard is run, the choices from the SendableChooser are automatically displayed. You can simply pick an option before the autonomous period begins and the corresponding command will run.