选择自动阶段动程序
出于竞争原因或测试新软件的原因,团队通常拥有多个自动阶段。程序通常会通过添加时间延迟,加入不同的策略等来变化。选择要运行的策略的方法通常包括开关,操纵杆按钮,旋钮或其他基于硬件的输入。
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
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;
Setting Up Options
The chooser allows you to pick from a list of defined elements, in this case the strings we defined above. In robotInit, 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 void robotInit() {
m_chooser.setDefaultOption("Default Auto", kDefaultAuto);
m_chooser.addOption("My Auto", kCustomAuto);
SmartDashboard.putData("Auto choices", m_chooser);
}
void Robot::RobotInit() {
m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault);
m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom);
frc::SmartDashboard::PutData("Auto Modes", &m_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();
fmt::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
}
}
Command-Based
备注
下面显示的代码段是HatchbotTraditional示例项目的一部分(Java <https://github.com/wpilibsuite/allwpilib/tree/main/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional>`__, C++):
创建SendableChooser对象
在“ RobotContainer”中,创建一个变量以保存对“ SendableChooser”对象的引用。可以创建两个或更多命令并将其存储在新变量中。使用“ SendableChooser”,可以在它们之间进行选择。在此示例中,“ SimpleAuto”和“ ComplexAuto”显示为选项。
// 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;
设置SendableChooser
假设你有两个自动阶段的程序可供选择,它们被封装在指令“ SimpleAuto”和“ ComplexAuto”中。在它们当中进行选择:
在“ RobotContainer”中创建一个“ SendableChooser”对象,并向其添加两个指令的实例。指令的数量没有限制,并且默认添加的指令(setDefaultOption)将成为最初选择的命令。注意,每个指令都包含在“ SendableChooser”实例上的“ setDefaultOption()”或“ addOption()”方法调用中。
// 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());
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);
启动自动阶段指令
在“ Robot.java”中,当自动阶段开始时,将选取“ SendableChooser”对象以获取所选指令,并且必须调度该指令。
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();
}
}
在自动阶段运行调度程序
在 “Robot.java” 中,每当机器操控台刷新时(约20ms一次),调度程序将被执行并使得被选择的自动阶段指令持续运行。
备注
运行调度程序可以在autonomousPeriodic()函数或robotPeriodic()中进行,两者在自动阶段下的功能相似。
40 @Override
41 public void robotPeriodic() {
42 CommandScheduler.getInstance().run();
43 }
29void Robot::RobotPeriodic() {
30 frc2::CommandScheduler::GetInstance().Run();
31}
取消自动阶段指令
在 “Robot.java” 当中,当遥控阶段开始时,自动阶段指令将被终止。
78 @Override
79 public void teleopInit() {
80 // This makes sure that the autonomous stops running when
81 // teleop starts running. If you want the autonomous to
82 // continue until interrupted by another command, remove
83 // this line or comment it out.
84 if (m_autonomousCommand != null) {
85 m_autonomousCommand.cancel();
86 }
87 }
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}
SmartDashboard显示

运行SmartDashboard时,将自动显示“ SendableChooser”中的选项。您可以在自动阶段开始之前选择一个选项,然后相应的指令将运行。