[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

@@ -4,15 +4,13 @@
package edu.wpi.first.wpilibj.examples.armbot;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.armbot.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.armbot.subsystems.ArmSubsystem;
import edu.wpi.first.wpilibj.examples.armbot.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
/**
@@ -27,7 +25,8 @@ public class RobotContainer {
private final ArmSubsystem m_robotArm = new ArmSubsystem();
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
CommandXboxController m_driverController =
new CommandXboxController(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -39,7 +38,7 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new RunCommand(
Commands.run(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getLeftY(), m_driverController.getRightX()),
@@ -54,9 +53,10 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
new JoystickButton(m_driverController, Button.kA.value)
m_driverController
.a()
.onTrue(
new InstantCommand(
Commands.runOnce(
() -> {
m_robotArm.setGoal(2);
m_robotArm.enable();
@@ -64,9 +64,10 @@ public class RobotContainer {
m_robotArm));
// Move the arm to neutral position when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
m_driverController
.b()
.onTrue(
new InstantCommand(
Commands.runOnce(
() -> {
m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads);
m_robotArm.enable();
@@ -74,13 +75,13 @@ public class RobotContainer {
m_robotArm));
// Disable the arm controller when Y is pressed.
new JoystickButton(m_driverController, Button.kY.value)
.onTrue(new InstantCommand(m_robotArm::disable));
m_driverController.y().onTrue(Commands.runOnce(m_robotArm::disable));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
.onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
m_driverController
.rightBumper()
.onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1.0)));
}
/**
@@ -97,6 +98,6 @@ public class RobotContainer {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return new InstantCommand();
return Commands.none();
}
}

View File

@@ -4,15 +4,13 @@
package edu.wpi.first.wpilibj.examples.armbotoffboard;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.ArmSubsystem;
import edu.wpi.first.wpilibj.examples.armbotoffboard.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
/**
@@ -27,7 +25,8 @@ public class RobotContainer {
private final ArmSubsystem m_robotArm = new ArmSubsystem();
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
CommandXboxController m_driverController =
new CommandXboxController(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -39,11 +38,8 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new RunCommand(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getLeftY(), m_driverController.getRightX()),
m_robotDrive));
m_robotDrive.arcadeDriveCommand(
() -> -m_driverController.getLeftY(), () -> m_driverController.getRightX()));
}
/**
@@ -54,19 +50,18 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
// Move the arm to 2 radians above horizontal when the 'A' button is pressed.
new JoystickButton(m_driverController, Button.kA.value)
.onTrue(new InstantCommand(() -> m_robotArm.setGoal(2), m_robotArm));
m_driverController.a().onTrue(m_robotArm.setArmGoalCommand(2));
// Move the arm to neutral position when the 'B' button is pressed.
new JoystickButton(m_driverController, Button.kB.value)
.onTrue(
new InstantCommand(
() -> m_robotArm.setGoal(Constants.ArmConstants.kArmOffsetRads), m_robotArm));
m_driverController
.b()
.onTrue(m_robotArm.setArmGoalCommand(Constants.ArmConstants.kArmOffsetRads));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
.onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
m_driverController
.rightBumper()
.onTrue(m_robotDrive.limitOutputCommand(0.5))
.onFalse(m_robotDrive.limitOutputCommand(1));
}
/**
@@ -75,6 +70,6 @@ public class RobotContainer {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return new InstantCommand();
return Commands.none();
}
}

View File

@@ -8,6 +8,8 @@ import edu.wpi.first.math.controller.ArmFeedforward;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.ArmConstants;
import edu.wpi.first.wpilibj.examples.armbotoffboard.ExampleSmartMotorController;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.TrapezoidProfileSubsystem;
/** A robot arm subsystem that moves with a motion profile. */
@@ -36,4 +38,8 @@ public class ArmSubsystem extends TrapezoidProfileSubsystem {
m_motor.setSetpoint(
ExampleSmartMotorController.PIDMode.kPosition, setpoint.position, feedforward / 12.0);
}
public Command setArmGoalCommand(double kArmOffsetRads) {
return Commands.runOnce(() -> setGoal(kArmOffsetRads), this);
}
}

View File

@@ -9,7 +9,10 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.examples.armbotoffboard.Constants.DriveConstants;
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.function.DoubleSupplier;
public class DriveSubsystem extends SubsystemBase {
// The motors on the left side of the drive.
@@ -54,13 +57,14 @@ public class DriveSubsystem extends SubsystemBase {
}
/**
* Drives the robot using arcade controls.
* A split-stick arcade command, with forward/backward controlled by the left hand, and turning
* controlled by the right.
*
* @param fwd the commanded forward movement
* @param rot the commanded rotation
* @param fwd supplier for the commanded forward movement
* @param rot supplier for the commanded rotation
*/
public void arcadeDrive(double fwd, double rot) {
m_drive.arcadeDrive(fwd, rot);
public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) {
return Commands.run(() -> m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble()), this);
}
/** Resets the drive encoders to currently read a position of 0. */
@@ -101,7 +105,7 @@ public class DriveSubsystem extends SubsystemBase {
*
* @param maxOutput the maximum output to which the drive will be constrained
*/
public void setMaxOutput(double maxOutput) {
m_drive.setMaxOutput(maxOutput);
public Command limitOutputCommand(double maxOutput) {
return Commands.runOnce(() -> m_drive.setMaxOutput(maxOutput));
}
}

View File

@@ -4,8 +4,6 @@
package edu.wpi.first.wpilibj.examples.drivedistanceoffboard;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.math.trajectory.TrapezoidProfile;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
@@ -13,10 +11,9 @@ import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.OIConstant
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.commands.DriveDistanceProfiled;
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.TrapezoidProfileCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -28,8 +25,13 @@ public class RobotContainer {
// The robot's subsystems
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
// Retained command references
private final Command m_driveFullSpeed = Commands.runOnce(() -> m_robotDrive.setMaxOutput(1));
private final Command m_driveHalfSpeed = Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5));
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
CommandXboxController m_driverController =
new CommandXboxController(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -41,7 +43,7 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new RunCommand(
Commands.run(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getLeftY(), m_driverController.getRightX()),
@@ -52,15 +54,18 @@ public class RobotContainer {
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* JoystickButton}.
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
*/
private void configureButtonBindings() {
// Drive at half speed when the bumper is held
m_driverController.rightBumper().onTrue(m_driveHalfSpeed).onFalse(m_driveFullSpeed);
// Drive forward by 3 meters when the 'A' button is pressed, with a timeout of 10 seconds
new JoystickButton(m_driverController, Button.kA.value)
.onTrue(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
m_driverController.a().onTrue(new DriveDistanceProfiled(3, m_robotDrive).withTimeout(10));
// Do the same thing as above when the 'B' button is pressed, but defined inline
new JoystickButton(m_driverController, Button.kB.value)
m_driverController
.b()
.onTrue(
new TrapezoidProfileCommand(
new TrapezoidProfile(
@@ -76,11 +81,6 @@ public class RobotContainer {
m_robotDrive)
.beforeStarting(m_robotDrive::resetEncoders)
.withTimeout(10));
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
.onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
}
/**
@@ -89,6 +89,6 @@ public class RobotContainer {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return new InstantCommand();
return Commands.none();
}
}

View File

@@ -4,20 +4,13 @@
package edu.wpi.first.wpilibj.examples.frisbeebot;
import static edu.wpi.first.wpilibj.XboxController.Button;
import edu.wpi.first.wpilibj.XboxController;
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj.examples.frisbeebot.subsystems.ShooterSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.ConditionalCommand;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -30,29 +23,34 @@ public class RobotContainer {
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
private final ShooterSubsystem m_shooter = new ShooterSubsystem();
// A simple autonomous routine that shoots the loaded frisbees
private final Command m_autoCommand =
// Start the command by spinning up the shooter...
new InstantCommand(m_shooter::enable, m_shooter)
.andThen(
private final Command m_spinUpShooter = Commands.runOnce(m_shooter::enable, m_shooter);
private final Command m_stopShooter = Commands.runOnce(m_shooter::disable, m_shooter);
// An autonomous routine that shoots the loaded frisbees
Command m_autonomousCommand =
Commands.sequence(
// Start the command by spinning up the shooter...
Commands.runOnce(m_shooter::enable, m_shooter),
// Wait until the shooter is at speed before feeding the frisbees
new WaitUntilCommand(m_shooter::atSetpoint),
Commands.waitUntil(m_shooter::atSetpoint),
// Start running the feeder
new InstantCommand(m_shooter::runFeeder, m_shooter),
Commands.runOnce(m_shooter::runFeeder, m_shooter),
// Shoot for the specified time
new WaitCommand(AutoConstants.kAutoShootTimeSeconds))
// Add a timeout (will end the command if, for instance, the shooter never gets up to
// speed)
Commands.waitSeconds(AutoConstants.kAutoShootTimeSeconds))
// Add a timeout (will end the command if, for instance, the shooter
// never gets up to speed)
.withTimeout(AutoConstants.kAutoTimeoutSeconds)
// When the command ends, turn off the shooter and the feeder
.andThen(
() -> {
m_shooter.disable();
m_shooter.stopFeeder();
});
Commands.runOnce(
() -> {
m_shooter.disable();
m_shooter.stopFeeder();
}));
// The driver's controller
XboxController m_driverController = new XboxController(OIConstants.kDriverControllerPort);
CommandXboxController m_driverController =
new CommandXboxController(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -64,7 +62,7 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new RunCommand(
Commands.run(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getLeftY(), m_driverController.getRightX()),
@@ -72,37 +70,47 @@ public class RobotContainer {
}
/**
* Use this method to define your button->command mappings. Buttons can be created by
* instantiating a {@link edu.wpi.first.wpilibj.GenericHID} or one of its subclasses ({@link
* edu.wpi.first.wpilibj.Joystick} or {@link XboxController}), and then passing it to a {@link
* edu.wpi.first.wpilibj2.command.button.JoystickButton}.
* Use this method to define your button->command mappings. Buttons can be created via the button
* factories on {@link edu.wpi.first.wpilibj2.command.button.CommandGenericHID} or one of its
* subclasses ({@link edu.wpi.first.wpilibj2.command.button.CommandJoystick} or {@link
* CommandXboxController}).
*/
private void configureButtonBindings() {
// Configure your button bindings here
// We can bind commands while retaining references to them in RobotContainer
// Spin up the shooter when the 'A' button is pressed
new JoystickButton(m_driverController, Button.kA.value)
.onTrue(new InstantCommand(m_shooter::enable, m_shooter));
m_driverController.a().onTrue(m_spinUpShooter);
// Turn off the shooter when the 'B' button is pressed
new JoystickButton(m_driverController, Button.kB.value)
.onTrue(new InstantCommand(m_shooter::disable, m_shooter));
m_driverController.b().onTrue(m_stopShooter);
// Run the feeder when the 'X' button is held, but only if the shooter is at speed
new JoystickButton(m_driverController, Button.kX.value)
.onTrue(
new ConditionalCommand(
// Run the feeder
new InstantCommand(m_shooter::runFeeder, m_shooter),
// Do nothing
new InstantCommand(),
// Determine which of the above to do based on whether the shooter has reached the
// desired speed
m_shooter::atSetpoint))
.onFalse(new InstantCommand(m_shooter::stopFeeder, m_shooter));
// We can also write them as temporary variables outside the bindings
// Drive at half speed when the bumper is held
new JoystickButton(m_driverController, Button.kRightBumper.value)
.onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
// Shoots if the shooter wheel has reached the target speed
Command shoot =
Commands.either(
// Run the feeder
Commands.runOnce(m_shooter::runFeeder, m_shooter),
// Do nothing
Commands.none(),
// Determine which of the above to do based on whether the shooter has reached the
// desired speed
m_shooter::atSetpoint);
Command stopFeeder = Commands.runOnce(m_shooter::stopFeeder, m_shooter);
// Shoot when the 'X' button is pressed
m_driverController.x().onTrue(shoot).onFalse(stopFeeder);
// We can also define commands inline at the binding!
// While holding the shoulder button, drive at half speed
m_driverController
.rightBumper()
.onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1)));
}
/**
@@ -111,6 +119,6 @@ public class RobotContainer {
* @return the command to run in autonomous
*/
public Command getAutonomousCommand() {
return m_autoCommand;
return m_autonomousCommand;
}
}

View File

@@ -4,21 +4,16 @@
package edu.wpi.first.wpilibj.examples.hatchbotinlined;
import static edu.wpi.first.wpilibj.PS4Controller.Button;
import edu.wpi.first.wpilibj.PS4Controller;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.OIConstants;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.ComplexAutoCommand;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.commands.Autos;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.button.CommandPS4Controller;
/**
* This class is where the bulk of the robot should be declared. Since Command-based is a
@@ -31,30 +26,20 @@ public class RobotContainer {
private final DriveSubsystem m_robotDrive = new DriveSubsystem();
private final HatchSubsystem m_hatchSubsystem = new HatchSubsystem();
// Retained command handles
// The autonomous routines
// A simple auto routine that drives forward a specified distance, and then stops.
private final Command m_simpleAuto =
new FunctionalCommand(
// Reset encoders on command start
m_robotDrive::resetEncoders,
// Drive forward while the command is executing
() -> m_robotDrive.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
// Stop driving at the end of the command
interrupt -> m_robotDrive.arcadeDrive(0, 0),
// End the command when the robot's driven distance exceeds the desired value
() -> m_robotDrive.getAverageEncoderDistance() >= AutoConstants.kAutoDriveDistanceInches,
// Require the drive subsystem
m_robotDrive);
private final Command m_simpleAuto = Autos.simpleAuto(m_robotDrive);
// A complex auto routine that drives forward, drops a hatch, and then drives backward.
private final Command m_complexAuto = new ComplexAutoCommand(m_robotDrive, m_hatchSubsystem);
private final Command m_complexAuto = Autos.complexAuto(m_robotDrive, m_hatchSubsystem);
// A chooser for autonomous commands
SendableChooser<Command> m_chooser = new SendableChooser<>();
// The driver's controller
PS4Controller m_driverController = new PS4Controller(OIConstants.kDriverControllerPort);
CommandPS4Controller m_driverController =
new CommandPS4Controller(OIConstants.kDriverControllerPort);
/** The container for the robot. Contains subsystems, OI devices, and commands. */
public RobotContainer() {
@@ -66,7 +51,7 @@ public class RobotContainer {
m_robotDrive.setDefaultCommand(
// A split-stick arcade command, with forward/backward controlled by the left
// hand, and turning controlled by the right.
new RunCommand(
Commands.run(
() ->
m_robotDrive.arcadeDrive(
-m_driverController.getLeftY(), m_driverController.getRightX()),
@@ -88,15 +73,18 @@ public class RobotContainer {
*/
private void configureButtonBindings() {
// Grab the hatch when the Circle button is pressed.
new JoystickButton(m_driverController, Button.kCircle.value)
.onTrue(new InstantCommand(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
m_driverController
.circle()
.onTrue(Commands.runOnce(m_hatchSubsystem::grabHatch, m_hatchSubsystem));
// Release the hatch when the Square button is pressed.
new JoystickButton(m_driverController, Button.kSquare.value)
.onTrue(new InstantCommand(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
m_driverController
.square()
.onTrue(Commands.runOnce(m_hatchSubsystem::releaseHatch, m_hatchSubsystem));
// While holding R1, drive at half speed
new JoystickButton(m_driverController, Button.kR1.value)
.onTrue(new InstantCommand(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(new InstantCommand(() -> m_robotDrive.setMaxOutput(1)));
m_driverController
.R1()
.onTrue(Commands.runOnce(() -> m_robotDrive.setMaxOutput(0.5)))
.onFalse(Commands.runOnce(() -> m_robotDrive.setMaxOutput(1)));
}
/**

View File

@@ -7,20 +7,30 @@ package edu.wpi.first.wpilibj.examples.hatchbotinlined.commands;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.AutoConstants;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.DriveSubsystem;
import edu.wpi.first.wpilibj.examples.hatchbotinlined.subsystems.HatchSubsystem;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.SequentialCommandGroup;
/** A complex auto command that drives forward, releases a hatch, and then drives backward. */
public class ComplexAutoCommand extends SequentialCommandGroup {
/**
* Creates a new ComplexAutoCommand.
*
* @param driveSubsystem The drive subsystem this command will run on
* @param hatchSubsystem The hatch subsystem this command will run on
*/
public ComplexAutoCommand(DriveSubsystem driveSubsystem, HatchSubsystem hatchSubsystem) {
addCommands(
/** Container for auto command factories. */
public final class Autos {
/** A simple auto routine that drives forward a specified distance, and then stops. */
public static Command simpleAuto(DriveSubsystem drive) {
return new FunctionalCommand(
// Reset encoders on command start
drive::resetEncoders,
// Drive forward while the command is executing
() -> drive.arcadeDrive(AutoConstants.kAutoDriveSpeed, 0),
// Stop driving at the end of the command
interrupt -> drive.arcadeDrive(0, 0),
// End the command when the robot's driven distance exceeds the desired value
() -> drive.getAverageEncoderDistance() >= AutoConstants.kAutoDriveDistanceInches,
// Require the drive subsystem
drive);
}
/** A complex auto routine that drives forward, drops a hatch, and then drives backward. */
public static Command complexAuto(DriveSubsystem driveSubsystem, HatchSubsystem hatchSubsystem) {
return Commands.sequence(
// Drive forward up to the front of the cargo ship
new FunctionalCommand(
// Reset encoders on command start
@@ -37,7 +47,7 @@ public class ComplexAutoCommand extends SequentialCommandGroup {
driveSubsystem),
// Release the hatch
new InstantCommand(hatchSubsystem::releaseHatch, hatchSubsystem),
Commands.runOnce(hatchSubsystem::releaseHatch, hatchSubsystem),
// Drive backward the specified distance
new FunctionalCommand(
@@ -54,4 +64,8 @@ public class ComplexAutoCommand extends SequentialCommandGroup {
// Require the drive subsystem
driveSubsystem));
}
private Autos() {
throw new UnsupportedOperationException("This is a utility class!");
}
}