[examples] Renovate command-based examples (#4409)

Refactor some examples to use newer features, such as HID factories, library-provided command factories, CommandPtr (C++), as well as new idioms such as static/instance command factories.
This commit is contained in:
Starlight220
2022-11-28 18:55:13 +02:00
committed by GitHub
parent 1a59737f40
commit 20dbae0cee
26 changed files with 401 additions and 417 deletions

View File

@@ -7,10 +7,11 @@
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/angle.h>
namespace ac = AutoConstants;
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
@@ -18,7 +19,7 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
@@ -30,32 +31,29 @@ void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(2_rad);
m_arm.Enable();
},
{&m_arm}));
m_driverController.A().OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(2_rad);
m_arm.Enable();
},
{&m_arm}));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(ArmConstants::kArmOffset);
m_arm.Enable();
},
{&m_arm}));
m_driverController.B().OnTrue(frc2::cmd::RunOnce(
[this] {
m_arm.SetGoal(ArmConstants::kArmOffset);
m_arm.Enable();
},
{&m_arm}));
// Disable the arm controller when Y is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kY)
.OnTrue(frc2::cmd::RunOnce([this] { m_arm.Disable(); }, {&m_arm}));
m_driverController.Y().OnTrue(
frc2::cmd::RunOnce([this] { m_arm.Disable(); }, {&m_arm}));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
m_driverController.RightBumper()
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }));
}
void RobotContainer::DisablePIDSubsystems() {
@@ -63,6 +61,5 @@ void RobotContainer::DisablePIDSubsystems() {
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return new frc2::InstantCommand([] {});
return nullptr;
}

View File

@@ -4,16 +4,13 @@
#pragma once
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/button/CommandXboxController.h>
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"
#include "subsystems/DriveSubsystem.h"
namespace ac = AutoConstants;
/**
* This class is where the bulk of the robot should be declared. Since
* Command-based is a "declarative" paradigm, very little robot logic should
@@ -35,7 +32,8 @@ class RobotContainer {
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
frc2::CommandXboxController m_driverController{
OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
@@ -43,7 +41,5 @@ class RobotContainer {
DriveSubsystem m_drive;
ArmSubsystem m_arm;
// The chooser for the autonomous routines
void ConfigureButtonBindings();
};

View File

@@ -4,11 +4,6 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/button/JoystickButton.h>
#include <units/angle.h>
RobotContainer::RobotContainer() {
@@ -18,34 +13,27 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
},
{&m_drive}));
m_drive.SetDefaultCommand(m_drive.ArcadeDriveCommand(
[this] { return -m_driverController.GetLeftY(); },
[this] { return m_driverController.GetRightX(); }));
}
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.OnTrue(frc2::cmd::RunOnce([this] { m_arm.SetGoal(2_rad); }, {&m_arm}));
m_driverController.A().OnTrue(m_arm.SetArmGoalCommand(2_rad));
// Move the arm to neutral position when the 'B' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.OnTrue(frc2::cmd::RunOnce(
[this] { m_arm.SetGoal(ArmConstants::kArmOffset); }, {&m_arm}));
m_driverController.B().OnTrue(
m_arm.SetArmGoalCommand(ArmConstants::kArmOffset));
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }));
m_driverController.RightBumper()
.OnTrue(m_drive.SetMaxOutputCommand(0.5))
.OnFalse(m_drive.SetMaxOutputCommand(1.0));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return new frc2::InstantCommand([] {});
return nullptr;
}

View File

@@ -25,3 +25,7 @@ void ArmSubsystem::UseState(State setpoint) {
m_motor.SetSetpoint(ExampleSmartMotorController::PIDMode::kPosition,
setpoint.position.value(), feedforward / 12_V);
}
frc2::CommandPtr ArmSubsystem::SetArmGoalCommand(units::radian_t goal) {
return frc2::cmd::RunOnce([this, goal] { this->SetGoal(goal); }, {this});
}

View File

@@ -26,10 +26,6 @@ void DriveSubsystem::Periodic() {
// Implementation of subsystem periodic method goes here.
}
void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
m_drive.ArcadeDrive(fwd, rot);
}
void DriveSubsystem::ResetEncoders() {
m_leftEncoder.Reset();
m_rightEncoder.Reset();
@@ -47,6 +43,16 @@ frc::Encoder& DriveSubsystem::GetRightEncoder() {
return m_rightEncoder;
}
void DriveSubsystem::SetMaxOutput(double maxOutput) {
m_drive.SetMaxOutput(maxOutput);
frc2::CommandPtr DriveSubsystem::SetMaxOutputCommand(double maxOutput) {
return frc2::cmd::RunOnce(
[this, maxOutput] { m_drive.SetMaxOutput(maxOutput); });
}
frc2::CommandPtr DriveSubsystem::ArcadeDriveCommand(
std::function<double()> fwd, std::function<double()> rot) {
return frc2::cmd::Run(
[this, fwd = std::move(fwd), rot = std::move(rot)] {
m_drive.ArcadeDrive(fwd(), rot());
},
{this});
}

View File

@@ -4,9 +4,8 @@
#pragma once
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/button/CommandXboxController.h>
#include "Constants.h"
#include "subsystems/ArmSubsystem.h"
@@ -29,7 +28,8 @@ class RobotContainer {
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
frc2::CommandXboxController m_driverController{
OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
@@ -37,7 +37,5 @@ class RobotContainer {
DriveSubsystem m_drive;
ArmSubsystem m_arm;
// The chooser for the autonomous routines
void ConfigureButtonBindings();
};

View File

@@ -5,6 +5,7 @@
#pragma once
#include <frc/controller/ArmFeedforward.h>
#include <frc2/command/Commands.h>
#include <frc2/command/TrapezoidProfileSubsystem.h>
#include <units/angle.h>
@@ -21,6 +22,8 @@ class ArmSubsystem : public frc2::TrapezoidProfileSubsystem<units::radians> {
void UseState(State setpoint) override;
frc2::CommandPtr SetArmGoalCommand(units::radian_t goal);
private:
ExampleSmartMotorController m_motor;
frc::ArmFeedforward m_feedforward;

View File

@@ -4,10 +4,13 @@
#pragma once
#include <functional>
#include <frc/Encoder.h>
#include <frc/drive/DifferentialDrive.h>
#include <frc/motorcontrol/MotorControllerGroup.h>
#include <frc/motorcontrol/PWMSparkMax.h>
#include <frc2/command/Commands.h>
#include <frc2/command/SubsystemBase.h>
#include "Constants.h"
@@ -23,14 +26,6 @@ class DriveSubsystem : public frc2::SubsystemBase {
// Subsystem methods go here.
/**
* Drives the robot using arcade controls.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
*/
void ArcadeDrive(double fwd, double rot);
/**
* Resets the drive encoders to currently read a position of 0.
*/
@@ -63,7 +58,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
void SetMaxOutput(double maxOutput);
frc2::CommandPtr SetMaxOutputCommand(double maxOutput);
frc2::CommandPtr ArcadeDriveCommand(std::function<double()> fwd,
std::function<double()> rot);
private:
// Components (e.g. motor controllers and sensors) should generally be

View File

@@ -4,10 +4,6 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/JoystickButton.h>
#include "commands/DriveDistanceProfiled.h"
RobotContainer::RobotContainer() {
@@ -29,39 +25,38 @@ void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
m_driverController.RightBumper()
.OnTrue(m_driveHalfSpeed.get())
.OnFalse(m_driveFullSpeed.get());
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of
// 10 seconds
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.OnTrue(DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
m_driverController.A().OnTrue(
DriveDistanceProfiled(3_m, &m_drive).WithTimeout(10_s));
// Do the same thing as above when the 'B' button is pressed, but defined
// inline
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.OnTrue(
frc2::TrapezoidProfileCommand<units::meters>(
frc::TrapezoidProfile<units::meters>(
// Limit the max acceleration and velocity
{DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration},
// End at desired position in meters; implicitly starts at 0
{3_m, 0_mps}),
// Pipe the profile state to the drive
[this](auto setpointState) {
m_drive.SetDriveStates(setpointState, setpointState);
},
// Require the drive
{&m_drive})
.ToPtr()
.BeforeStarting(
frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
.WithTimeout(10_s));
m_driverController.B().OnTrue(
frc2::TrapezoidProfileCommand<units::meters>(
frc::TrapezoidProfile<units::meters>(
// Limit the max acceleration and velocity
{DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration},
// End at desired position in meters; implicitly starts at 0
{3_m, 0_mps}),
// Pipe the profile state to the drive
[this](auto setpointState) {
m_drive.SetDriveStates(setpointState, setpointState);
},
// Require the drive
{&m_drive})
// Convert to CommandPtr
.ToPtr()
.BeforeStarting(
frc2::cmd::RunOnce([this]() { m_drive.ResetEncoders(); }, {}))
.WithTimeout(10_s));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {
// Runs the chosen command in autonomous
return new frc2::InstantCommand([] {});
return nullptr;
}

View File

@@ -4,14 +4,10 @@
#pragma once
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/StartEndCommand.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/CommandXboxController.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
@@ -31,17 +27,19 @@ class RobotContainer {
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
frc2::CommandXboxController m_driverController{
OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
// The robot's subsystems
DriveSubsystem m_drive;
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// RobotContainer-owned commands
frc2::CommandPtr m_driveHalfSpeed =
frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {});
frc2::CommandPtr m_driveFullSpeed =
frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {});
void ConfigureButtonBindings();
};

View File

@@ -4,9 +4,6 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/button/JoystickButton.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
@@ -14,7 +11,7 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
@@ -25,24 +22,42 @@ RobotContainer::RobotContainer() {
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// We can bind commands while keeping their ownership in RobotContainer
// Spin up the shooter when the 'A' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
.OnTrue(&m_spinUpShooter);
m_driverController.A().OnTrue(m_spinUpShooter.get());
// Turn off the shooter when the 'B' button is pressed
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
.OnTrue(&m_stopShooter);
m_driverController.B().OnTrue(m_stopShooter.get());
// Shoot when the 'X' button is held
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kX)
.OnTrue(&m_shoot)
.OnFalse(&m_stopFeeder);
// We can also *move* command ownership to the scheduler
// Note that we won't be able to access these commands after moving them!
// Shoots if the shooter wheel has reached the target speed
frc2::CommandPtr shoot = frc2::cmd::Either(
// Run the feeder
frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
// Do nothing
frc2::cmd::None(),
// Determine which of the above to do based on whether the shooter has
// reached the desired speed
[this] { return m_shooter.AtSetpoint(); });
frc2::CommandPtr stopFeeder =
frc2::cmd::RunOnce([this] { m_shooter.StopFeeder(); }, {&m_shooter});
// Shoot when the 'X' button is pressed
m_driverController.X()
.OnTrue(std::move(shoot))
.OnFalse(std::move(stopFeeder));
// We can also define commands inline at the binding!
// (ownership will be passed to the scheduler)
// While holding the shoulder button, drive at half speed
frc2::JoystickButton(&m_driverController,
frc::XboxController::Button::kRightBumper)
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
m_driverController.RightBumper()
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {}));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -4,16 +4,10 @@
#pragma once
#include <frc/XboxController.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/ConditionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/WaitCommand.h>
#include <frc2/command/WaitUntilCommand.h>
#include <frc2/command/CommandPtr.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/CommandXboxController.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
@@ -32,65 +26,47 @@ class RobotContainer {
public:
RobotContainer();
// The chooser for the autonomous routines
frc2::Command* GetAutonomousCommand();
private:
// The driver's controller
frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
frc2::CommandXboxController m_driverController{
OIConstants::kDriverControllerPort};
// The robot's subsystems
DriveSubsystem m_drive;
ShooterSubsystem m_shooter;
// A simple autonomous routine that shoots the loaded frisbees
// RobotContainer-owned commands
// (These variables will still be valid after binding, because we don't move
// ownership)
frc2::CommandPtr m_spinUpShooter =
frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter});
frc2::CommandPtr m_stopShooter =
frc2::cmd::RunOnce([this] { m_shooter.Disable(); }, {&m_shooter});
// An autonomous routine that shoots the loaded frisbees
frc2::CommandPtr m_autonomousCommand =
frc2::SequentialCommandGroup{
frc2::cmd::Sequence(
// Start the command by spinning up the shooter...
frc2::InstantCommand([this] { m_shooter.Enable(); }, {&m_shooter}),
frc2::cmd::RunOnce([this] { m_shooter.Enable(); }, {&m_shooter}),
// Wait until the shooter is at speed before feeding the frisbees
frc2::WaitUntilCommand([this] { return m_shooter.AtSetpoint(); }),
frc2::cmd::WaitUntil([this] { return m_shooter.AtSetpoint(); }),
// Start running the feeder
frc2::InstantCommand([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
frc2::cmd::RunOnce([this] { m_shooter.RunFeeder(); }, {&m_shooter}),
// Shoot for the specified time
frc2::WaitCommand(ac::kAutoShootTimeSeconds)}
frc2::cmd::Wait(ac::kAutoShootTimeSeconds))
// Add a timeout (will end the command if, for instance, the shooter
// never gets up to speed)
.WithTimeout(ac::kAutoTimeoutSeconds)
// When the command ends, turn off the shooter and the feeder
.AndThen([this] {
.AndThen(frc2::cmd::RunOnce([this] {
m_shooter.Disable();
m_shooter.StopFeeder();
});
// Assorted commands to be bound to buttons
frc2::InstantCommand m_spinUpShooter{[this] { m_shooter.Enable(); },
{&m_shooter}};
frc2::InstantCommand m_stopShooter{[this] { m_shooter.Disable(); },
{&m_shooter}};
// Shoots if the shooter wheel has reached the target speed
frc2::ConditionalCommand m_shoot{
// Run the feeder
frc2::InstantCommand{[this] { m_shooter.RunFeeder(); }, {&m_shooter}},
// Do nothing
frc2::InstantCommand(),
// Determine which of the above to do based on whether the shooter has
// reached the desired speed
[this] { return m_shooter.AtSetpoint(); }};
frc2::InstantCommand m_stopFeeder{[this] { m_shooter.StopFeeder(); },
{&m_shooter}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
// The chooser for the autonomous routines
}));
void ConfigureButtonBindings();
};

View File

@@ -5,14 +5,14 @@
#include "RobotContainer.h"
#include <frc/shuffleboard/Shuffleboard.h>
#include <frc2/command/button/JoystickButton.h>
RobotContainer::RobotContainer() {
// Initialize all of your commands and subsystems here
// Add commands to the autonomous command chooser
m_chooser.SetDefaultOption("Simple Auto", &m_simpleAuto);
m_chooser.AddOption("Complex Auto", &m_complexAuto);
// 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());
// Put the chooser on the dashboard
frc::Shuffleboard::GetTab("Autonomous").Add(m_chooser);
@@ -21,7 +21,7 @@ RobotContainer::RobotContainer() {
ConfigureButtonBindings();
// Set up default drive command
m_drive.SetDefaultCommand(frc2::RunCommand(
m_drive.SetDefaultCommand(frc2::cmd::Run(
[this] {
m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
m_driverController.GetRightX());
@@ -33,15 +33,15 @@ void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// Grab the hatch when the 'Circle' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kCircle)
.OnTrue(&m_grabHatch);
m_driverController.Circle().OnTrue(
frc2::cmd::RunOnce([this] { m_hatch.GrabHatch(); }, {&m_hatch}));
// Release the hatch when the 'Square' button is pressed.
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kSquare)
.OnTrue(&m_releaseHatch);
m_driverController.Square().OnTrue(
frc2::cmd::RunOnce([this] { m_hatch.ReleaseHatch(); }, {&m_hatch}));
// While holding R1, drive at half speed
frc2::JoystickButton(&m_driverController, frc::PS4Controller::Button::kR1)
.OnTrue(&m_driveHalfSpeed)
.OnFalse(&m_driveFullSpeed);
m_driverController.R1()
.OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
.OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));
}
frc2::Command* RobotContainer::GetAutonomousCommand() {

View File

@@ -2,16 +2,37 @@
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#include "commands/ComplexAuto.h"
#include "commands/Autos.h"
#include <frc2/command/Commands.h>
#include <frc2/command/FunctionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include "Constants.h"
using namespace AutoConstants;
ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
AddCommands(
frc2::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
return frc2::FunctionalCommand(
// Reset encoders on command start
[drive] { drive->ResetEncoders(); },
// Drive forward while the command is executing
[drive] { drive->ArcadeDrive(AutoConstants::kAutoDriveSpeed, 0); },
// Stop driving at the end of the command
[drive](bool interrupted) { drive->ArcadeDrive(0, 0); },
// End the command when the robot's driven distance exceeds the
// desired value
[drive] {
return drive->GetAverageEncoderDistance() >=
AutoConstants::kAutoDriveDistanceInches;
},
// Requires the drive subsystem
{drive})
.ToPtr();
}
frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
HatchSubsystem* hatch) {
return frc2::cmd::Sequence(
// Drive forward the specified distance
frc2::FunctionalCommand(
// Reset encoders on command start
@@ -27,9 +48,10 @@ ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
kAutoDriveDistanceInches;
},
// Requires the drive subsystem
{drive}),
{drive})
.ToPtr(),
// Release the hatch
frc2::InstantCommand([hatch] { hatch->ReleaseHatch(); }, {hatch}),
frc2::cmd::RunOnce([hatch] { hatch->ReleaseHatch(); }, {hatch}),
// Drive backward the specified distance
// Drive forward the specified distance
frc2::FunctionalCommand(
@@ -46,5 +68,6 @@ ComplexAuto::ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch) {
kAutoBackupDistanceInches;
},
// Requires the drive subsystem
{drive}));
{drive})
.ToPtr());
}

View File

@@ -4,17 +4,13 @@
#pragma once
#include <frc/PS4Controller.h>
#include <frc/smartdashboard/SendableChooser.h>
#include <frc2/command/Command.h>
#include <frc2/command/FunctionalCommand.h>
#include <frc2/command/InstantCommand.h>
#include <frc2/command/ParallelRaceGroup.h>
#include <frc2/command/RunCommand.h>
#include <frc2/command/SequentialCommandGroup.h>
#include <frc2/command/Commands.h>
#include <frc2/command/button/CommandPS4Controller.h>
#include "Constants.h"
#include "commands/ComplexAuto.h"
#include "commands/Autos.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
@@ -35,7 +31,8 @@ class RobotContainer {
private:
// The driver's controller
frc::PS4Controller m_driverController{OIConstants::kDriverControllerPort};
frc2::CommandPS4Controller m_driverController{
OIConstants::kDriverControllerPort};
// The robot's subsystems and commands are defined here...
@@ -43,33 +40,11 @@ class RobotContainer {
DriveSubsystem m_drive;
HatchSubsystem m_hatch;
// Commands owned by RobotContainer
// The autonomous routines
frc2::FunctionalCommand m_simpleAuto = frc2::FunctionalCommand(
// Reset encoders on command start
[this] { m_drive.ResetEncoders(); },
// Drive forward while the command is executing
[this] { m_drive.ArcadeDrive(AutoConstants::kAutoDriveSpeed, 0); },
// Stop driving at the end of the command
[this](bool interrupted) { m_drive.ArcadeDrive(0, 0); },
// End the command when the robot's driven distance exceeds the desired
// value
[this] {
return m_drive.GetAverageEncoderDistance() >=
AutoConstants::kAutoDriveDistanceInches;
},
// Requires the drive subsystem
{&m_drive});
ComplexAuto m_complexAuto{&m_drive, &m_hatch};
// Assorted commands to be bound to buttons
frc2::InstantCommand m_grabHatch{[this] { m_hatch.GrabHatch(); }, {&m_hatch}};
frc2::InstantCommand m_releaseHatch{[this] { m_hatch.ReleaseHatch(); },
{&m_hatch}};
frc2::InstantCommand m_driveHalfSpeed{[this] { m_drive.SetMaxOutput(0.5); },
{}};
frc2::InstantCommand m_driveFullSpeed{[this] { m_drive.SetMaxOutput(1); },
{}};
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;

View File

@@ -0,0 +1,26 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <frc2/command/CommandPtr.h>
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
/** Container for auto command factories. */
namespace autos {
/**
* A simple auto that drives forward, then stops.
*/
frc2::CommandPtr SimpleAuto(DriveSubsystem* drive);
/**
* A complex auto command that drives forward, releases a hatch, and then drives
* backward.
*/
frc2::CommandPtr ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
} // namespace autos

View File

@@ -1,28 +0,0 @@
// Copyright (c) FIRST and other WPILib contributors.
// Open Source Software; you can modify and/or share it under the terms of
// the WPILib BSD license file in the root directory of this project.
#pragma once
#include <frc2/command/CommandHelper.h>
#include <frc2/command/SequentialCommandGroup.h>
#include "Constants.h"
#include "subsystems/DriveSubsystem.h"
#include "subsystems/HatchSubsystem.h"
/**
* A complex auto command that drives forward, releases a hatch, and then drives
* backward.
*/
class ComplexAuto
: public frc2::CommandHelper<frc2::SequentialCommandGroup, ComplexAuto> {
public:
/**
* Creates a new ComplexAuto.
*
* @param drive The drive subsystem this command will run on
* @param hatch The hatch subsystem this command will run on
*/
ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
};

View File

@@ -34,10 +34,8 @@ RobotContainer::RobotContainer() {
void RobotContainer::ConfigureButtonBindings() {
// Configure your button bindings here
// NOTE: Using `new` here will leak these commands if they are ever no longer
// needed. This is usually a non-issue as button-bindings tend to be permanent
// - however, if you wish to avoid this, the commands should be
// stack-allocated and declared as members of RobotContainer.
// NOTE: since we're binding a CommandPtr, command ownership here is moved to
// the scheduler thus, no memory leaks!
// Grab the hatch when the 'A' button is pressed.
frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)