mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-20 00:51:42 +00:00
[commands] Merge CommandBase into Command and SubsystemBase into Subsystem (#5392)
Moves all CommandBase functionality into Command and deprecates CommandBase for removal. Moves all SubsystemBase functionality into Subsystem and deprecates SubsystemBase for removal. Adds a function to CommandScheduler to remove all registered Subsystems.
This commit is contained in:
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.command2;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class ReplaceMeCommand extends CommandBase {
|
||||
public class ReplaceMeCommand extends Command {
|
||||
/** Creates a new ReplaceMeCommand. */
|
||||
public ReplaceMeCommand() {
|
||||
// Use addRequirements() here to declare subsystem dependencies.
|
||||
|
||||
@@ -4,9 +4,9 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.commands.subsystem2;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class ReplaceMeSubsystem extends SubsystemBase {
|
||||
public class ReplaceMeSubsystem extends Subsystem {
|
||||
/** Creates a new ReplaceMeSubsystem. */
|
||||
public ReplaceMeSubsystem() {}
|
||||
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.armbot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ 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 edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.examples.drivedistanceoffboard.ExampleSmartMotorController;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final ExampleSmartMotorController m_leftLeader =
|
||||
new ExampleSmartMotorController(DriveConstants.kLeftMotor1Port);
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.frisbeebot.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -20,7 +20,6 @@ import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.button.JoystickButton;
|
||||
|
||||
/**
|
||||
@@ -38,7 +37,7 @@ public class RobotContainer {
|
||||
|
||||
private final XboxController m_joystick = new XboxController(0);
|
||||
|
||||
private final CommandBase m_autonomousCommand =
|
||||
private final Command m_autonomousCommand =
|
||||
new Autonomous(m_drivetrain, m_claw, m_wrist, m_elevator);
|
||||
|
||||
/** The container for the robot. Contains subsystems, OI devices, and commands. */
|
||||
|
||||
@@ -6,10 +6,10 @@ package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Robot;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Claw;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/** Closes the claw until the limit switch is tripped. */
|
||||
public class CloseClaw extends CommandBase {
|
||||
public class CloseClaw extends Command {
|
||||
private final Claw m_claw;
|
||||
|
||||
public CloseClaw(Claw claw) {
|
||||
|
||||
@@ -5,14 +5,14 @@
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Elevator;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/**
|
||||
* Move the elevator to a given location. This command finishes when it is within the tolerance, but
|
||||
* leaves the PID loop running to maintain the position. Other commands using the elevator should
|
||||
* make sure they disable PID!
|
||||
*/
|
||||
public class SetElevatorSetpoint extends CommandBase {
|
||||
public class SetElevatorSetpoint extends Command {
|
||||
private final Elevator m_elevator;
|
||||
private final double m_setpoint;
|
||||
|
||||
|
||||
@@ -5,14 +5,14 @@
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Wrist;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/**
|
||||
* Move the wrist to a given angle. This command finishes when it is within the tolerance, but
|
||||
* leaves the PID loop running to maintain the position. Other commands using the wrist should make
|
||||
* sure they disable PID!
|
||||
*/
|
||||
public class SetWristSetpoint extends CommandBase {
|
||||
public class SetWristSetpoint extends Command {
|
||||
private final Wrist m_wrist;
|
||||
private final double m_setpoint;
|
||||
|
||||
|
||||
@@ -5,11 +5,11 @@
|
||||
package edu.wpi.first.wpilibj.examples.gearsbot.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
/** Have the robot drive tank style. */
|
||||
public class TankDrive extends CommandBase {
|
||||
public class TankDrive extends Command {
|
||||
private final Drivetrain m_drivetrain;
|
||||
private final DoubleSupplier m_left;
|
||||
private final DoubleSupplier m_right;
|
||||
|
||||
@@ -8,13 +8,13 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.examples.gearsbot.Constants.ClawConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Victor;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
/**
|
||||
* The claw subsystem is a simple system with a motor for opening and closing. If using stronger
|
||||
* motors, you should probably use a sensor so that the motors don't stall.
|
||||
*/
|
||||
public class Claw extends SubsystemBase {
|
||||
public class Claw extends Subsystem {
|
||||
private final Victor m_motor = new Victor(ClawConstants.kMotorPort);
|
||||
private final DigitalInput m_contact = new DigitalInput(ClawConstants.kContactPort);
|
||||
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.motorcontrol.MotorController;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
public class Drivetrain extends Subsystem {
|
||||
/**
|
||||
* The Drivetrain subsystem incorporates the sensors and actuators attached to the robots chassis.
|
||||
* These include four drive motors, a left and right encoder and a gyro.
|
||||
|
||||
@@ -11,9 +11,9 @@ import edu.wpi.first.wpilibj.examples.gyrodrivecommands.Constants.DriveConstants
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,11 +11,11 @@ import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbotinlined.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link edu.wpi.first.wpilibj.DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
@@ -23,13 +23,13 @@ public class HatchSubsystem extends SubsystemBase {
|
||||
HatchConstants.kHatchSolenoidPorts[1]);
|
||||
|
||||
/** Grabs the hatch. */
|
||||
public CommandBase grabHatchCommand() {
|
||||
public Command grabHatchCommand() {
|
||||
// implicitly require `this`
|
||||
return this.runOnce(() -> m_hatchSolenoid.set(kForward));
|
||||
}
|
||||
|
||||
/** Releases the hatch. */
|
||||
public CommandBase releaseHatchCommand() {
|
||||
public Command releaseHatchCommand() {
|
||||
// implicitly require `this`
|
||||
return this.runOnce(() -> m_hatchSolenoid.set(kReverse));
|
||||
}
|
||||
|
||||
@@ -5,7 +5,7 @@
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
/**
|
||||
@@ -13,7 +13,7 @@ import java.util.function.DoubleSupplier;
|
||||
* explicitly for pedagogical purposes - actual code should inline a command this simple with {@link
|
||||
* edu.wpi.first.wpilibj2.command.RunCommand}.
|
||||
*/
|
||||
public class DefaultDrive extends CommandBase {
|
||||
public class DefaultDrive extends Command {
|
||||
private final DriveSubsystem m_drive;
|
||||
private final DoubleSupplier m_forward;
|
||||
private final DoubleSupplier m_rotation;
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class DriveDistance extends CommandBase {
|
||||
public class DriveDistance extends Command {
|
||||
private final DriveSubsystem m_drive;
|
||||
private final double m_distance;
|
||||
private final double m_speed;
|
||||
|
||||
@@ -5,14 +5,14 @@
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.HatchSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/**
|
||||
* A simple command that grabs a hatch with the {@link HatchSubsystem}. Written explicitly for
|
||||
* pedagogical purposes. Actual code should inline a command this simple with {@link
|
||||
* edu.wpi.first.wpilibj2.command.InstantCommand}.
|
||||
*/
|
||||
public class GrabHatch extends CommandBase {
|
||||
public class GrabHatch extends Command {
|
||||
// The subsystem the command runs on
|
||||
private final HatchSubsystem m_hatchSubsystem;
|
||||
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.hatchbottraditional.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.subsystems.DriveSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class HalveDriveSpeed extends CommandBase {
|
||||
public class HalveDriveSpeed extends Command {
|
||||
private final DriveSubsystem m_drive;
|
||||
|
||||
public HalveDriveSpeed(DriveSubsystem drive) {
|
||||
|
||||
@@ -10,9 +10,9 @@ import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -11,10 +11,10 @@ import edu.wpi.first.util.sendable.SendableBuilder;
|
||||
import edu.wpi.first.wpilibj.DoubleSolenoid;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.examples.hatchbottraditional.Constants.HatchConstants;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
/** A hatch mechanism actuated by a single {@link DoubleSolenoid}. */
|
||||
public class HatchSubsystem extends SubsystemBase {
|
||||
public class HatchSubsystem extends Subsystem {
|
||||
private final DoubleSolenoid m_hatchSolenoid =
|
||||
new DoubleSolenoid(
|
||||
PneumaticsModuleType.CTREPCM,
|
||||
|
||||
@@ -15,9 +15,9 @@ import edu.wpi.first.wpilibj.drive.MecanumDrive;
|
||||
import edu.wpi.first.wpilibj.examples.mecanumcontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
private final PWMSparkMax m_frontLeft = new PWMSparkMax(DriveConstants.kFrontLeftMotorPort);
|
||||
private final PWMSparkMax m_rearLeft = new PWMSparkMax(DriveConstants.kRearLeftMotorPort);
|
||||
private final PWMSparkMax m_frontRight = new PWMSparkMax(DriveConstants.kFrontRightMotorPort);
|
||||
|
||||
@@ -14,9 +14,9 @@ import edu.wpi.first.wpilibj.examples.ramsetecommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.MotorControllerGroup;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.PWMSparkMax;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -14,7 +14,7 @@ import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Intake;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Pneumatics;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Shooter;
|
||||
import edu.wpi.first.wpilibj.examples.rapidreactcommandbot.subsystems.Storage;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.button.Trigger;
|
||||
|
||||
@@ -81,7 +81,7 @@ public class RapidReactCommandBot {
|
||||
*
|
||||
* <p>Scheduled during {@link Robot#autonomousInit()}.
|
||||
*/
|
||||
public CommandBase getAutonomousCommand() {
|
||||
public Command getAutonomousCommand() {
|
||||
// Drive forward for 2 meters at half speed with a 3 second timeout
|
||||
return m_drive
|
||||
.driveDistanceCommand(AutoConstants.kDriveDistanceMeters, AutoConstants.kDriveSpeed)
|
||||
|
||||
@@ -9,11 +9,11 @@ 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.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
public class Drive extends SubsystemBase {
|
||||
public class Drive extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
@@ -61,7 +61,7 @@ public class Drive extends SubsystemBase {
|
||||
* @param fwd the commanded forward movement
|
||||
* @param rot the commanded rotation
|
||||
*/
|
||||
public CommandBase arcadeDriveCommand(DoubleSupplier fwd, DoubleSupplier rot) {
|
||||
public Command 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 CommandBase driveDistanceCommand(double distanceMeters, double speed) {
|
||||
public Command driveDistanceCommand(double distanceMeters, double speed) {
|
||||
return runOnce(
|
||||
() -> {
|
||||
// Reset encoders at the start of the command
|
||||
|
||||
@@ -9,10 +9,10 @@ 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.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class Intake extends SubsystemBase {
|
||||
public class Intake extends Subsystem {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(IntakeConstants.kMotorPort);
|
||||
|
||||
// Double solenoid connected to two channels of a PCM with the default CAN ID
|
||||
@@ -23,14 +23,14 @@ public class Intake extends SubsystemBase {
|
||||
IntakeConstants.kSolenoidPorts[1]);
|
||||
|
||||
/** Returns a command that deploys the intake, and then runs the intake motor indefinitely. */
|
||||
public CommandBase intakeCommand() {
|
||||
public Command 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 CommandBase retractCommand() {
|
||||
public Command retractCommand() {
|
||||
return runOnce(
|
||||
() -> {
|
||||
m_motor.disable();
|
||||
|
||||
@@ -8,11 +8,11 @@ import edu.wpi.first.wpilibj.AnalogPotentiometer;
|
||||
import edu.wpi.first.wpilibj.Compressor;
|
||||
import edu.wpi.first.wpilibj.PneumaticsModuleType;
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
/** Subsystem for managing the compressor, pressure sensor, etc. */
|
||||
public class Pneumatics extends SubsystemBase {
|
||||
public class Pneumatics extends Subsystem {
|
||||
// External analog pressure sensor
|
||||
// product-specific voltage->pressure conversion, see product manual
|
||||
// in this case, 250(V/5)-25
|
||||
@@ -48,7 +48,7 @@ public class Pneumatics extends SubsystemBase {
|
||||
*
|
||||
* @return command
|
||||
*/
|
||||
public CommandBase disableCompressorCommand() {
|
||||
public Command disableCompressorCommand() {
|
||||
return startEnd(
|
||||
() -> {
|
||||
// Disable closed-loop mode on the compressor.
|
||||
|
||||
@@ -12,10 +12,10 @@ 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.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class Shooter extends SubsystemBase {
|
||||
public class Shooter extends Subsystem {
|
||||
private final PWMSparkMax m_shooterMotor = new PWMSparkMax(ShooterConstants.kShooterMotorPort);
|
||||
private final PWMSparkMax m_feederMotor = new PWMSparkMax(ShooterConstants.kFeederMotorPort);
|
||||
private final Encoder m_shooterEncoder =
|
||||
@@ -50,7 +50,7 @@ public class Shooter extends SubsystemBase {
|
||||
*
|
||||
* @param setpointRotationsPerSecond The desired shooter velocity
|
||||
*/
|
||||
public CommandBase shootCommand(double setpointRotationsPerSecond) {
|
||||
public Command shootCommand(double setpointRotationsPerSecond) {
|
||||
return parallel(
|
||||
// Run the shooter flywheel at the desired setpoint using feedforward and feedback
|
||||
run(
|
||||
|
||||
@@ -8,10 +8,10 @@ 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.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class Storage extends SubsystemBase {
|
||||
public class Storage extends Subsystem {
|
||||
private final PWMSparkMax m_motor = new PWMSparkMax(StorageConstants.kMotorPort);
|
||||
private final DigitalInput m_ballSensor = new DigitalInput(StorageConstants.kBallSensorPort);
|
||||
|
||||
@@ -27,7 +27,7 @@ public class Storage extends SubsystemBase {
|
||||
}
|
||||
|
||||
/** Returns a command that runs the storage motor indefinitely. */
|
||||
public CommandBase runCommand() {
|
||||
public Command runCommand() {
|
||||
return run(() -> m_motor.set(1)).withName("run");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
package edu.wpi.first.wpilibj.examples.romireference.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.romireference.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import java.util.function.Supplier;
|
||||
|
||||
public class ArcadeDrive extends CommandBase {
|
||||
public class ArcadeDrive extends Command {
|
||||
private final Drivetrain m_drivetrain;
|
||||
private final Supplier<Double> m_xaxisSpeedSupplier;
|
||||
private final Supplier<Double> m_zaxisRotateSupplier;
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.romireference.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.romireference.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class DriveDistance extends CommandBase {
|
||||
public class DriveDistance extends Command {
|
||||
private final Drivetrain m_drive;
|
||||
private final double m_distance;
|
||||
private final double m_speed;
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.romireference.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.romireference.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class DriveTime extends CommandBase {
|
||||
public class DriveTime extends Command {
|
||||
private final double m_duration;
|
||||
private final double m_speed;
|
||||
private final Drivetrain m_drive;
|
||||
|
||||
@@ -5,9 +5,9 @@
|
||||
package edu.wpi.first.wpilibj.examples.romireference.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.romireference.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
public class TurnDegrees extends CommandBase {
|
||||
public class TurnDegrees extends Command {
|
||||
private final Drivetrain m_drive;
|
||||
private final double m_degrees;
|
||||
private final double m_speed;
|
||||
|
||||
@@ -5,13 +5,13 @@
|
||||
package edu.wpi.first.wpilibj.examples.romireference.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.examples.romireference.subsystems.Drivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/*
|
||||
* Creates a new TurnTime command. This command will turn your robot for a
|
||||
* desired rotational speed and time.
|
||||
*/
|
||||
public class TurnTime extends CommandBase {
|
||||
public class TurnTime extends Command {
|
||||
private final double m_duration;
|
||||
private final double m_rotationalSpeed;
|
||||
private final Drivetrain m_drive;
|
||||
|
||||
@@ -9,9 +9,9 @@ import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.examples.romireference.sensors.RomiGyro;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class Drivetrain extends SubsystemBase {
|
||||
public class Drivetrain extends Subsystem {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
@@ -8,7 +8,7 @@ import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj.DigitalOutput;
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.Timer;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
/**
|
||||
* This class represents the onboard IO of the Romi reference robot. This includes the pushbuttons
|
||||
@@ -17,7 +17,7 @@ import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
* <p>DIO 0 - Button A (input only) DIO 1 - Button B (input) or Green LED (output) DIO 2 - Button C
|
||||
* (input) or Red LED (output) DIO 3 - Yellow LED (output only)
|
||||
*/
|
||||
public class OnBoardIO extends SubsystemBase {
|
||||
public class OnBoardIO extends Subsystem {
|
||||
private final DigitalInput m_buttonA = new DigitalInput(0);
|
||||
private final DigitalOutput m_yellowLed = new DigitalOutput(3);
|
||||
|
||||
|
||||
@@ -22,9 +22,9 @@ import edu.wpi.first.wpilibj.simulation.DifferentialDrivetrainSim;
|
||||
import edu.wpi.first.wpilibj.simulation.EncoderSim;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.Field2d;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// The motors on the left side of the drive.
|
||||
private final MotorControllerGroup m_leftMotors =
|
||||
new MotorControllerGroup(
|
||||
|
||||
@@ -13,9 +13,9 @@ import edu.wpi.first.math.kinematics.SwerveModuleState;
|
||||
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
|
||||
import edu.wpi.first.wpilibj.examples.swervecontrollercommand.Constants.DriveConstants;
|
||||
import edu.wpi.first.wpilibj.interfaces.Gyro;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class DriveSubsystem extends SubsystemBase {
|
||||
public class DriveSubsystem extends Subsystem {
|
||||
// Robot swerve modules
|
||||
private final SwerveModule m_frontLeft =
|
||||
new SwerveModule(
|
||||
|
||||
@@ -5,12 +5,12 @@
|
||||
package edu.wpi.first.wpilibj.templates.commandbased.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
|
||||
public final class Autos {
|
||||
/** Example static factory for an autonomous command. */
|
||||
public static CommandBase exampleAuto(ExampleSubsystem subsystem) {
|
||||
public static Command exampleAuto(ExampleSubsystem subsystem) {
|
||||
return Commands.sequence(subsystem.exampleMethodCommand(), new ExampleCommand(subsystem));
|
||||
}
|
||||
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
package edu.wpi.first.wpilibj.templates.commandbased.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.templates.commandbased.subsystems.ExampleSubsystem;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/** An example command that uses an example subsystem. */
|
||||
public class ExampleCommand extends CommandBase {
|
||||
public class ExampleCommand extends Command {
|
||||
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
|
||||
private final ExampleSubsystem m_subsystem;
|
||||
|
||||
|
||||
@@ -4,10 +4,10 @@
|
||||
|
||||
package edu.wpi.first.wpilibj.templates.commandbased.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class ExampleSubsystem extends SubsystemBase {
|
||||
public class ExampleSubsystem extends Subsystem {
|
||||
/** Creates a new ExampleSubsystem. */
|
||||
public ExampleSubsystem() {}
|
||||
|
||||
@@ -16,7 +16,7 @@ public class ExampleSubsystem extends SubsystemBase {
|
||||
*
|
||||
* @return a command
|
||||
*/
|
||||
public CommandBase exampleMethodCommand() {
|
||||
public Command exampleMethodCommand() {
|
||||
// Inline construction of command goes here.
|
||||
// Subsystem::RunOnce implicitly requires `this` subsystem.
|
||||
return runOnce(
|
||||
|
||||
@@ -5,10 +5,10 @@
|
||||
package edu.wpi.first.wpilibj.templates.romicommandbased.commands;
|
||||
|
||||
import edu.wpi.first.wpilibj.templates.romicommandbased.subsystems.RomiDrivetrain;
|
||||
import edu.wpi.first.wpilibj2.command.CommandBase;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
|
||||
/** An example command that uses an example subsystem. */
|
||||
public class ExampleCommand extends CommandBase {
|
||||
public class ExampleCommand extends Command {
|
||||
@SuppressWarnings({"PMD.UnusedPrivateField", "PMD.SingularField"})
|
||||
private final RomiDrivetrain m_subsystem;
|
||||
|
||||
|
||||
@@ -7,9 +7,9 @@ package edu.wpi.first.wpilibj.templates.romicommandbased.subsystems;
|
||||
import edu.wpi.first.wpilibj.Encoder;
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj.motorcontrol.Spark;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
|
||||
public class RomiDrivetrain extends SubsystemBase {
|
||||
public class RomiDrivetrain extends Subsystem {
|
||||
private static final double kCountsPerRevolution = 1440.0;
|
||||
private static final double kWheelDiameterInch = 2.75591; // 70 mm
|
||||
|
||||
|
||||
Reference in New Issue
Block a user