Improved Command-based examples (#906)

Robot.cpp has been split into header-source pairs and the Command-based
examples now define an example subsystem in the Robot class.
This commit is contained in:
Tyler Veness
2018-03-05 22:06:40 -08:00
committed by Peter Johnson
parent 14228d82f3
commit 96e9a6989c
12 changed files with 368 additions and 296 deletions

View File

@@ -7,9 +7,11 @@
#include "ExampleCommand.h"
#include "../Robot.h"
ExampleCommand::ExampleCommand() {
// Use Requires() here to declare subsystem dependencies
// eg. Requires(&Robot::chassis);
Requires(&Robot::m_subsystem);
}
// Called just before this Command runs the first time

View File

@@ -7,9 +7,11 @@
#include "MyAutoCommand.h"
#include "../Robot.h"
MyAutoCommand::MyAutoCommand() {
// Use Requires() here to declare subsystem dependencies
// eg. Requires(&Robot::chassis);
Requires(&Robot::m_subsystem);
}
// Called just before this Command runs the first time

View File

@@ -5,93 +5,77 @@
/* the project. */
/*----------------------------------------------------------------------------*/
#include <Commands/Command.h>
#include "Robot.h"
#include <Commands/Scheduler.h>
#include <LiveWindow/LiveWindow.h>
#include <SmartDashboard/SendableChooser.h>
#include <SmartDashboard/SmartDashboard.h>
#include <TimedRobot.h>
#include "Commands/ExampleCommand.h"
#include "Commands/MyAutoCommand.h"
ExampleSubsystem Robot::m_subsystem;
OI Robot::m_oi;
class Robot : public frc::TimedRobot {
public:
void RobotInit() override {
m_chooser.AddDefault("Default Auto", &m_defaultAuto);
m_chooser.AddObject("My Auto", &m_myAuto);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
void Robot::RobotInit() {
m_chooser.AddDefault("Default Auto", &m_defaultAuto);
m_chooser.AddObject("My Auto", &m_myAuto);
frc::SmartDashboard::PutData("Auto Modes", &m_chooser);
}
/**
* This function is called once each time the robot enters Disabled mode. You
* can use it to reset any subsystem information you want to clear when the
* robot is disabled.
*/
void Robot::DisabledInit() {}
void Robot::DisabledPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
/**
* This autonomous (along with the chooser code above) shows how to select
* between different autonomous modes using the dashboard. The sendable chooser
* code works with the Java SmartDashboard. If you prefer the LabVIEW Dashboard,
* remove all of the chooser code and uncomment the GetString code to get the
* auto name from the text box below the Gyro.
*
* You can add additional auto modes by adding additional commands to the
* chooser code above (like the commented example) or additional comparisons to
* the if-else structure below with additional strings & commands.
*/
void Robot::AutonomousInit() {
// std::string autoSelected = frc::SmartDashboard::GetString(
// "Auto Selector", "Default");
// if (autoSelected == "My Auto") {
// m_autonomousCommand = &m_myAuto;
// } else {
// m_autonomousCommand = &m_defaultAuto;
// }
m_autonomousCommand = m_chooser.GetSelected();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Start();
}
}
/**
* This function is called once each time the robot enters Disabled
* mode.
* You can use it to reset any subsystem information you want to clear
* when
* the robot is disabled.
*/
void DisabledInit() override {}
void Robot::AutonomousPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
void DisabledPeriodic() override {
frc::Scheduler::GetInstance()->Run();
void Robot::TeleopInit() {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
/**
* This autonomous (along with the chooser code above) shows how to
* select
* between different autonomous modes using the dashboard. The sendable
* chooser code works with the Java SmartDashboard. If you prefer the
* LabVIEW Dashboard, remove all of the chooser code and uncomment the
* GetString code to get the auto name from the text box below the Gyro.
*
* You can add additional auto modes by adding additional commands to
* the
* chooser code above (like the commented example) or additional
* comparisons
* to the if-else structure below with additional strings & commands.
*/
void AutonomousInit() override {
std::string autoSelected = frc::SmartDashboard::GetString(
"Auto Selector", "Default");
if (autoSelected == "My Auto") {
m_autonomousCommand = &m_myAuto;
} else {
m_autonomousCommand = &m_defaultAuto;
}
void Robot::TeleopPeriodic() {
frc::Scheduler::GetInstance()->Run();
}
m_autonomousCommand = m_chooser.GetSelected();
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Start();
}
}
void AutonomousPeriodic() override {
frc::Scheduler::GetInstance()->Run();
}
void TeleopInit() override {
// This makes sure that the autonomous stops running when
// teleop starts running. If you want the autonomous to
// continue until interrupted by another command, remove
// this line or comment it out.
if (m_autonomousCommand != nullptr) {
m_autonomousCommand->Cancel();
m_autonomousCommand = nullptr;
}
}
void TeleopPeriodic() override { frc::Scheduler::GetInstance()->Run(); }
void TestPeriodic() override {}
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc::Command* m_autonomousCommand = nullptr;
ExampleCommand m_defaultAuto;
MyAutoCommand m_myAuto;
frc::SendableChooser<frc::Command*> m_chooser;
};
void Robot::TestPeriodic() {}
START_ROBOT_CLASS(Robot)

View File

@@ -0,0 +1,40 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2017-2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/
#pragma once
#include <Commands/Command.h>
#include <SmartDashboard/SendableChooser.h>
#include <TimedRobot.h>
#include "Commands/ExampleCommand.h"
#include "Commands/MyAutoCommand.h"
#include "OI.h"
#include "Subsystems/ExampleSubsystem.h"
class Robot : public frc::TimedRobot {
public:
static ExampleSubsystem m_subsystem;
static OI m_oi;
void RobotInit() override;
void DisabledInit() override;
void DisabledPeriodic() override;
void AutonomousInit() override;
void AutonomousPeriodic() override;
void TeleopInit() override;
void TeleopPeriodic() override;
void TestPeriodic() override;
private:
// Have it null by default so that if testing teleop it
// doesn't have undefined behavior and potentially crash.
frc::Command* m_autonomousCommand = nullptr;
ExampleCommand m_defaultAuto;
MyAutoCommand m_myAuto;
frc::SendableChooser<frc::Command*> m_chooser;
};