From 21003e34ebe7e8451b0b584b1cf87b086fda837c Mon Sep 17 00:00:00 2001 From: Ryan Blue Date: Mon, 28 Nov 2022 22:47:18 -0500 Subject: [PATCH] [commands] Update Subsystem factories and example to return CommandBase (#4729) Also update rapidreactcommandbot example factories to fit this convention (as in #4655). C++ does not need an update as CommandPtr already uses CommandBase (#4677). --- .../java/edu/wpi/first/wpilibj2/command/Subsystem.java | 8 ++++---- .../rapidreactcommandbot/RapidReactCommandBot.java | 4 ++-- .../examples/rapidreactcommandbot/subsystems/Drive.java | 6 +++--- .../examples/rapidreactcommandbot/subsystems/Intake.java | 6 +++--- .../examples/rapidreactcommandbot/subsystems/Shooter.java | 4 ++-- .../examples/rapidreactcommandbot/subsystems/Storage.java | 4 ++-- 6 files changed, 16 insertions(+), 16 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java index 147859b9b2..f8457b10c7 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Subsystem.java @@ -85,7 +85,7 @@ public interface Subsystem { * @return the command * @see InstantCommand */ - default Command runOnce(Runnable action) { + default CommandBase runOnce(Runnable action) { return Commands.runOnce(action, this); } @@ -97,7 +97,7 @@ public interface Subsystem { * @return the command * @see RunCommand */ - default Command run(Runnable action) { + default CommandBase run(Runnable action) { return Commands.run(action, this); } @@ -110,7 +110,7 @@ public interface Subsystem { * @return the command * @see StartEndCommand */ - default Command startEnd(Runnable start, Runnable end) { + default CommandBase startEnd(Runnable start, Runnable end) { return Commands.startEnd(start, end, this); } @@ -122,7 +122,7 @@ public interface Subsystem { * @param end the action to run on interrupt * @return the command */ - default Command runEnd(Runnable run, Runnable end) { + default CommandBase runEnd(Runnable run, Runnable end) { return Commands.runEnd(run, end, this); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java index b5dca8c510..bb550ce76e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/RapidReactCommandBot.java @@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Drive; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Intake; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Shooter; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Storage; -import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.button.CommandXboxController; import edu.wpi.first.wpilibj2.command.button.Trigger; @@ -76,7 +76,7 @@ public class RapidReactCommandBot { * *

Scheduled during {@link Robot#autonomousInit()}. */ - public Command getAutonomousCommand() { + public CommandBase getAutonomousCommand() { // Drive forward for 2 meters at half speed with a 3 second timeout return m_drive .driveDistanceCommand(AutoConstants.kDriveDistanceMeters, AutoConstants.kDriveSpeed) diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java index 736ff446da..eaaa8ad747 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Drive.java @@ -9,7 +9,7 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive; import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.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.CommandBase; import edu.wpi.first.wpilibj2.command.SubsystemBase; import java.util.function.DoubleSupplier; @@ -61,7 +61,7 @@ public class Drive extends SubsystemBase { * @param fwd the commanded forward movement * @param rot the commanded rotation */ - public Command arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) { + public CommandBase arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) { // A split-stick arcade command, with forward/backward controlled by the left // hand, and turning controlled by the right. return run(() -> m_drive.arcadeDrive(fwd.getAsDouble(), rot.getAsDouble())) @@ -74,7 +74,7 @@ public class Drive extends SubsystemBase { * @param distanceMeters The distance to drive forward in meters * @param speed The fraction of max speed at which to drive */ - public Command driveDistanceCommand(double distanceMeters, double speed) { + public CommandBase driveDistanceCommand(double distanceMeters, double speed) { return runOnce( () -> { // Reset encoders at the start of the command diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java index e091cd6822..607c1232a7 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Intake.java @@ -9,7 +9,7 @@ import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.Inta import edu.wpi.first.wpilibj.DoubleSolenoid; import edu.wpi.first.wpilibj.PneumaticsModuleType; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; -import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Intake extends SubsystemBase { @@ -21,14 +21,14 @@ public class Intake extends SubsystemBase { IntakeConstants.kSolenoidPorts[2]); /** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */ - public Command intakeCommand() { + public CommandBase intakeCommand() { return runOnce(() -> m_pistons.set(DoubleSolenoid.Value.kForward)) .andThen(run(() -> m_motor.set(1.0))) .withName("Intake"); } /** Returns a command that turns off and retracts the intake. */ - public Command retractCommand() { + public CommandBase retractCommand() { return runOnce( () -> { m_motor.disable(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java index 0e7f9b56ce..9191fb6094 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Shooter.java @@ -12,7 +12,7 @@ import edu.wpi.first.math.controller.SimpleMotorFeedforward; import edu.wpi.first.wpilibj.Encoder; import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.ShooterConstants; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; -import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Shooter extends SubsystemBase { @@ -50,7 +50,7 @@ public class Shooter extends SubsystemBase { * * @param setpointRotationsPerSecond The desired shooter velocity */ - public Command shootCommand(double setpointRotationsPerSecond) { + public CommandBase shootCommand(double setpointRotationsPerSecond) { return parallel( // Run the shooter flywheel at the desired setpoint using feedforward and feedback run( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java index dac61a43fc..9b45d66833 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Storage.java @@ -8,7 +8,7 @@ import static edu.wpi.first.wpilibj.examples.rapidreactcommandbot.Constants.Stor import edu.wpi.first.wpilibj.DigitalInput; import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax; -import edu.wpi.first.wpilibj2.command.Command; +import edu.wpi.first.wpilibj2.command.CommandBase; import edu.wpi.first.wpilibj2.command.SubsystemBase; public class Storage extends SubsystemBase { @@ -27,7 +27,7 @@ public class Storage extends SubsystemBase { } /** Returns a command that runs the storage motor indefinitely. */ - public Command runCommand() { + public CommandBase runCommand() { return run(() -> m_motor.set(1)).withName("run"); } }