From aaea85ff165602a612e57a0e8170eaaa43ceec8f Mon Sep 17 00:00:00 2001 From: Ryan Blue Date: Fri, 14 Jul 2023 01:12:01 -0400 Subject: [PATCH] [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. --- .../wpi/first/wpilibj2/command/Command.java | 172 +++++++++++++----- .../first/wpilibj2/command/CommandBase.java | 103 +---------- .../wpilibj2/command/CommandScheduler.java | 9 + .../wpi/first/wpilibj2/command/Commands.java | 30 +-- .../wpilibj2/command/ConditionalCommand.java | 2 +- .../wpilibj2/command/FunctionalCommand.java | 2 +- .../command/MecanumControllerCommand.java | 2 +- .../wpilibj2/command/NotifierCommand.java | 2 +- .../first/wpilibj2/command/PIDCommand.java | 2 +- .../first/wpilibj2/command/PIDSubsystem.java | 2 +- .../command/ParallelCommandGroup.java | 2 +- .../command/ParallelDeadlineGroup.java | 2 +- .../wpilibj2/command/ParallelRaceGroup.java | 2 +- .../wpilibj2/command/ProfiledPIDCommand.java | 2 +- .../command/ProfiledPIDSubsystem.java | 2 +- .../first/wpilibj2/command/ProxyCommand.java | 2 +- .../wpilibj2/command/RamseteCommand.java | 2 +- .../first/wpilibj2/command/RepeatCommand.java | 2 +- .../wpilibj2/command/ScheduleCommand.java | 2 +- .../first/wpilibj2/command/SelectCommand.java | 2 +- .../command/SequentialCommandGroup.java | 2 +- .../wpi/first/wpilibj2/command/Subsystem.java | 105 +++++++++-- .../first/wpilibj2/command/SubsystemBase.java | 81 +-------- .../command/SwerveControllerCommand.java | 2 +- .../command/TrapezoidProfileCommand.java | 2 +- .../command/TrapezoidProfileSubsystem.java | 2 +- .../first/wpilibj2/command/WaitCommand.java | 2 +- .../wpilibj2/command/WaitUntilCommand.java | 2 +- .../wpilibj2/command/WrapperCommand.java | 2 +- .../main/native/cpp/frc2/command/Command.cpp | 82 ++++++++- .../native/cpp/frc2/command/CommandBase.cpp | 79 -------- .../native/cpp/frc2/command/CommandPtr.cpp | 4 +- .../cpp/frc2/command/CommandScheduler.cpp | 4 + .../cpp/frc2/command/ConditionalCommand.cpp | 2 +- .../frc2/command/ParallelDeadlineGroup.cpp | 2 +- .../native/cpp/frc2/command/ProxyCommand.cpp | 2 +- .../cpp/frc2/command/RamseteCommand.cpp | 2 +- .../native/cpp/frc2/command/RepeatCommand.cpp | 2 +- .../frc2/command/SequentialCommandGroup.cpp | 2 +- .../native/cpp/frc2/command/Subsystem.cpp | 56 ++++++ .../native/cpp/frc2/command/SubsystemBase.cpp | 55 +----- .../native/cpp/frc2/command/WaitCommand.cpp | 2 +- .../native/include/frc2/command/Command.h | 113 ++++++++++-- .../native/include/frc2/command/CommandBase.h | 112 +----------- .../native/include/frc2/command/CommandPtr.h | 12 +- .../include/frc2/command/CommandScheduler.h | 7 + .../include/frc2/command/ConditionalCommand.h | 5 +- .../include/frc2/command/FunctionalCommand.h | 4 +- .../frc2/command/MecanumControllerCommand.h | 4 +- .../include/frc2/command/NotifierCommand.h | 4 +- .../native/include/frc2/command/PIDCommand.h | 4 +- .../include/frc2/command/PIDSubsystem.h | 4 +- .../frc2/command/ParallelCommandGroup.h | 2 +- .../frc2/command/ParallelDeadlineGroup.h | 2 +- .../include/frc2/command/ParallelRaceGroup.h | 2 +- .../include/frc2/command/ProfiledPIDCommand.h | 4 +- .../frc2/command/ProfiledPIDSubsystem.h | 4 +- .../include/frc2/command/ProxyCommand.h | 4 +- .../include/frc2/command/RamseteCommand.h | 4 +- .../include/frc2/command/RepeatCommand.h | 4 +- .../include/frc2/command/ScheduleCommand.h | 4 +- .../include/frc2/command/SelectCommand.h | 6 +- .../frc2/command/SequentialCommandGroup.h | 2 +- .../native/include/frc2/command/Subsystem.h | 58 +++++- .../include/frc2/command/SubsystemBase.h | 54 +----- .../frc2/command/SwerveControllerCommand.h | 4 +- .../frc2/command/TrapezoidProfileCommand.h | 4 +- .../frc2/command/TrapezoidProfileSubsystem.h | 4 +- .../native/include/frc2/command/WaitCommand.h | 4 +- .../include/frc2/command/WaitUntilCommand.h | 4 +- .../include/frc2/command/WrapperCommand.h | 4 +- .../command/CommandRequirementsTest.java | 6 +- .../command/CommandSendableButtonTest.java | 2 +- .../wpilibj2/command/CommandTestBase.java | 1 + .../command/ConditionalCommandTest.java | 6 +- .../wpilibj2/command/DefaultCommandTest.java | 6 +- .../command/ParallelCommandGroupTest.java | 14 +- .../command/ParallelDeadlineGroupTest.java | 14 +- .../command/ParallelRaceGroupTest.java | 18 +- .../first/wpilibj2/command/SchedulerTest.java | 4 +- .../command/SchedulingRecursionTest.java | 22 +-- .../wpilibj2/command/SelectCommandTest.java | 8 +- .../command/SequentialCommandGroupTest.java | 8 +- .../cpp/frc2/command/CommandTestBase.cpp | 2 + .../native/cpp/frc2/command/CommandTestBase.h | 8 +- .../command/MecanumControllerCommandTest.cpp | 3 +- .../frc2/command/SchedulingRecursionTest.cpp | 4 +- .../command/SwerveControllerCommandTest.cpp | 3 +- .../cpp/commands/command2/ReplaceMeCommand2.h | 6 +- .../commands/subsystem2/ReplaceMeSubsystem2.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../GearsBot/include/commands/CloseClaw.h | 4 +- .../include/commands/SetElevatorSetpoint.h | 4 +- .../include/commands/SetWristSetpoint.h | 4 +- .../GearsBot/include/commands/TankDrive.h | 4 +- .../GearsBot/include/subsystems/Claw.h | 4 +- .../GearsBot/include/subsystems/Drivetrain.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../cpp/subsystems/DriveSubsystem.cpp | 2 +- .../cpp/subsystems/HatchSubsystem.cpp | 2 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/HatchSubsystem.h | 4 +- .../cpp/subsystems/DriveSubsystem.cpp | 2 +- .../cpp/subsystems/HatchSubsystem.cpp | 2 +- .../include/commands/DefaultDrive.h | 5 +- .../include/commands/DriveDistance.h | 5 +- .../include/commands/GrabHatch.h | 4 +- .../include/commands/HalveDriveSpeed.h | 4 +- .../include/commands/ReleaseHatch.h | 5 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/HatchSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/Drive.h | 4 +- .../include/subsystems/Intake.h | 4 +- .../include/subsystems/Pneumatics.h | 4 +- .../include/subsystems/Shooter.h | 4 +- .../include/subsystems/Storage.h | 4 +- .../include/commands/DriveDistance.h | 5 +- .../include/commands/DriveTime.h | 4 +- .../include/commands/TeleopArcadeDrive.h | 4 +- .../include/commands/TurnDegrees.h | 4 +- .../RomiReference/include/commands/TurnTime.h | 4 +- .../include/subsystems/Drivetrain.h | 4 +- .../include/subsystems/OnBoardIO.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/subsystems/DriveSubsystem.h | 4 +- .../include/commands/ExampleCommand.h | 6 +- .../include/subsystems/ExampleSubsystem.h | 4 +- .../commands/command2/ReplaceMeCommand.java | 4 +- .../subsystem2/ReplaceMeSubsystem.java | 4 +- .../armbot/subsystems/DriveSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../frisbeebot/subsystems/DriveSubsystem.java | 4 +- .../examples/gearsbot/RobotContainer.java | 3 +- .../examples/gearsbot/commands/CloseClaw.java | 4 +- .../commands/SetElevatorSetpoint.java | 4 +- .../gearsbot/commands/SetWristSetpoint.java | 4 +- .../examples/gearsbot/commands/TankDrive.java | 4 +- .../examples/gearsbot/subsystems/Claw.java | 4 +- .../gearsbot/subsystems/Drivetrain.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/HatchSubsystem.java | 10 +- .../commands/DefaultDrive.java | 4 +- .../commands/DriveDistance.java | 4 +- .../commands/GrabHatch.java | 4 +- .../commands/HalveDriveSpeed.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/HatchSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../RapidReactCommandBot.java | 4 +- .../subsystems/Drive.java | 10 +- .../subsystems/Intake.java | 10 +- .../subsystems/Pneumatics.java | 8 +- .../subsystems/Shooter.java | 8 +- .../subsystems/Storage.java | 8 +- .../romireference/commands/ArcadeDrive.java | 4 +- .../romireference/commands/DriveDistance.java | 4 +- .../romireference/commands/DriveTime.java | 4 +- .../romireference/commands/TurnDegrees.java | 4 +- .../romireference/commands/TurnTime.java | 4 +- .../romireference/subsystems/Drivetrain.java | 4 +- .../romireference/subsystems/OnBoardIO.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../subsystems/DriveSubsystem.java | 4 +- .../commandbased/commands/Autos.java | 4 +- .../commandbased/commands/ExampleCommand.java | 4 +- .../subsystems/ExampleSubsystem.java | 8 +- .../commands/ExampleCommand.java | 4 +- .../subsystems/RomiDrivetrain.java | 4 +- 176 files changed, 887 insertions(+), 910 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java index 7b5ccc7fb6..635a7aabd7 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Command.java @@ -7,6 +7,10 @@ package edu.wpi.first.wpilibj2.command; import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; import edu.wpi.first.util.function.BooleanConsumer; +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.util.sendable.SendableRegistry; +import java.util.HashSet; import java.util.Set; import java.util.function.BooleanSupplier; @@ -20,12 +24,19 @@ import java.util.function.BooleanSupplier; * *

This class is provided by the NewCommands VendorDep */ -public interface Command { +public abstract class Command implements Sendable { + protected Set m_requirements = new HashSet<>(); + + protected Command() { + String name = getClass().getName(); + SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1)); + } + /** The initial subroutine of a command. Called once when the command is initially scheduled. */ - default void initialize() {} + public void initialize() {} /** The main body of a command. Called repeatedly while the command is scheduled. */ - default void execute() {} + public void execute() {} /** * The action to take when the command ends. Called when either the command finishes normally, or @@ -36,7 +47,7 @@ public interface Command { * * @param interrupted whether the command was interrupted/canceled */ - default void end(boolean interrupted) {} + public void end(boolean interrupted) {} /** * Whether the command has finished. Once a command finishes, the scheduler will call its end() @@ -44,7 +55,7 @@ public interface Command { * * @return whether the command has finished. */ - default boolean isFinished() { + public boolean isFinished() { return false; } @@ -60,7 +71,63 @@ public interface Command { * @return the set of subsystems that are required * @see InterruptionBehavior */ - Set getRequirements(); + public Set getRequirements() { + return m_requirements; + } + + /** + * Adds the specified subsystems to the requirements of the command. The scheduler will prevent + * two commands that require the same subsystem from being scheduled simultaneously. + * + *

Note that the scheduler determines the requirements of a command when it is scheduled, so + * this method should normally be called from the command's constructor. + * + * @param requirements the requirements to add + */ + public final void addRequirements(Subsystem... requirements) { + for (Subsystem requirement : requirements) { + m_requirements.add(requireNonNullParam(requirement, "requirement", "addRequirements")); + } + } + + /** + * Gets the name of this Command. + * + *

By default, the simple class name is used. This can be changed with {@link + * #setName(String)}. + * + * @return The display name of the Command + */ + public String getName() { + return SendableRegistry.getName(this); + } + + /** + * Sets the name of this Command. + * + * @param name The display name of the Command. + */ + public void setName(String name) { + SendableRegistry.setName(this, name); + } + + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ + public String getSubsystem() { + return SendableRegistry.getSubsystem(this); + } + + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ + public void setSubsystem(String subsystem) { + SendableRegistry.setSubsystem(this, subsystem); + } /** * Decorates this command with a timeout. If the specified timeout is exceeded before the command @@ -75,7 +142,7 @@ public interface Command { * @param seconds the timeout duration * @return the command with the timeout added */ - default ParallelRaceGroup withTimeout(double seconds) { + public ParallelRaceGroup withTimeout(double seconds) { return raceWith(new WaitCommand(seconds)); } @@ -93,7 +160,7 @@ public interface Command { * @return the command with the interrupt condition added * @see #onlyWhile(BooleanSupplier) */ - default ParallelRaceGroup until(BooleanSupplier condition) { + public ParallelRaceGroup until(BooleanSupplier condition) { return raceWith(new WaitUntilCommand(condition)); } @@ -111,7 +178,7 @@ public interface Command { * @return the command with the run condition added * @see #until(BooleanSupplier) */ - default ParallelRaceGroup onlyWhile(BooleanSupplier condition) { + public ParallelRaceGroup onlyWhile(BooleanSupplier condition) { return until(() -> !condition.getAsBoolean()); } @@ -128,7 +195,7 @@ public interface Command { * @param requirements the required subsystems * @return the decorated command */ - default SequentialCommandGroup beforeStarting(Runnable toRun, Subsystem... requirements) { + public SequentialCommandGroup beforeStarting(Runnable toRun, Subsystem... requirements) { return beforeStarting(new InstantCommand(toRun, requirements)); } @@ -144,7 +211,7 @@ public interface Command { * @param before the command to run before this one * @return the decorated command */ - default SequentialCommandGroup beforeStarting(Command before) { + public SequentialCommandGroup beforeStarting(Command before) { return new SequentialCommandGroup(before, this); } @@ -161,7 +228,7 @@ public interface Command { * @param requirements the required subsystems * @return the decorated command */ - default SequentialCommandGroup andThen(Runnable toRun, Subsystem... requirements) { + public SequentialCommandGroup andThen(Runnable toRun, Subsystem... requirements) { return andThen(new InstantCommand(toRun, requirements)); } @@ -178,7 +245,7 @@ public interface Command { * @param next the commands to run next * @return the decorated command */ - default SequentialCommandGroup andThen(Command... next) { + public SequentialCommandGroup andThen(Command... next) { SequentialCommandGroup group = new SequentialCommandGroup(this); group.addCommands(next); return group; @@ -198,7 +265,7 @@ public interface Command { * @param parallel the commands to run in parallel * @return the decorated command */ - default ParallelDeadlineGroup deadlineWith(Command... parallel) { + public ParallelDeadlineGroup deadlineWith(Command... parallel) { return new ParallelDeadlineGroup(this, parallel); } @@ -216,7 +283,7 @@ public interface Command { * @param parallel the commands to run in parallel * @return the decorated command */ - default ParallelCommandGroup alongWith(Command... parallel) { + public ParallelCommandGroup alongWith(Command... parallel) { ParallelCommandGroup group = new ParallelCommandGroup(this); group.addCommands(parallel); return group; @@ -236,7 +303,7 @@ public interface Command { * @param parallel the commands to run in parallel * @return the decorated command */ - default ParallelRaceGroup raceWith(Command... parallel) { + public ParallelRaceGroup raceWith(Command... parallel) { ParallelRaceGroup group = new ParallelRaceGroup(this); group.addCommands(parallel); return group; @@ -254,7 +321,7 @@ public interface Command { * * @return the decorated command */ - default RepeatCommand repeatedly() { + public RepeatCommand repeatedly() { return new RepeatCommand(this); } @@ -265,7 +332,7 @@ public interface Command { * * @return the decorated command */ - default ProxyCommand asProxy() { + public ProxyCommand asProxy() { return new ProxyCommand(this); } @@ -284,7 +351,7 @@ public interface Command { * @return the decorated command * @see #onlyIf(BooleanSupplier) */ - default ConditionalCommand unless(BooleanSupplier condition) { + public ConditionalCommand unless(BooleanSupplier condition) { return new ConditionalCommand(new InstantCommand(), this, condition); } @@ -303,7 +370,7 @@ public interface Command { * @return the decorated command * @see #unless(BooleanSupplier) */ - default ConditionalCommand onlyIf(BooleanSupplier condition) { + public ConditionalCommand onlyIf(BooleanSupplier condition) { return unless(() -> !condition.getAsBoolean()); } @@ -313,7 +380,7 @@ public interface Command { * @param doesRunWhenDisabled true to run when disabled. * @return the decorated command */ - default WrapperCommand ignoringDisable(boolean doesRunWhenDisabled) { + public WrapperCommand ignoringDisable(boolean doesRunWhenDisabled) { return new WrapperCommand(this) { @Override public boolean runsWhenDisabled() { @@ -328,7 +395,7 @@ public interface Command { * @param interruptBehavior the desired interrupt behavior * @return the decorated command */ - default WrapperCommand withInterruptBehavior(InterruptionBehavior interruptBehavior) { + public WrapperCommand withInterruptBehavior(InterruptionBehavior interruptBehavior) { return new WrapperCommand(this) { @Override public InterruptionBehavior getInterruptionBehavior() { @@ -345,7 +412,7 @@ public interface Command { * interrupted. * @return the decorated command */ - default WrapperCommand finallyDo(BooleanConsumer end) { + public WrapperCommand finallyDo(BooleanConsumer end) { requireNonNullParam(end, "end", "Command.finallyDo()"); return new WrapperCommand(this) { @Override @@ -363,7 +430,7 @@ public interface Command { * @param handler a lambda to run when the command is interrupted * @return the decorated command */ - default WrapperCommand handleInterrupt(Runnable handler) { + public WrapperCommand handleInterrupt(Runnable handler) { requireNonNullParam(handler, "handler", "Command.handleInterrupt()"); return finallyDo( interrupted -> { @@ -374,7 +441,7 @@ public interface Command { } /** Schedules this command. */ - default void schedule() { + public void schedule() { CommandScheduler.getInstance().schedule(this); } @@ -384,7 +451,7 @@ public interface Command { * * @see CommandScheduler#cancel(Command...) */ - default void cancel() { + public void cancel() { CommandScheduler.getInstance().cancel(this); } @@ -394,7 +461,7 @@ public interface Command { * * @return Whether the command is scheduled. */ - default boolean isScheduled() { + public boolean isScheduled() { return CommandScheduler.getInstance().isScheduled(this); } @@ -404,7 +471,7 @@ public interface Command { * @param requirement the subsystem to inquire about * @return whether the subsystem is required */ - default boolean hasRequirement(Subsystem requirement) { + public boolean hasRequirement(Subsystem requirement) { return getRequirements().contains(requirement); } @@ -414,7 +481,7 @@ public interface Command { * @return a variant of {@link InterruptionBehavior}, defaulting to {@link * InterruptionBehavior#kCancelSelf kCancelSelf}. */ - default InterruptionBehavior getInterruptionBehavior() { + public InterruptionBehavior getInterruptionBehavior() { return InterruptionBehavior.kCancelSelf; } @@ -424,43 +491,52 @@ public interface Command { * * @return whether the command should run when the robot is disabled */ - default boolean runsWhenDisabled() { + public boolean runsWhenDisabled() { return false; } - /** - * Gets the name of this Command. Defaults to the simple class name if not overridden. - * - * @return The display name of the Command - */ - default String getName() { - return this.getClass().getSimpleName(); - } - - /** - * Sets the name of this Command. Nullop if not overridden. - * - * @param name The display name of the Command. - */ - default void setName(String name) {} - /** * Decorates this Command with a name. * * @param name name * @return the decorated Command */ - default WrapperCommand withName(String name) { + public WrapperCommand withName(String name) { WrapperCommand wrapper = new WrapperCommand(Command.this) {}; wrapper.setName(name); return wrapper; } + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("Command"); + builder.addStringProperty(".name", this::getName, null); + builder.addBooleanProperty( + "running", + this::isScheduled, + value -> { + if (value) { + if (!isScheduled()) { + schedule(); + } + } else { + if (isScheduled()) { + cancel(); + } + } + }); + builder.addBooleanProperty( + ".isParented", () -> CommandScheduler.getInstance().isComposed(this), null); + builder.addStringProperty( + "interruptBehavior", () -> getInterruptionBehavior().toString(), null); + builder.addBooleanProperty("runsWhenDisabled", this::runsWhenDisabled, null); + } + /** * An enum describing the command's behavior when another command with a shared requirement is * scheduled. */ - enum InterruptionBehavior { + public enum InterruptionBehavior { /** * This command ends, {@link #end(boolean) end(true)} is called, and the incoming command is * scheduled normally. diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java index 5067a5a271..12243cb58b 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandBase.java @@ -4,107 +4,16 @@ package edu.wpi.first.wpilibj2.command; -import static edu.wpi.first.util.ErrorMessages.requireNonNullParam; - import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableBuilder; -import edu.wpi.first.util.sendable.SendableRegistry; -import java.util.HashSet; -import java.util.Set; /** * A {@link Sendable} base class for {@link Command}s. * *

This class is provided by the NewCommands VendorDep + * + * @deprecated All functionality provided by {@link CommandBase} has been merged into {@link + * Command}. Use {@link Command} instead. */ -public abstract class CommandBase implements Sendable, Command { - protected Set m_requirements = new HashSet<>(); - - protected CommandBase() { - String name = getClass().getName(); - SendableRegistry.add(this, name.substring(name.lastIndexOf('.') + 1)); - } - - /** - * Adds the specified subsystems to the requirements of the command. The scheduler will prevent - * two commands that require the same subsystem from being scheduled simultaneously. - * - *

Note that the scheduler determines the requirements of a command when it is scheduled, so - * this method should normally be called from the command's constructor. - * - * @param requirements the requirements to add - */ - public final void addRequirements(Subsystem... requirements) { - for (Subsystem requirement : requirements) { - m_requirements.add(requireNonNullParam(requirement, "requirement", "addRequirements")); - } - } - - @Override - public Set getRequirements() { - return m_requirements; - } - - @Override - public String getName() { - return SendableRegistry.getName(this); - } - - /** - * Sets the name of this Command. - * - * @param name name - */ - @Override - public void setName(String name) { - SendableRegistry.setName(this, name); - } - - /** - * Gets the subsystem name of this Command. - * - * @return Subsystem name - */ - public String getSubsystem() { - return SendableRegistry.getSubsystem(this); - } - - /** - * Sets the subsystem name of this Command. - * - * @param subsystem subsystem name - */ - public void setSubsystem(String subsystem) { - SendableRegistry.setSubsystem(this, subsystem); - } - - /** - * Initializes this sendable. Useful for allowing implementations to easily extend SendableBase. - * - * @param builder the builder used to construct this sendable - */ - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("Command"); - builder.addStringProperty(".name", this::getName, null); - builder.addBooleanProperty( - "running", - this::isScheduled, - value -> { - if (value) { - if (!isScheduled()) { - schedule(); - } - } else { - if (isScheduled()) { - cancel(); - } - } - }); - builder.addBooleanProperty( - ".isParented", () -> CommandScheduler.getInstance().isComposed(this), null); - builder.addStringProperty( - "interruptBehavior", () -> getInterruptionBehavior().toString(), null); - builder.addBooleanProperty("runsWhenDisabled", this::runsWhenDisabled, null); - } -} +@Deprecated(since = "2024", forRemoval = true) +@SuppressWarnings("PMD.AbstractClassWithoutAnyMethod") +public abstract class CommandBase extends Command {} diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 37cac9cb3a..4eb023cdc2 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -362,6 +362,15 @@ public final class CommandScheduler implements NTSendable, AutoCloseable { m_subsystems.keySet().removeAll(Set.of(subsystems)); } + /** + * Un-registers all registered Subsystems with the scheduler. All currently registered subsystems + * will no longer have their periodic block called, and will not have their default command + * scheduled. + */ + public void unregisterAllSubsystems() { + m_subsystems.clear(); + } + /** * Sets the default command for a subsystem. Registers that subsystem if it is not already * registered. Default commands will run whenever there is no other command currently scheduled diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java index 737b9cc03c..c3fbfea838 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Commands.java @@ -21,7 +21,7 @@ public final class Commands { * * @return the command */ - public static CommandBase none() { + public static Command none() { return new InstantCommand(); } @@ -35,7 +35,7 @@ public final class Commands { * @return the command * @see InstantCommand */ - public static CommandBase runOnce(Runnable action, Subsystem... requirements) { + public static Command runOnce(Runnable action, Subsystem... requirements) { return new InstantCommand(action, requirements); } @@ -47,7 +47,7 @@ public final class Commands { * @return the command * @see RunCommand */ - public static CommandBase run(Runnable action, Subsystem... requirements) { + public static Command run(Runnable action, Subsystem... requirements) { return new RunCommand(action, requirements); } @@ -61,7 +61,7 @@ public final class Commands { * @return the command * @see StartEndCommand */ - public static CommandBase startEnd(Runnable start, Runnable end, Subsystem... requirements) { + public static Command startEnd(Runnable start, Runnable end, Subsystem... requirements) { return new StartEndCommand(start, end, requirements); } @@ -74,7 +74,7 @@ public final class Commands { * @param requirements subsystems the action requires * @return the command */ - public static CommandBase runEnd(Runnable run, Runnable end, Subsystem... requirements) { + public static Command runEnd(Runnable run, Runnable end, Subsystem... requirements) { requireNonNullParam(end, "end", "Command.runEnd"); return new FunctionalCommand( () -> {}, run, interrupted -> end.run(), () -> false, requirements); @@ -87,7 +87,7 @@ public final class Commands { * @return the command * @see PrintCommand */ - public static CommandBase print(String message) { + public static Command print(String message) { return new PrintCommand(message); } @@ -100,7 +100,7 @@ public final class Commands { * @return the command * @see WaitCommand */ - public static CommandBase waitSeconds(double seconds) { + public static Command waitSeconds(double seconds) { return new WaitCommand(seconds); } @@ -111,7 +111,7 @@ public final class Commands { * @return the command * @see WaitUntilCommand */ - public static CommandBase waitUntil(BooleanSupplier condition) { + public static Command waitUntil(BooleanSupplier condition) { return new WaitUntilCommand(condition); } @@ -126,7 +126,7 @@ public final class Commands { * @return the command * @see ConditionalCommand */ - public static CommandBase either(Command onTrue, Command onFalse, BooleanSupplier selector) { + public static Command either(Command onTrue, Command onFalse, BooleanSupplier selector) { return new ConditionalCommand(onTrue, onFalse, selector); } @@ -138,7 +138,7 @@ public final class Commands { * @return the command * @see SelectCommand */ - public static CommandBase select(Map commands, Supplier selector) { + public static Command select(Map commands, Supplier selector) { return new SelectCommand(commands, selector); } @@ -149,7 +149,7 @@ public final class Commands { * @return the command group * @see SequentialCommandGroup */ - public static CommandBase sequence(Command... commands) { + public static Command sequence(Command... commands) { return new SequentialCommandGroup(commands); } @@ -164,7 +164,7 @@ public final class Commands { * @see SequentialCommandGroup * @see Command#repeatedly() */ - public static CommandBase repeatingSequence(Command... commands) { + public static Command repeatingSequence(Command... commands) { return sequence(commands).repeatedly(); } @@ -175,7 +175,7 @@ public final class Commands { * @return the command * @see ParallelCommandGroup */ - public static CommandBase parallel(Command... commands) { + public static Command parallel(Command... commands) { return new ParallelCommandGroup(commands); } @@ -187,7 +187,7 @@ public final class Commands { * @return the command group * @see ParallelRaceGroup */ - public static CommandBase race(Command... commands) { + public static Command race(Command... commands) { return new ParallelRaceGroup(commands); } @@ -200,7 +200,7 @@ public final class Commands { * @return the command group * @see ParallelDeadlineGroup */ - public static CommandBase deadline(Command deadline, Command... commands) { + public static Command deadline(Command deadline, Command... commands) { return new ParallelDeadlineGroup(deadline, commands); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java index 6bda65d5cc..42db3f0b99 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ConditionalCommand.java @@ -19,7 +19,7 @@ import java.util.function.BooleanSupplier; * *

This class is provided by the NewCommands VendorDep */ -public class ConditionalCommand extends CommandBase { +public class ConditionalCommand extends Command { private final Command m_onTrue; private final Command m_onFalse; private final BooleanSupplier m_condition; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java index fcd4bd7384..dde5ae1f01 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/FunctionalCommand.java @@ -17,7 +17,7 @@ import java.util.function.Consumer; * *

This class is provided by the NewCommands VendorDep */ -public class FunctionalCommand extends CommandBase { +public class FunctionalCommand extends Command { protected final Runnable m_onInit; protected final Runnable m_onExecute; protected final Consumer m_onEnd; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java index a87486482f..16d9c8a1ab 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommand.java @@ -38,7 +38,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class MecanumControllerCommand extends CommandBase { +public class MecanumControllerCommand extends Command { private final Timer m_timer = new Timer(); private final boolean m_usePID; private final Trajectory m_trajectory; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java index 730ef1bcc6..ad1a12ad2d 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/NotifierCommand.java @@ -17,7 +17,7 @@ import edu.wpi.first.wpilibj.Notifier; * *

This class is provided by the NewCommands VendorDep */ -public class NotifierCommand extends CommandBase { +public class NotifierCommand extends Command { protected final Notifier m_notifier; protected final double m_period; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java index ec184c8403..c761f3f18d 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDCommand.java @@ -18,7 +18,7 @@ import java.util.function.DoubleSupplier; * *

This class is provided by the NewCommands VendorDep */ -public class PIDCommand extends CommandBase { +public class PIDCommand extends Command { protected final PIDController m_controller; protected DoubleSupplier m_measurement; protected DoubleSupplier m_setpoint; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java index 84318de14a..d7ece4aa87 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/PIDSubsystem.java @@ -14,7 +14,7 @@ import edu.wpi.first.math.controller.PIDController; * *

This class is provided by the NewCommands VendorDep */ -public abstract class PIDSubsystem extends SubsystemBase { +public abstract class PIDSubsystem extends Subsystem { protected final PIDController m_controller; protected boolean m_enabled; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java index 6c5c8ea3a6..8604189415 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroup.java @@ -17,7 +17,7 @@ import java.util.Map; * *

This class is provided by the NewCommands VendorDep */ -public class ParallelCommandGroup extends CommandBase { +public class ParallelCommandGroup extends Command { // maps commands in this composition to whether they are still running private final Map m_commands = new HashMap<>(); private boolean m_runWhenDisabled = true; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java index 8c95685178..6d263e88cf 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroup.java @@ -20,7 +20,7 @@ import java.util.Map; * *

This class is provided by the NewCommands VendorDep */ -public class ParallelDeadlineGroup extends CommandBase { +public class ParallelDeadlineGroup extends Command { // maps commands in this composition to whether they are still running private final Map m_commands = new HashMap<>(); private boolean m_runWhenDisabled = true; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java index 697b1f3e79..7195cd70bf 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroup.java @@ -18,7 +18,7 @@ import java.util.Set; * *

This class is provided by the NewCommands VendorDep */ -public class ParallelRaceGroup extends CommandBase { +public class ParallelRaceGroup extends Command { private final Set m_commands = new HashSet<>(); private boolean m_runWhenDisabled = true; private boolean m_finished = true; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java index 4344913601..f7175fc2eb 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDCommand.java @@ -20,7 +20,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class ProfiledPIDCommand extends CommandBase { +public class ProfiledPIDCommand extends Command { protected final ProfiledPIDController m_controller; protected DoubleSupplier m_measurement; protected Supplier m_goal; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java index 283b4bfd46..e58a77b402 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProfiledPIDSubsystem.java @@ -16,7 +16,7 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile; * *

This class is provided by the NewCommands VendorDep */ -public abstract class ProfiledPIDSubsystem extends SubsystemBase { +public abstract class ProfiledPIDSubsystem extends Subsystem { protected final ProfiledPIDController m_controller; protected boolean m_enabled; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java index ef6ca5b6ea..d6e93e88ba 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ProxyCommand.java @@ -15,7 +15,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class ProxyCommand extends CommandBase { +public class ProxyCommand extends Command { private final Supplier m_supplier; private Command m_command; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java index 45ac09a918..9f19e4a792 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RamseteCommand.java @@ -33,7 +33,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class RamseteCommand extends CommandBase { +public class RamseteCommand extends Command { private final Timer m_timer = new Timer(); private final boolean m_usePID; private final Trajectory m_trajectory; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java index 103a5c9d06..5b49ae0027 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RepeatCommand.java @@ -19,7 +19,7 @@ import edu.wpi.first.util.sendable.SendableBuilder; * *

This class is provided by the NewCommands VendorDep */ -public class RepeatCommand extends CommandBase { +public class RepeatCommand extends Command { protected final Command m_command; private boolean m_ended; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java index a61be2f336..cc2234119e 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/ScheduleCommand.java @@ -13,7 +13,7 @@ import java.util.Set; * *

This class is provided by the NewCommands VendorDep */ -public class ScheduleCommand extends CommandBase { +public class ScheduleCommand extends Command { private final Set m_toSchedule; /** diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java index 492ff3eb92..5498916fa0 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SelectCommand.java @@ -20,7 +20,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class SelectCommand extends CommandBase { +public class SelectCommand extends Command { private final Map m_commands; private final Supplier m_selector; private Command m_selectedCommand; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java index 5be4491903..c3598cb04c 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroup.java @@ -17,7 +17,7 @@ import java.util.List; * *

This class is provided by the NewCommands VendorDep */ -public class SequentialCommandGroup extends CommandBase { +public class SequentialCommandGroup extends Command { private final List m_commands = new ArrayList<>(); private int m_currentCommandIndex = -1; private boolean m_runWhenDisabled = true; 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 be7a2a7215..a14192521d 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 @@ -4,6 +4,10 @@ package edu.wpi.first.wpilibj2.command; +import edu.wpi.first.util.sendable.Sendable; +import edu.wpi.first.util.sendable.SendableBuilder; +import edu.wpi.first.util.sendable.SendableRegistry; + /** * A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based * framework; they encapsulate low-level hardware objects (motor controllers, sensors, etc.) and @@ -13,29 +17,34 @@ package edu.wpi.first.wpilibj2.command; * their {@link Command#getRequirements()} method, and resources used within a subsystem should * generally remain encapsulated and not be shared by other parts of the robot. * - *

Subsystems must be registered with the scheduler with the {@link - * CommandScheduler#registerSubsystem(Subsystem...)} method in order for the {@link - * Subsystem#periodic()} method to be called. It is recommended that this method be called from the - * constructor of users' Subsystem implementations. The {@link SubsystemBase} class offers a simple - * base for user implementations that handles this. + *

Subsystems are automatically registered with the default scheduler in order for the {@link + * Subsystem#periodic()} method to be called. * *

This class is provided by the NewCommands VendorDep */ -public interface Subsystem { +public abstract class Subsystem implements Sendable { + /** Constructor. */ + public Subsystem() { + String name = this.getClass().getSimpleName(); + name = name.substring(name.lastIndexOf('.') + 1); + SendableRegistry.addLW(this, name, name); + CommandScheduler.getInstance().registerSubsystem(this); + } + /** * This method is called periodically by the {@link CommandScheduler}. Useful for updating * subsystem-specific state that you don't want to offload to a {@link Command}. Teams should try * to be consistent within their own codebases about which responsibilities will be handled by * Commands, and which will be handled here. */ - default void periodic() {} + public void periodic() {} /** * This method is called periodically by the {@link CommandScheduler}. Useful for updating * subsystem-specific state that needs to be maintained for simulations, such as for updating * {@link edu.wpi.first.wpilibj.simulation} classes and setting simulated sensor readings. */ - default void simulationPeriodic() {} + public void simulationPeriodic() {} /** * Sets the default {@link Command} of the subsystem. The default command will be automatically @@ -46,7 +55,7 @@ public interface Subsystem { * * @param defaultCommand the default command to associate with this subsystem */ - default void setDefaultCommand(Command defaultCommand) { + public void setDefaultCommand(Command defaultCommand) { CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand); } @@ -54,7 +63,7 @@ public interface Subsystem { * Removes the default command for the subsystem. This will not cancel the default command if it * is currently running. */ - default void removeDefaultCommand() { + public void removeDefaultCommand() { CommandScheduler.getInstance().removeDefaultCommand(this); } @@ -64,7 +73,7 @@ public interface Subsystem { * * @return the default command associated with this subsystem */ - default Command getDefaultCommand() { + public Command getDefaultCommand() { return CommandScheduler.getInstance().getDefaultCommand(this); } @@ -74,15 +83,51 @@ public interface Subsystem { * * @return the scheduled command currently requiring this subsystem */ - default Command getCurrentCommand() { + public Command getCurrentCommand() { return CommandScheduler.getInstance().requiring(this); } + /** + * Gets the name of this Subsystem. + * + * @return Name + */ + public String getName() { + return SendableRegistry.getName(this); + } + + /** + * Sets the name of this Subsystem. + * + * @param name name + */ + public void setName(String name) { + SendableRegistry.setName(this, name); + } + + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ + public String getSubsystem() { + return SendableRegistry.getSubsystem(this); + } + + /** + * Sets the subsystem name of this Subsystem. + * + * @param subsystem subsystem name + */ + public void setSubsystem(String subsystem) { + SendableRegistry.setSubsystem(this, subsystem); + } + /** * Registers this subsystem with the {@link CommandScheduler}, allowing its {@link * Subsystem#periodic()} method to be called when the scheduler runs. */ - default void register() { + public void register() { CommandScheduler.getInstance().registerSubsystem(this); } @@ -93,7 +138,7 @@ public interface Subsystem { * @return the command * @see InstantCommand */ - default CommandBase runOnce(Runnable action) { + public Command runOnce(Runnable action) { return Commands.runOnce(action, this); } @@ -105,7 +150,7 @@ public interface Subsystem { * @return the command * @see RunCommand */ - default CommandBase run(Runnable action) { + public Command run(Runnable action) { return Commands.run(action, this); } @@ -118,7 +163,7 @@ public interface Subsystem { * @return the command * @see StartEndCommand */ - default CommandBase startEnd(Runnable start, Runnable end) { + public Command startEnd(Runnable start, Runnable end) { return Commands.startEnd(start, end, this); } @@ -130,7 +175,33 @@ public interface Subsystem { * @param end the action to run on interrupt * @return the command */ - default CommandBase runEnd(Runnable run, Runnable end) { + public Command runEnd(Runnable run, Runnable end) { return Commands.runEnd(run, end, this); } + + /** + * Associates a {@link Sendable} with this Subsystem. Also update the child's name. + * + * @param name name to give child + * @param child sendable + */ + public void addChild(String name, Sendable child) { + SendableRegistry.addLW(child, getSubsystem(), name); + } + + @Override + public void initSendable(SendableBuilder builder) { + builder.setSmartDashboardType("Subsystem"); + + builder.addBooleanProperty(".hasDefault", () -> getDefaultCommand() != null, null); + builder.addStringProperty( + ".default", + () -> getDefaultCommand() != null ? getDefaultCommand().getName() : "none", + null); + builder.addBooleanProperty(".hasCommand", () -> getCurrentCommand() != null, null); + builder.addStringProperty( + ".command", + () -> getCurrentCommand() != null ? getCurrentCommand().getName() : "none", + null); + } } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java index 6cf926ee23..c087f97541 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SubsystemBase.java @@ -4,84 +4,15 @@ package edu.wpi.first.wpilibj2.command; -import edu.wpi.first.util.sendable.Sendable; -import edu.wpi.first.util.sendable.SendableBuilder; -import edu.wpi.first.util.sendable.SendableRegistry; - /** * A base for subsystems that handles registration in the constructor, and provides a more intuitive * method for setting the default command. * *

This class is provided by the NewCommands VendorDep + * + * @deprecated All functionality provided by {@link SubsystemBase} has been merged into {@link + * Subsystem}. Use {@link Subsystem} instead. */ -public abstract class SubsystemBase implements Subsystem, Sendable { - /** Constructor. */ - public SubsystemBase() { - String name = this.getClass().getSimpleName(); - name = name.substring(name.lastIndexOf('.') + 1); - SendableRegistry.addLW(this, name, name); - CommandScheduler.getInstance().registerSubsystem(this); - } - - /** - * Gets the name of this Subsystem. - * - * @return Name - */ - public String getName() { - return SendableRegistry.getName(this); - } - - /** - * Sets the name of this Subsystem. - * - * @param name name - */ - public void setName(String name) { - SendableRegistry.setName(this, name); - } - - /** - * Gets the subsystem name of this Subsystem. - * - * @return Subsystem name - */ - public String getSubsystem() { - return SendableRegistry.getSubsystem(this); - } - - /** - * Sets the subsystem name of this Subsystem. - * - * @param subsystem subsystem name - */ - public void setSubsystem(String subsystem) { - SendableRegistry.setSubsystem(this, subsystem); - } - - /** - * Associates a {@link Sendable} with this Subsystem. Also update the child's name. - * - * @param name name to give child - * @param child sendable - */ - public void addChild(String name, Sendable child) { - SendableRegistry.addLW(child, getSubsystem(), name); - } - - @Override - public void initSendable(SendableBuilder builder) { - builder.setSmartDashboardType("Subsystem"); - - builder.addBooleanProperty(".hasDefault", () -> getDefaultCommand() != null, null); - builder.addStringProperty( - ".default", - () -> getDefaultCommand() != null ? getDefaultCommand().getName() : "none", - null); - builder.addBooleanProperty(".hasCommand", () -> getCurrentCommand() != null, null); - builder.addStringProperty( - ".command", - () -> getCurrentCommand() != null ? getCurrentCommand().getName() : "none", - null); - } -} +@Deprecated(since = "2024", forRemoval = true) +@SuppressWarnings("PMD.AbstractClassWithoutAnyMethod") +public abstract class SubsystemBase extends Subsystem {} diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java index 5bf82a48e0..3eacac3301 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommand.java @@ -31,7 +31,7 @@ import java.util.function.Supplier; * *

This class is provided by the NewCommands VendorDep */ -public class SwerveControllerCommand extends CommandBase { +public class SwerveControllerCommand extends Command { private final Timer m_timer = new Timer(); private final Trajectory m_trajectory; private final Supplier m_pose; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java index 231012d758..c8de5ba226 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileCommand.java @@ -16,7 +16,7 @@ import java.util.function.Consumer; * *

This class is provided by the NewCommands VendorDep */ -public class TrapezoidProfileCommand extends CommandBase { +public class TrapezoidProfileCommand extends Command { private final TrapezoidProfile m_profile; private final Consumer m_output; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java index 1db661928e..372e223d34 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/TrapezoidProfileSubsystem.java @@ -14,7 +14,7 @@ import edu.wpi.first.math.trajectory.TrapezoidProfile; * *

This class is provided by the NewCommands VendorDep */ -public abstract class TrapezoidProfileSubsystem extends SubsystemBase { +public abstract class TrapezoidProfileSubsystem extends Subsystem { private final double m_period; private final TrapezoidProfile.Constraints m_constraints; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java index 5fa9173772..e7b32be8f6 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitCommand.java @@ -13,7 +13,7 @@ import edu.wpi.first.wpilibj.Timer; * *

This class is provided by the NewCommands VendorDep */ -public class WaitCommand extends CommandBase { +public class WaitCommand extends Command { protected Timer m_timer = new Timer(); private final double m_duration; diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java index 4d51e62108..b96bc26a3a 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WaitUntilCommand.java @@ -15,7 +15,7 @@ import java.util.function.BooleanSupplier; * *

This class is provided by the NewCommands VendorDep */ -public class WaitUntilCommand extends CommandBase { +public class WaitUntilCommand extends Command { private final BooleanSupplier m_condition; /** diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java index c48871c5f4..c687f0a4fb 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/WrapperCommand.java @@ -14,7 +14,7 @@ import java.util.Set; * added to any other composition or scheduled individually, and the composition requires all * subsystems its components require. */ -public abstract class WrapperCommand extends CommandBase { +public abstract class WrapperCommand extends Command { protected final Command m_command; /** diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp index 87494d77cd..97a25d2eb2 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/Command.cpp @@ -4,6 +4,9 @@ #include "frc2/command/Command.h" +#include +#include + #include "frc2/command/CommandHelper.h" #include "frc2/command/CommandScheduler.h" #include "frc2/command/ConditionalCommand.h" @@ -19,6 +22,10 @@ using namespace frc2; +Command::Command() { + wpi::SendableRegistry::Add(this, GetTypeName(*this)); +} + Command::~Command() { CommandScheduler::GetInstance().Cancel(this); } @@ -32,6 +39,42 @@ void Command::Initialize() {} void Command::Execute() {} void Command::End(bool interrupted) {} +wpi::SmallSet Command::GetRequirements() const { + return m_requirements; +} + +void Command::AddRequirements(std::initializer_list requirements) { + m_requirements.insert(requirements.begin(), requirements.end()); +} + +void Command::AddRequirements(std::span requirements) { + m_requirements.insert(requirements.begin(), requirements.end()); +} + +void Command::AddRequirements(wpi::SmallSet requirements) { + m_requirements.insert(requirements.begin(), requirements.end()); +} + +void Command::AddRequirements(Subsystem* requirement) { + m_requirements.insert(requirement); +} + +void Command::SetName(std::string_view name) { + wpi::SendableRegistry::SetName(this, name); +} + +std::string Command::GetName() const { + return wpi::SendableRegistry::GetName(this); +} + +std::string Command::GetSubsystem() const { + return wpi::SendableRegistry::GetSubsystem(this); +} + +void Command::SetSubsystem(std::string_view subsystem) { + wpi::SendableRegistry::SetSubsystem(this, subsystem); +} + CommandPtr Command::WithTimeout(units::second_t duration) && { return std::move(*this).ToPtr().WithTimeout(duration); } @@ -125,12 +168,6 @@ bool Command::HasRequirement(Subsystem* requirement) const { return hasRequirement; } -std::string Command::GetName() const { - return GetTypeName(*this); -} - -void Command::SetName(std::string_view name) {} - bool Command::IsComposed() const { return m_isComposed; } @@ -139,6 +176,39 @@ void Command::SetComposed(bool isComposed) { m_isComposed = isComposed; } +void Command::InitSendable(wpi::SendableBuilder& builder) { + builder.SetSmartDashboardType("Command"); + builder.AddStringProperty( + ".name", [this] { return GetName(); }, nullptr); + builder.AddBooleanProperty( + "running", [this] { return IsScheduled(); }, + [this](bool value) { + bool isScheduled = IsScheduled(); + if (value && !isScheduled) { + Schedule(); + } else if (!value && isScheduled) { + Cancel(); + } + }); + builder.AddBooleanProperty( + ".isParented", [this] { return IsComposed(); }, nullptr); + builder.AddStringProperty( + "interruptBehavior", + [this] { + switch (GetInterruptionBehavior()) { + case Command::InterruptionBehavior::kCancelIncoming: + return "kCancelIncoming"; + case Command::InterruptionBehavior::kCancelSelf: + return "kCancelSelf"; + default: + return "Invalid"; + } + }, + nullptr); + builder.AddBooleanProperty( + "runsWhenDisabled", [this] { return RunsWhenDisabled(); }, nullptr); +} + namespace frc2 { bool RequirementsDisjoint(Command* first, Command* second) { bool disjoint = true; diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp index 416c78be15..7e2fad1a9f 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandBase.cpp @@ -3,82 +3,3 @@ // the WPILib BSD license file in the root directory of this project. #include "frc2/command/CommandBase.h" - -#include -#include - -using namespace frc2; - -CommandBase::CommandBase() { - wpi::SendableRegistry::Add(this, GetTypeName(*this)); -} - -void CommandBase::AddRequirements( - std::initializer_list requirements) { - m_requirements.insert(requirements.begin(), requirements.end()); -} - -void CommandBase::AddRequirements(std::span requirements) { - m_requirements.insert(requirements.begin(), requirements.end()); -} - -void CommandBase::AddRequirements(wpi::SmallSet requirements) { - m_requirements.insert(requirements.begin(), requirements.end()); -} - -void CommandBase::AddRequirements(Subsystem* requirement) { - m_requirements.insert(requirement); -} - -wpi::SmallSet CommandBase::GetRequirements() const { - return m_requirements; -} - -void CommandBase::SetName(std::string_view name) { - wpi::SendableRegistry::SetName(this, name); -} - -std::string CommandBase::GetName() const { - return wpi::SendableRegistry::GetName(this); -} - -std::string CommandBase::GetSubsystem() const { - return wpi::SendableRegistry::GetSubsystem(this); -} - -void CommandBase::SetSubsystem(std::string_view subsystem) { - wpi::SendableRegistry::SetSubsystem(this, subsystem); -} - -void CommandBase::InitSendable(wpi::SendableBuilder& builder) { - builder.SetSmartDashboardType("Command"); - builder.AddStringProperty( - ".name", [this] { return GetName(); }, nullptr); - builder.AddBooleanProperty( - "running", [this] { return IsScheduled(); }, - [this](bool value) { - bool isScheduled = IsScheduled(); - if (value && !isScheduled) { - Schedule(); - } else if (!value && isScheduled) { - Cancel(); - } - }); - builder.AddBooleanProperty( - ".isParented", [this] { return IsComposed(); }, nullptr); - builder.AddStringProperty( - "interruptBehavior", - [this] { - switch (GetInterruptionBehavior()) { - case Command::InterruptionBehavior::kCancelIncoming: - return "kCancelIncoming"; - case Command::InterruptionBehavior::kCancelSelf: - return "kCancelSelf"; - default: - return "Invalid"; - } - }, - nullptr); - builder.AddBooleanProperty( - "runsWhenDisabled", [this] { return RunsWhenDisabled(); }, nullptr); -} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp index 5a9a50427d..6b2b86e3c2 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandPtr.cpp @@ -236,12 +236,12 @@ CommandPtr CommandPtr::WithName(std::string_view name) && { return std::move(wrapper).ToPtr(); } -CommandBase* CommandPtr::get() const& { +Command* CommandPtr::get() const& { AssertValid(); return m_ptr.get(); } -std::unique_ptr CommandPtr::Unwrap() && { +std::unique_ptr CommandPtr::Unwrap() && { AssertValid(); return std::move(m_ptr); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 6d3256d4b7..900f7bddd1 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -291,6 +291,10 @@ void CommandScheduler::UnregisterSubsystem( } } +void CommandScheduler::UnregisterAllSubsystems() { + m_impl->subsystems.clear(); +} + void CommandScheduler::SetDefaultCommand(Subsystem* subsystem, CommandPtr&& defaultCommand) { if (!defaultCommand.get()->HasRequirement(subsystem)) { diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp index e8d083bd52..4c07c7ae24 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/ConditionalCommand.cpp @@ -66,7 +66,7 @@ Command::InterruptionBehavior ConditionalCommand::GetInterruptionBehavior() } void ConditionalCommand::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddStringProperty( "onTrue", [this] { return m_onTrue->GetName(); }, nullptr); builder.AddStringProperty( diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp index 14c28c3a72..a6b5c1c264 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp @@ -97,7 +97,7 @@ void ParallelDeadlineGroup::SetDeadline(std::unique_ptr&& deadline) { } void ParallelDeadlineGroup::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddStringProperty( "deadline", [this] { return m_deadline->GetName(); }, nullptr); diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp index cc1b815815..49bff658ce 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/ProxyCommand.cpp @@ -41,7 +41,7 @@ bool ProxyCommand::IsFinished() { } void ProxyCommand::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddStringProperty( "proxied", [this] { diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp index 7a71a0d473..3e289c1252 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/RamseteCommand.cpp @@ -161,7 +161,7 @@ bool RamseteCommand::IsFinished() { } void RamseteCommand::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddDoubleProperty( "leftVelocity", [this] { return m_prevSpeeds.left.value(); }, nullptr); builder.AddDoubleProperty( diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp index f9b57c3e19..2e74c8c72f 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/RepeatCommand.cpp @@ -56,7 +56,7 @@ Command::InterruptionBehavior RepeatCommand::GetInterruptionBehavior() const { } void RepeatCommand::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddStringProperty( "command", [this] { return m_command->GetName(); }, nullptr); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp index 7888c1d175..b9ea3d56ec 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp @@ -83,7 +83,7 @@ void SequentialCommandGroup::AddCommands( } void SequentialCommandGroup::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddIntegerProperty( "index", [this] { return m_currentCommandIndex; }, nullptr); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp index d1d50e1de0..9fc6e8adac 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/Subsystem.cpp @@ -8,6 +8,12 @@ #include "frc2/command/Commands.h" using namespace frc2; + +Subsystem::Subsystem() { + wpi::SendableRegistry::AddLW(this, GetTypeName(*this)); + CommandScheduler::GetInstance().RegisterSubsystem({this}); +} + Subsystem::~Subsystem() { CommandScheduler::GetInstance().UnregisterSubsystem(this); } @@ -33,6 +39,26 @@ Command* Subsystem::GetCurrentCommand() const { return CommandScheduler::GetInstance().Requiring(this); } +std::string Subsystem::GetName() const { + return wpi::SendableRegistry::GetName(this); +} + +void Subsystem::SetName(std::string_view name) { + wpi::SendableRegistry::SetName(this, name); +} + +std::string Subsystem::GetSubsystem() const { + return wpi::SendableRegistry::GetSubsystem(this); +} + +void Subsystem::SetSubsystem(std::string_view name) { + wpi::SendableRegistry::SetSubsystem(this, name); +} + +void Subsystem::AddChild(std::string name, wpi::Sendable* child) { + wpi::SendableRegistry::AddLW(child, GetSubsystem(), name); +} + void Subsystem::Register() { return CommandScheduler::GetInstance().RegisterSubsystem(this); } @@ -54,3 +80,33 @@ CommandPtr Subsystem::RunEnd(std::function run, std::function end) { return cmd::RunEnd(std::move(run), std::move(end), {this}); } + +void Subsystem::InitSendable(wpi::SendableBuilder& builder) { + builder.SetSmartDashboardType("Subsystem"); + builder.AddBooleanProperty( + ".hasDefault", [this] { return GetDefaultCommand() != nullptr; }, + nullptr); + builder.AddStringProperty( + ".default", + [this]() -> std::string { + auto command = GetDefaultCommand(); + if (command == nullptr) { + return "none"; + } + return command->GetName(); + }, + nullptr); + builder.AddBooleanProperty( + ".hasCommand", [this] { return GetCurrentCommand() != nullptr; }, + nullptr); + builder.AddStringProperty( + ".command", + [this]() -> std::string { + auto command = GetCurrentCommand(); + if (command == nullptr) { + return "none"; + } + return command->GetName(); + }, + nullptr); +} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp index 8216a07582..71e411999e 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/SubsystemBase.cpp @@ -12,57 +12,4 @@ using namespace frc2; -SubsystemBase::SubsystemBase() { - wpi::SendableRegistry::AddLW(this, GetTypeName(*this)); - CommandScheduler::GetInstance().RegisterSubsystem({this}); -} - -void SubsystemBase::InitSendable(wpi::SendableBuilder& builder) { - builder.SetSmartDashboardType("Subsystem"); - builder.AddBooleanProperty( - ".hasDefault", [this] { return GetDefaultCommand() != nullptr; }, - nullptr); - builder.AddStringProperty( - ".default", - [this]() -> std::string { - auto command = GetDefaultCommand(); - if (command == nullptr) { - return "none"; - } - return command->GetName(); - }, - nullptr); - builder.AddBooleanProperty( - ".hasCommand", [this] { return GetCurrentCommand() != nullptr; }, - nullptr); - builder.AddStringProperty( - ".command", - [this]() -> std::string { - auto command = GetCurrentCommand(); - if (command == nullptr) { - return "none"; - } - return command->GetName(); - }, - nullptr); -} - -std::string SubsystemBase::GetName() const { - return wpi::SendableRegistry::GetName(this); -} - -void SubsystemBase::SetName(std::string_view name) { - wpi::SendableRegistry::SetName(this, name); -} - -std::string SubsystemBase::GetSubsystem() const { - return wpi::SendableRegistry::GetSubsystem(this); -} - -void SubsystemBase::SetSubsystem(std::string_view name) { - wpi::SendableRegistry::SetSubsystem(this, name); -} - -void SubsystemBase::AddChild(std::string name, wpi::Sendable* child) { - wpi::SendableRegistry::AddLW(child, GetSubsystem(), name); -} +SubsystemBase::SubsystemBase() {} diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp index c5fed484f2..36b15dd2d4 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/WaitCommand.cpp @@ -30,7 +30,7 @@ bool WaitCommand::RunsWhenDisabled() const { } void WaitCommand::InitSendable(wpi::SendableBuilder& builder) { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddDoubleProperty( "duration", [this] { return m_duration.value(); }, nullptr); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h index 8f608d5ba9..2ad19fd39a 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/Command.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/Command.h @@ -13,6 +13,7 @@ #include #include #include +#include #include "frc2/command/Subsystem.h" @@ -41,10 +42,9 @@ std::string GetTypeName(const T& type) { * @see CommandScheduler * @see CommandHelper */ -class Command { +class Command : public wpi::Sendable, public wpi::SendableHelper { public: - Command() = default; - virtual ~Command(); + ~Command() override; Command(const Command&) = default; Command& operator=(const Command& rhs); @@ -92,7 +92,91 @@ class Command { * @return the set of subsystems that are required * @see InterruptionBehavior */ - virtual wpi::SmallSet GetRequirements() const = 0; + virtual wpi::SmallSet GetRequirements() const; + + /** + * Adds the specified Subsystem requirements to the command. + * + * The scheduler will prevent two commands that require the same subsystem + * from being scheduled simultaneously. + * + * Note that the scheduler determines the requirements of a command when it + * is scheduled, so this method should normally be called from the command's + * constructor. + * + * @param requirements the Subsystem requirements to add + */ + void AddRequirements(std::initializer_list requirements); + + /** + * Adds the specified Subsystem requirements to the command. + * + * The scheduler will prevent two commands that require the same subsystem + * from being scheduled simultaneously. + * + * Note that the scheduler determines the requirements of a command when it + * is scheduled, so this method should normally be called from the command's + * constructor. + * + * @param requirements the Subsystem requirements to add + */ + void AddRequirements(std::span requirements); + + /** + * Adds the specified Subsystem requirements to the command. + * + * The scheduler will prevent two commands that require the same subsystem + * from being scheduled simultaneously. + * + * Note that the scheduler determines the requirements of a command when it + * is scheduled, so this method should normally be called from the command's + * constructor. + * + * @param requirements the Subsystem requirements to add + */ + void AddRequirements(wpi::SmallSet requirements); + + /** + * Adds the specified Subsystem requirement to the command. + * + * The scheduler will prevent two commands that require the same subsystem + * from being scheduled simultaneously. + * + * Note that the scheduler determines the requirements of a command when it + * is scheduled, so this method should normally be called from the command's + * constructor. + * + * @param requirement the Subsystem requirement to add + */ + void AddRequirements(Subsystem* requirement); + + /** + * Gets the name of this Command. + * + * @return Name + */ + std::string GetName() const; + + /** + * Sets the name of this Command. + * + * @param name name + */ + void SetName(std::string_view name); + + /** + * Gets the subsystem name of this Command. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; + + /** + * Sets the subsystem name of this Command. + * + * @param subsystem subsystem name + */ + void SetSubsystem(std::string_view subsystem); /** * An enum describing the command's behavior when another command with a @@ -345,28 +429,19 @@ class Command { return InterruptionBehavior::kCancelSelf; } - /** - * Gets the name of this Command. Defaults to the simple class name if not - * overridden. - * - * @return The display name of the Command - */ - virtual std::string GetName() const; - - /** - * Sets the name of this Command. Nullop if not overridden. - * - * @param name The display name of the Command. - */ - virtual void SetName(std::string_view name); - /** * Transfers ownership of this command to a unique pointer. Used for * decorator methods. */ virtual CommandPtr ToPtr() && = 0; + void InitSendable(wpi::SendableBuilder& builder) override; + protected: + Command(); + + wpi::SmallSet m_requirements; + /** * Transfers ownership of this command to a unique pointer. Used for * decorator methods. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h index 510d0000cf..ea24e42d97 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandBase.h @@ -4,14 +4,7 @@ #pragma once -#include -#include -#include -#include - -#include -#include -#include +#include #include "frc2/command/Command.h" @@ -20,106 +13,13 @@ namespace frc2 { * A Sendable base class for Commands. * * This class is provided by the NewCommands VendorDep + * + * @deprecated All functionality provided by CommandBase has been merged into + * Command. Use Command instead. */ -class CommandBase : public Command, - public wpi::Sendable, - public wpi::SendableHelper { - public: - /** - * Adds the specified Subsystem requirements to the command. - * - * The scheduler will prevent two commands that require the same subsystem - * from being scheduled simultaneously. - * - * Note that the scheduler determines the requirements of a command when it - * is scheduled, so this method should normally be called from the command's - * constructor. - * - * @param requirements the Subsystem requirements to add - */ - void AddRequirements(std::initializer_list requirements); - - /** - * Adds the specified Subsystem requirements to the command. - * - * The scheduler will prevent two commands that require the same subsystem - * from being scheduled simultaneously. - * - * Note that the scheduler determines the requirements of a command when it - * is scheduled, so this method should normally be called from the command's - * constructor. - * - * @param requirements the Subsystem requirements to add - */ - void AddRequirements(std::span requirements); - - /** - * Adds the specified Subsystem requirements to the command. - * - * The scheduler will prevent two commands that require the same subsystem - * from being scheduled simultaneously. - * - * Note that the scheduler determines the requirements of a command when it - * is scheduled, so this method should normally be called from the command's - * constructor. - * - * @param requirements the Subsystem requirements to add - */ - void AddRequirements(wpi::SmallSet requirements); - - /** - * Adds the specified Subsystem requirement to the command. - * - * The scheduler will prevent two commands that require the same subsystem - * from being scheduled simultaneously. - * - * Note that the scheduler determines the requirements of a command when it - * is scheduled, so this method should normally be called from the command's - * constructor. - * - * @param requirement the Subsystem requirement to add - */ - void AddRequirements(Subsystem* requirement); - - /** - * Gets the Subsystem requirements of the command. - * - * @return the Command's Subsystem requirements - */ - wpi::SmallSet GetRequirements() const override; - - /** - * Sets the name of this Command. - * - * @param name name - */ - void SetName(std::string_view name) override; - - /** - * Gets the name of this Command. - * - * @return Name - */ - std::string GetName() const override; - - /** - * Gets the subsystem name of this Command. - * - * @return Subsystem name - */ - std::string GetSubsystem() const; - - /** - * Sets the subsystem name of this Command. - * - * @param subsystem subsystem name - */ - void SetSubsystem(std::string_view subsystem); - - void InitSendable(wpi::SendableBuilder& builder) override; - +class [[deprecated("Use Command instead")]] CommandBase : public Command { protected: + WPI_DEPRECATED("Use Command instead") CommandBase(); - wpi::SmallSet m_requirements; }; } // namespace frc2 diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h index 878d63b3ff..bb344a3505 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandPtr.h @@ -13,7 +13,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" namespace frc2 { /** @@ -28,7 +28,7 @@ namespace frc2 { */ class CommandPtr final { public: - explicit CommandPtr(std::unique_ptr&& command) + explicit CommandPtr(std::unique_ptr&& command) : m_ptr(std::move(command)) {} template T> @@ -269,15 +269,15 @@ class CommandPtr final { /** * Get a raw pointer to the held command. */ - CommandBase* get() const&; + Command* get() const&; // Prevent calls on a temporary, as the returned pointer would be invalid - CommandBase* get() && = delete; + Command* get() && = delete; /** * Convert to the underlying unique_ptr. */ - std::unique_ptr Unwrap() &&; + std::unique_ptr Unwrap() &&; /** * Schedules this command. @@ -336,7 +336,7 @@ class CommandPtr final { std::vector&& vec); private: - std::unique_ptr m_ptr; + std::unique_ptr m_ptr; void AssertValid() const; }; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h index 4b65f30812..0d5040bdf7 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h @@ -158,6 +158,13 @@ class CommandScheduler final : public nt::NTSendable, void UnregisterSubsystem(std::initializer_list subsystems); void UnregisterSubsystem(std::span subsystems); + /** + * Un-registers all registered Subsystems with the scheduler. All currently + * registered subsystems will no longer have their periodic block called, and + * will not have their default command scheduled. + */ + void UnregisterAllSubsystems(); + /** * Sets the default command for a subsystem. Registers that subsystem if it * is not already registered. Default commands will run whenever there is no diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h index 20a2a1272a..676ee0c953 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ConditionalCommand.h @@ -9,7 +9,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -26,8 +26,7 @@ namespace frc2 { * * @see ScheduleCommand */ -class ConditionalCommand - : public CommandHelper { +class ConditionalCommand : public CommandHelper { public: /** * Creates a new ConditionalCommand. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h index ef2b5b93ab..223f4c2f6a 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/FunctionalCommand.h @@ -8,7 +8,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -21,7 +21,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class FunctionalCommand : public CommandHelper { +class FunctionalCommand : public CommandHelper { public: /** * Creates a new FunctionalCommand. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h index 8ebdbe074b..e78718700b 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/MecanumControllerCommand.h @@ -23,7 +23,7 @@ #include #include -#include "CommandBase.h" +#include "Command.h" #include "CommandHelper.h" #pragma once @@ -51,7 +51,7 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ class MecanumControllerCommand - : public CommandHelper { + : public CommandHelper { public: /** * Constructs a new MecanumControllerCommand that when executed will follow diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h index 607799bebe..7db5e3fa36 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/NotifierCommand.h @@ -11,7 +11,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -27,7 +27,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class NotifierCommand : public CommandHelper { +class NotifierCommand : public CommandHelper { public: /** * Creates a new NotifierCommand. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h index 818c50b05e..c3579740bb 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/PIDCommand.h @@ -10,7 +10,7 @@ #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -24,7 +24,7 @@ namespace frc2 { * * @see PIDController */ -class PIDCommand : public CommandHelper { +class PIDCommand : public CommandHelper { public: /** * Creates a new PIDCommand, which controls the given output with a diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h index 426e3ecc63..27683ed36d 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/PIDSubsystem.h @@ -6,7 +6,7 @@ #include -#include "frc2/command/SubsystemBase.h" +#include "frc2/command/Subsystem.h" namespace frc2 { /** @@ -17,7 +17,7 @@ namespace frc2 { * * @see PIDController */ -class PIDSubsystem : public SubsystemBase { +class PIDSubsystem : public Subsystem { public: /** * Creates a new PIDSubsystem. diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h index 2fe6f937ab..bb33a059fa 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelCommandGroup.h @@ -33,7 +33,7 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ class ParallelCommandGroup - : public CommandHelper { + : public CommandHelper { public: /** * Creates a new ParallelCommandGroup. The given commands will be executed diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h index adb29db57f..9e253fbffd 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelDeadlineGroup.h @@ -34,7 +34,7 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ class ParallelDeadlineGroup - : public CommandHelper { + : public CommandHelper { public: /** * Creates a new ParallelDeadlineGroup. The given commands (including the diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h index 4a760a0c9e..caefa48fa3 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ParallelRaceGroup.h @@ -32,7 +32,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class ParallelRaceGroup : public CommandHelper { +class ParallelRaceGroup : public CommandHelper { public: /** * Creates a new ParallelCommandRace. The given commands will be executed diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h index 3fbe726cbd..596ac1bda6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDCommand.h @@ -12,7 +12,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -28,7 +28,7 @@ namespace frc2 { */ template class ProfiledPIDCommand - : public CommandHelper> { + : public CommandHelper> { using Distance_t = units::unit_t; using Velocity = units::compound_unit>; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h index cfdfc6b631..b78f081bc3 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProfiledPIDSubsystem.h @@ -7,7 +7,7 @@ #include #include -#include "frc2/command/SubsystemBase.h" +#include "frc2/command/Subsystem.h" namespace frc2 { /** @@ -19,7 +19,7 @@ namespace frc2 { * @see ProfiledPIDController */ template -class ProfiledPIDSubsystem : public SubsystemBase { +class ProfiledPIDSubsystem : public Subsystem { using Distance_t = units::unit_t; using Velocity = units::compound_unit>; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h index b4a00a5221..63d37693e3 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ProxyCommand.h @@ -9,7 +9,7 @@ #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" #include "frc2/command/SetUtilities.h" @@ -21,7 +21,7 @@ namespace frc2 { * *

This class is provided by the NewCommands VendorDep */ -class ProxyCommand : public CommandHelper { +class ProxyCommand : public CommandHelper { public: /** * Creates a new ProxyCommand that schedules the supplied command when diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h index d375e11ff6..729c46b285 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/RamseteCommand.h @@ -19,7 +19,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -42,7 +42,7 @@ namespace frc2 { * @see RamseteController * @see Trajectory */ -class RamseteCommand : public CommandHelper { +class RamseteCommand : public CommandHelper { public: /** * Constructs a new RamseteCommand that, when executed, will follow the diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h index 7ae603fcf7..9c1a5d1528 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/RepeatCommand.h @@ -13,7 +13,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -29,7 +29,7 @@ namespace frc2 { * *

This class is provided by the NewCommands VendorDep */ -class RepeatCommand : public CommandHelper { +class RepeatCommand : public CommandHelper { public: /** * Creates a new RepeatCommand. Will run another command repeatedly, diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h index 63cc3b331e..eedb72b111 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/ScheduleCommand.h @@ -8,7 +8,7 @@ #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" #include "frc2/command/SetUtilities.h" @@ -21,7 +21,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class ScheduleCommand : public CommandHelper { +class ScheduleCommand : public CommandHelper { public: /** * Creates a new ScheduleCommand that schedules the given commands when diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h index b4548e5ac3..a42cbc032e 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SelectCommand.h @@ -18,7 +18,7 @@ #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/PrintCommand.h" namespace frc2 { @@ -35,7 +35,7 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ template -class SelectCommand : public CommandHelper> { +class SelectCommand : public CommandHelper> { public: /** * Creates a new SelectCommand. @@ -113,7 +113,7 @@ class SelectCommand : public CommandHelper> { } void InitSendable(wpi::SendableBuilder& builder) override { - CommandBase::InitSendable(builder); + Command::InitSendable(builder); builder.AddStringProperty( "selected", diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h b/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h index a0da1b34be..dac6cc7d45 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SequentialCommandGroup.h @@ -37,7 +37,7 @@ const size_t invalid_index = std::numeric_limits::max(); * This class is provided by the NewCommands VendorDep */ class SequentialCommandGroup - : public CommandHelper { + : public CommandHelper { public: /** * Creates a new SequentialCommandGroup. The given commands will be run diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h index 840488d432..a07a684847 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/Subsystem.h @@ -5,8 +5,11 @@ #pragma once #include +#include #include +#include + #include "frc2/command/CommandScheduler.h" namespace frc2 { @@ -23,22 +26,19 @@ class CommandPtr; * subsystem should generally remain encapsulated and not be shared by other * parts of the robot. * - *

Subsystems must be registered with the scheduler with the + *

Subsystems are automatically registered with the scheduler with the * CommandScheduler.RegisterSubsystem() method in order for the - * Periodic() method to be called. It is recommended that this method be called - * from the constructor of users' Subsystem implementations. The - * SubsystemBase class offers a simple base for user implementations - * that handles this. + * Periodic() method to be called. * * This class is provided by the NewCommands VendorDep * * @see Command * @see CommandScheduler - * @see SubsystemBase */ -class Subsystem { +class Subsystem : public wpi::Sendable, public wpi::SendableHelper { public: - virtual ~Subsystem(); + ~Subsystem() override; + /** * This method is called periodically by the CommandScheduler. Useful for * updating subsystem-specific state that you don't want to offload to a @@ -110,6 +110,43 @@ class Subsystem { */ void Register(); + /** + * Gets the name of this Subsystem. + * + * @return Name + */ + std::string GetName() const; + + /** + * Sets the name of this Subsystem. + * + * @param name name + */ + void SetName(std::string_view name); + + /** + * Gets the subsystem name of this Subsystem. + * + * @return Subsystem name + */ + std::string GetSubsystem() const; + + /** + * Sets the subsystem name of this Subsystem. + * + * @param name subsystem name + */ + void SetSubsystem(std::string_view name); + + /** + * Associate a Sendable with this Subsystem. + * Also update the child's name. + * + * @param name name to give child + * @param child sendable + */ + void AddChild(std::string name, wpi::Sendable* child); + /** * Constructs a command that runs an action once and finishes. Requires this * subsystem. @@ -147,5 +184,10 @@ class Subsystem { */ [[nodiscard]] CommandPtr RunEnd(std::function run, std::function end); + + void InitSendable(wpi::SendableBuilder& builder) override; + + protected: + Subsystem(); }; } // namespace frc2 diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SubsystemBase.h b/wpilibNewCommands/src/main/native/include/frc2/command/SubsystemBase.h index 86fb026fc1..7af5463699 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SubsystemBase.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SubsystemBase.h @@ -4,11 +4,7 @@ #pragma once -#include -#include - -#include -#include +#include #include "frc2/command/Subsystem.h" @@ -18,51 +14,13 @@ namespace frc2 { * provides a more intuitive method for setting the default command. * * This class is provided by the NewCommands VendorDep + * + * @deprecated All functionality provided by SubsystemBase has been merged into + * Subsystem. Use Subsystem instead. */ -class SubsystemBase : public Subsystem, - public wpi::Sendable, - public wpi::SendableHelper { - public: - void InitSendable(wpi::SendableBuilder& builder) override; - - /** - * Gets the name of this Subsystem. - * - * @return Name - */ - std::string GetName() const; - - /** - * Sets the name of this Subsystem. - * - * @param name name - */ - void SetName(std::string_view name); - - /** - * Gets the subsystem name of this Subsystem. - * - * @return Subsystem name - */ - std::string GetSubsystem() const; - - /** - * Sets the subsystem name of this Subsystem. - * - * @param name subsystem name - */ - void SetSubsystem(std::string_view name); - - /** - * Associate a Sendable with this Subsystem. - * Also update the child's name. - * - * @param name name to give child - * @param child sendable - */ - void AddChild(std::string name, wpi::Sendable* child); - +class [[deprecated("Use Subsystem instead")]] SubsystemBase : public Subsystem { protected: + WPI_DEPRECATED("Use Subsystem instead") SubsystemBase(); }; } // namespace frc2 diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h index d51ae1e47e..24d3f1dbcf 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/SwerveControllerCommand.h @@ -21,7 +21,7 @@ #include #include -#include "CommandBase.h" +#include "Command.h" #include "CommandHelper.h" #pragma once @@ -51,7 +51,7 @@ namespace frc2 { */ template class SwerveControllerCommand - : public CommandHelper> { + : public CommandHelper> { using voltsecondspermeter = units::compound_unit>; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h index 1d00d668f0..292bea9dbc 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileCommand.h @@ -11,7 +11,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -25,7 +25,7 @@ namespace frc2 { */ template class TrapezoidProfileCommand - : public CommandHelper> { + : public CommandHelper> { using Distance_t = units::unit_t; using Velocity = units::compound_unit>; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h index abce33ce20..2686a30aa0 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/TrapezoidProfileSubsystem.h @@ -7,7 +7,7 @@ #include #include -#include "frc2/command/SubsystemBase.h" +#include "frc2/command/Subsystem.h" namespace frc2 { /** @@ -18,7 +18,7 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ template -class TrapezoidProfileSubsystem : public SubsystemBase { +class TrapezoidProfileSubsystem : public Subsystem { using Distance_t = units::unit_t; using Velocity = units::compound_unit>; diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h index 5d3f27d7d9..e28615e468 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/WaitCommand.h @@ -7,7 +7,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -16,7 +16,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class WaitCommand : public CommandHelper { +class WaitCommand : public CommandHelper { public: /** * Creates a new WaitCommand. This command will do nothing, and end after the diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/WaitUntilCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/WaitUntilCommand.h index 3b26999abe..377a1ba9a6 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/WaitUntilCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/WaitUntilCommand.h @@ -8,7 +8,7 @@ #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -18,7 +18,7 @@ namespace frc2 { * * This class is provided by the NewCommands VendorDep */ -class WaitUntilCommand : public CommandHelper { +class WaitUntilCommand : public CommandHelper { public: /** * Creates a new WaitUntilCommand that ends after a given condition becomes diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h b/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h index c467746704..98e8b20082 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/WrapperCommand.h @@ -13,7 +13,7 @@ #include #include -#include "frc2/command/CommandBase.h" +#include "frc2/command/Command.h" #include "frc2/command/CommandHelper.h" namespace frc2 { @@ -24,7 +24,7 @@ namespace frc2 { *

Wrapped commands may only be used through the wrapper, trying to directly * schedule them or add them to a group will throw an exception. */ -class WrapperCommand : public CommandHelper { +class WrapperCommand : public CommandHelper { public: /** * Wrap a command. diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java index 47657e19ed..a56f62ae48 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandRequirementsTest.java @@ -15,7 +15,7 @@ class CommandRequirementsTest extends CommandTestBase { @Test void requirementInterruptTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement); Command interrupted = interruptedHolder.getMock(); @@ -42,7 +42,7 @@ class CommandRequirementsTest extends CommandTestBase { @Test void requirementUninterruptibleTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; Command notInterrupted = new RunCommand(() -> {}, requirement) @@ -61,7 +61,7 @@ class CommandRequirementsTest extends CommandTestBase { @Test void defaultCommandRequirementErrorTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem system = new SubsystemBase() {}; + Subsystem system = new Subsystem() {}; Command missingRequirement = new WaitUntilCommand(() -> false); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java index 6d2a788de6..c89ed7f7f3 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java @@ -21,7 +21,7 @@ class CommandSendableButtonTest extends CommandTestBase { private AtomicInteger m_schedule; private AtomicInteger m_cancel; private BooleanPublisher m_publish; - private CommandBase m_command; + private Command m_command; @BeforeEach void setUp() { diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java index 1d46fb5654..13f6597738 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java @@ -23,6 +23,7 @@ public class CommandTestBase { CommandScheduler.getInstance().enable(); CommandScheduler.getInstance().getActiveButtonLoop().clear(); CommandScheduler.getInstance().clearComposedCommands(); + CommandScheduler.getInstance().unregisterAllSubsystems(); setDSEnabled(true); } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java index 4659f0ec3d..b24f948ebf 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java @@ -46,9 +46,9 @@ class ConditionalCommandTest extends CommandTestBase { @Test void conditionalCommandRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java index 23ae47d648..9b93fffe8a 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java @@ -14,7 +14,7 @@ class DefaultCommandTest extends CommandTestBase { @Test void defaultCommandScheduleTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new Subsystem() {}; MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); @@ -29,7 +29,7 @@ class DefaultCommandTest extends CommandTestBase { @Test void defaultCommandInterruptResumeTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new Subsystem() {}; MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); @@ -54,7 +54,7 @@ class DefaultCommandTest extends CommandTestBase { @Test void defaultCommandDisableResumeTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new Subsystem() {}; MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java index 7dc91106ee..7b7bc2e243 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java @@ -90,10 +90,10 @@ class ParallelCommandGroupTest extends CommandTestBase @Test void parallelGroupRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; + Subsystem system4 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -115,9 +115,9 @@ class ParallelCommandGroupTest extends CommandTestBase @Test void parallelGroupRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); Command command1 = command1Holder.getMock(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java index 6fa644bb24..31a593fced 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelDeadlineGroupTest.java @@ -87,10 +87,10 @@ class ParallelDeadlineGroupTest extends CommandTestBase @Test void parallelDeadlineRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; + Subsystem system4 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -112,9 +112,9 @@ class ParallelDeadlineGroupTest extends CommandTestBase @Test void parallelDeadlineRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); Command command1 = command1Holder.getMock(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java index 67524960ca..54785ca1b5 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelRaceGroupTest.java @@ -92,10 +92,10 @@ class ParallelRaceGroupTest extends CommandTestBase @Test void parallelRaceRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; + Subsystem system4 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -117,9 +117,9 @@ class ParallelRaceGroupTest extends CommandTestBase @Test void parallelRaceRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); Command command1 = command1Holder.getMock(); @@ -131,8 +131,8 @@ class ParallelRaceGroupTest extends CommandTestBase @Test void parallelRaceOnlyCallsEndOnceTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; MockCommandHolder command1Holder = new MockCommandHolder(true, system1); Command command1 = command1Holder.getMock(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java index ee1f8eb37c..5d79c447d8 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulerTest.java @@ -48,7 +48,7 @@ class SchedulerTest extends CommandTestBase { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(0); Subsystem system = - new SubsystemBase() { + new Subsystem() { @Override public void periodic() { counter.incrementAndGet(); @@ -67,7 +67,7 @@ class SchedulerTest extends CommandTestBase { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(0); Subsystem system = - new SubsystemBase() { + new Subsystem() { @Override public void periodic() { counter.incrementAndGet(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java index 28e9e6fbeb..79ee60c7ae 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SchedulingRecursionTest.java @@ -25,9 +25,9 @@ class SchedulingRecursionTest extends CommandTestBase { void cancelFromInitialize(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean hasOtherRun = new AtomicBoolean(); - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; Command selfCancels = - new CommandBase() { + new Command() { { addRequirements(requirement); } @@ -62,9 +62,9 @@ class SchedulingRecursionTest extends CommandTestBase { void defaultCommandGetsRescheduledAfterSelfCanceling(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean hasOtherRun = new AtomicBoolean(); - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; Command selfCancels = - new CommandBase() { + new Command() { { addRequirements(requirement); } @@ -100,7 +100,7 @@ class SchedulingRecursionTest extends CommandTestBase { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); Command selfCancels = - new CommandBase() { + new Command() { @Override public void end(boolean interrupted) { counter.incrementAndGet(); @@ -119,10 +119,10 @@ class SchedulingRecursionTest extends CommandTestBase { void scheduleFromEndCancel() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; InstantCommand other = new InstantCommand(() -> {}, requirement); Command selfCancels = - new CommandBase() { + new Command() { { addRequirements(requirement); } @@ -146,10 +146,10 @@ class SchedulingRecursionTest extends CommandTestBase { void scheduleFromEndInterrupt() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; InstantCommand other = new InstantCommand(() -> {}, requirement); Command selfCancels = - new CommandBase() { + new Command() { { addRequirements(requirement); } @@ -175,11 +175,11 @@ class SchedulingRecursionTest extends CommandTestBase { void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new Subsystem() {}; Command other = new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior); Command defaultCommand = - new CommandBase() { + new Command() { { addRequirements(requirement); } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java index 736f120a97..0bca07e0ca 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SelectCommandTest.java @@ -75,10 +75,10 @@ class SelectCommandTest extends CommandTestBase implements MultiCompositionTestB @Test void selectCommandRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; + Subsystem system4 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java index ff578f45d4..a9e5120be6 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java @@ -100,10 +100,10 @@ class SequentialCommandGroupTest extends CommandTestBase @Test void sequentialGroupRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Subsystem system1 = new Subsystem() {}; + Subsystem system2 = new Subsystem() {}; + Subsystem system3 = new Subsystem() {}; + Subsystem system4 = new Subsystem() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp index 6e3bde02a9..1bd180c8a5 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp @@ -11,12 +11,14 @@ CommandTestBase::CommandTestBase() { scheduler.CancelAll(); scheduler.Enable(); scheduler.GetActiveButtonLoop()->Clear(); + scheduler.UnregisterAllSubsystems(); SetDSEnabled(true); } CommandTestBase::~CommandTestBase() { CommandScheduler::GetInstance().GetActiveButtonLoop()->Clear(); + CommandScheduler::GetInstance().UnregisterAllSubsystems(); } CommandScheduler CommandTestBase::GetScheduler() { diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h index 1e4e5f7123..9ad59e5081 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h @@ -12,14 +12,14 @@ #include "frc2/command/CommandHelper.h" #include "frc2/command/CommandScheduler.h" #include "frc2/command/SetUtilities.h" -#include "frc2/command/SubsystemBase.h" +#include "frc2/command/Subsystem.h" #include "gmock/gmock.h" #include "gtest/gtest.h" #include "make_vector.h" namespace frc2 { -class TestSubsystem : public SubsystemBase { +class TestSubsystem : public Subsystem { public: explicit TestSubsystem(std::function periodic = [] {}) : m_periodic{periodic} {} @@ -32,7 +32,7 @@ class TestSubsystem : public SubsystemBase { /** * NOTE: Moving mock objects causes EXPECT_CALL to not work correctly! */ -class MockCommand : public CommandHelper { +class MockCommand : public CommandHelper { public: MOCK_CONST_METHOD0(GetRequirements, wpi::SmallSet()); MOCK_METHOD0(IsFinished, bool()); @@ -107,12 +107,14 @@ class CommandTestBaseWithParam : public ::testing::TestWithParam { scheduler.CancelAll(); scheduler.Enable(); scheduler.GetActiveButtonLoop()->Clear(); + scheduler.UnregisterAllSubsystems(); SetDSEnabled(true); } ~CommandTestBaseWithParam() override { CommandScheduler::GetInstance().GetActiveButtonLoop()->Clear(); + CommandScheduler::GetInstance().UnregisterAllSubsystems(); } protected: diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp index c042203910..0868716ac6 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/MecanumControllerCommandTest.cpp @@ -17,6 +17,7 @@ #include #include +#include "CommandTestBase.h" #include "gtest/gtest.h" #define EXPECT_NEAR_UNITS(val1, val2, eps) \ @@ -87,7 +88,7 @@ class MecanumControllerCommandTest : public ::testing::Test { }; TEST_F(MecanumControllerCommandTest, ReachesReference) { - frc2::Subsystem subsystem; + frc2::TestSubsystem subsystem; auto waypoints = std::vector{frc::Pose2d{0_m, 0_m, 0_rad}, frc::Pose2d{1_m, 5_m, 3_rad}}; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp index 733117c7bc..5c9bbbdfe0 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp @@ -14,7 +14,7 @@ class SchedulingRecursionTest : public CommandTestBaseWithParam {}; class SelfCancellingCommand - : public CommandHelper { + : public CommandHelper { public: SelfCancellingCommand(CommandScheduler* scheduler, Subsystem* requirement, Command::InterruptionBehavior interruptionBehavior = @@ -76,7 +76,7 @@ TEST_P(SchedulingRecursionTest, EXPECT_TRUE(hasOtherRun); } -class CancelEndCommand : public CommandHelper { +class CancelEndCommand : public CommandHelper { public: CancelEndCommand(CommandScheduler* scheduler, int& counter) : m_scheduler(scheduler), m_counter(counter) {} diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp index 902439fba1..0a3557c9eb 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SwerveControllerCommandTest.cpp @@ -18,6 +18,7 @@ #include #include +#include "CommandTestBase.h" #include "gtest/gtest.h" #define EXPECT_NEAR_UNITS(val1, val2, eps) \ @@ -72,7 +73,7 @@ class SwerveControllerCommandTest : public ::testing::Test { }; TEST_F(SwerveControllerCommandTest, ReachesReference) { - frc2::Subsystem subsystem; + frc2::TestSubsystem subsystem; auto waypoints = std::vector{frc::Pose2d{0_m, 0_m, 0_rad}, frc::Pose2d{1_m, 5_m, 3_rad}}; diff --git a/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.h b/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.h index 8a1e8e017c..d3071eb4b0 100644 --- a/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.h +++ b/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.h @@ -4,18 +4,18 @@ #pragma once -#include +#include #include /** * An example command. * - *

Note that this extends CommandHelper, rather extending CommandBase + *

Note that this extends CommandHelper, rather extending Command * directly; this is crucially important, or else the decorator functions in * Command will *not* work! */ class ReplaceMeCommand2 - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: ReplaceMeCommand2(); diff --git a/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.h b/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.h index ca11456d43..e3f455f2e6 100644 --- a/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.h +++ b/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.h @@ -4,9 +4,9 @@ #pragma once -#include +#include -class ReplaceMeSubsystem2 : public frc2::SubsystemBase { +class ReplaceMeSubsystem2 : public frc2::Subsystem { public: ReplaceMeSubsystem2(); diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h index 47bf28e4d9..9146454b03 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBot/include/subsystems/DriveSubsystem.h @@ -8,11 +8,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h index 6830b960d0..054c819d68 100644 --- a/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/ArmBotOffboard/include/subsystems/DriveSubsystem.h @@ -11,11 +11,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h index 9086353bf9..5e64e53837 100644 --- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.h @@ -8,13 +8,13 @@ #include #include #include -#include +#include #include #include "Constants.h" #include "ExampleSmartMotorController.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h index 47bf28e4d9..9146454b03 100644 --- a/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/Frisbeebot/include/subsystems/DriveSubsystem.h @@ -8,11 +8,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h index 05116042e7..31e2b92064 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/CloseClaw.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/Claw.h" @@ -12,7 +12,7 @@ /** * Closes the claw until the limit switch is tripped. */ -class CloseClaw : public frc2::CommandHelper { +class CloseClaw : public frc2::CommandHelper { public: explicit CloseClaw(Claw& claw); void Initialize() override; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h index a106d62ad1..3e8c18c33f 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetElevatorSetpoint.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/Elevator.h" @@ -17,7 +17,7 @@ * commands using the elevator should make sure they disable PID! */ class SetElevatorSetpoint - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: explicit SetElevatorSetpoint(double setpoint, Elevator& elevator); void Initialize() override; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h index 2f6ca21b72..1494ad6dcc 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/SetWristSetpoint.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/Wrist.h" @@ -15,7 +15,7 @@ * Other commands using the wrist should make sure they disable PID! */ class SetWristSetpoint - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: explicit SetWristSetpoint(double setpoint, Wrist& wrist); void Initialize() override; diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h index 5a81c11f3c..bf6597d972 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/commands/TankDrive.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/Drivetrain.h" @@ -12,7 +12,7 @@ /** * Have the robot drive tank style using the PS3 Joystick until interrupted. */ -class TankDrive : public frc2::CommandHelper { +class TankDrive : public frc2::CommandHelper { public: TankDrive(std::function left, std::function right, Drivetrain& drivetrain); diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h index c6f17d84a2..048ffb568a 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Claw.h @@ -6,14 +6,14 @@ #include #include -#include +#include /** * 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. */ -class Claw : public frc2::SubsystemBase { +class Claw : public frc2::Subsystem { public: Claw(); diff --git a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h index 9e739c4dbc..7a84dbef4b 100644 --- a/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/GearsBot/include/subsystems/Drivetrain.h @@ -10,7 +10,7 @@ #include #include #include -#include +#include namespace frc { class Joystick; @@ -21,7 +21,7 @@ class Joystick; * the robots chassis. These include four drive motors, a left and right encoder * and a gyro. */ -class Drivetrain : public frc2::SubsystemBase { +class Drivetrain : public frc2::Subsystem { public: Drivetrain(); diff --git a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h index 96174dd4f7..5ea5db37d0 100644 --- a/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/GyroDriveCommands/include/subsystems/DriveSubsystem.h @@ -9,12 +9,12 @@ #include #include #include -#include +#include #include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp index 3372a4dca9..0ed075a7af 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp @@ -47,7 +47,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) { } void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) { - SubsystemBase::InitSendable(builder); + Subsystem::InitSendable(builder); // Publish encoder distances to telemetry. builder.AddDoubleProperty( diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp index 449465bb49..bd79d2b074 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp @@ -25,7 +25,7 @@ frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() { } void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) { - SubsystemBase::InitSendable(builder); + Subsystem::InitSendable(builder); // Publish the solenoid state to telemetry. builder.AddBooleanProperty( diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h index 5984a1a4f3..72c88e299f 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.h @@ -8,11 +8,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h index e81f3b2d79..9d0c9b5559 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.h @@ -7,11 +7,11 @@ #include #include #include -#include +#include #include "Constants.h" -class HatchSubsystem : public frc2::SubsystemBase { +class HatchSubsystem : public frc2::Subsystem { public: HatchSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp index 3372a4dca9..0ed075a7af 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp @@ -47,7 +47,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) { } void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) { - SubsystemBase::InitSendable(builder); + Subsystem::InitSendable(builder); // Publish encoder distances to telemetry. builder.AddDoubleProperty( diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp index 975141fe1c..ae1b26c150 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp @@ -21,7 +21,7 @@ void HatchSubsystem::ReleaseHatch() { } void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) { - SubsystemBase::InitSendable(builder); + Subsystem::InitSendable(builder); // Publish the solenoid state to telemetry. builder.AddBooleanProperty( diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h index 2e7cac8c54..b5cb4f498c 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/DriveSubsystem.h" @@ -16,8 +16,7 @@ * * @see RunCommand */ -class DefaultDrive - : public frc2::CommandHelper { +class DefaultDrive : public frc2::CommandHelper { public: /** * Creates a new DefaultDrive. diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.h index 34d2577fd8..5a0fad87b6 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.h @@ -4,13 +4,12 @@ #pragma once -#include +#include #include #include "subsystems/DriveSubsystem.h" -class DriveDistance - : public frc2::CommandHelper { +class DriveDistance : public frc2::CommandHelper { public: /** * Creates a new DriveDistance. diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h index 0cf5c5a584..c8a36a463d 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/HatchSubsystem.h" @@ -16,7 +16,7 @@ * * @see InstantCommand */ -class GrabHatch : public frc2::CommandHelper { +class GrabHatch : public frc2::CommandHelper { public: explicit GrabHatch(HatchSubsystem* subsystem); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.h index efc572d17a..52d828156c 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.h @@ -4,13 +4,13 @@ #pragma once -#include +#include #include #include "subsystems/DriveSubsystem.h" class HalveDriveSpeed - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: explicit HalveDriveSpeed(DriveSubsystem* subsystem); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.h index e3628cf810..0b4b953702 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/HatchSubsystem.h" @@ -16,8 +16,7 @@ * * @see InstantCommand */ -class ReleaseHatch - : public frc2::CommandHelper { +class ReleaseHatch : public frc2::CommandHelper { public: explicit ReleaseHatch(HatchSubsystem* subsystem); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h index 5984a1a4f3..72c88e299f 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.h @@ -8,11 +8,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.h b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.h index 392e9b20ab..61ef97f6d0 100644 --- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.h @@ -6,11 +6,11 @@ #include #include -#include +#include #include "Constants.h" -class HatchSubsystem : public frc2::SubsystemBase { +class HatchSubsystem : public frc2::Subsystem { public: HatchSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h index 579a3950ea..2ecf9ea85d 100644 --- a/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/MecanumControllerCommand/include/subsystems/DriveSubsystem.h @@ -13,11 +13,11 @@ #include #include #include -#include +#include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h index 8ea14dad39..49f717214c 100644 --- a/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/RamseteCommand/include/subsystems/DriveSubsystem.h @@ -11,12 +11,12 @@ #include #include #include -#include +#include #include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h index ac96c52839..0d98091ab8 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.h @@ -11,12 +11,12 @@ #include #include #include -#include +#include #include #include "Constants.h" -class Drive : public frc2::SubsystemBase { +class Drive : public frc2::Subsystem { public: Drive(); /** diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h index 111353a0f5..be5aa43f9b 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.h @@ -9,11 +9,11 @@ #include #include #include -#include +#include #include "Constants.h" -class Intake : public frc2::SubsystemBase { +class Intake : public frc2::Subsystem { public: Intake() = default; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h index 0c1fee92a9..dfd37b8cdf 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.h @@ -8,12 +8,12 @@ #include #include #include -#include +#include #include #include "Constants.h" -class Pneumatics : frc2::SubsystemBase { +class Pneumatics : frc2::Subsystem { public: Pneumatics(); /** Returns a command that disables the compressor indefinitely. */ diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h index b31155934f..d3d98fc81d 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.h @@ -11,13 +11,13 @@ #include #include #include -#include +#include #include #include #include "Constants.h" -class Shooter : public frc2::SubsystemBase { +class Shooter : public frc2::Subsystem { public: Shooter(); diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h index 58694b3035..5f0340f4bd 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.h @@ -7,11 +7,11 @@ #include #include #include -#include +#include #include "Constants.h" -class Storage : frc2::SubsystemBase { +class Storage : frc2::Subsystem { public: Storage(); /** Returns a command that runs the storage motor indefinitely. */ diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.h index 34a1e93867..cdfb74fb01 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.h @@ -4,14 +4,13 @@ #pragma once -#include +#include #include #include #include "subsystems/Drivetrain.h" -class DriveDistance - : public frc2::CommandHelper { +class DriveDistance : public frc2::CommandHelper { public: DriveDistance(double speed, units::meter_t distance, Drivetrain* drive) : m_speed(speed), m_distance(distance), m_drive(drive) { diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.h index a0135e5442..226c5258a8 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.h @@ -5,13 +5,13 @@ #pragma once #include -#include +#include #include #include #include "subsystems/Drivetrain.h" -class DriveTime : public frc2::CommandHelper { +class DriveTime : public frc2::CommandHelper { public: DriveTime(double speed, units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.h index 859b6b7078..f5364207f3 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.h @@ -4,13 +4,13 @@ #pragma once -#include +#include #include #include "subsystems/Drivetrain.h" class TeleopArcadeDrive - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: TeleopArcadeDrive(Drivetrain* subsystem, std::function xaxisSpeedSupplier, diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.h index 7ce65df456..6afc08a456 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.h @@ -4,14 +4,14 @@ #pragma once -#include +#include #include #include #include #include "subsystems/Drivetrain.h" -class TurnDegrees : public frc2::CommandHelper { +class TurnDegrees : public frc2::CommandHelper { public: TurnDegrees(double speed, units::degree_t angle, Drivetrain* drive) : m_speed(speed), m_angle(angle), m_drive(drive) { diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.h index 395825d6c0..c2c190ef55 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.h @@ -5,13 +5,13 @@ #pragma once #include -#include +#include #include #include #include "subsystems/Drivetrain.h" -class TurnTime : public frc2::CommandHelper { +class TurnTime : public frc2::CommandHelper { public: TurnTime(double speed, units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h index 98ae9574b0..055d6eefa3 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.h @@ -8,12 +8,12 @@ #include #include #include -#include +#include #include #include "sensors/RomiGyro.h" -class Drivetrain : public frc2::SubsystemBase { +class Drivetrain : public frc2::Subsystem { public: static constexpr double kCountsPerRevolution = 1440.0; static constexpr units::meter_t kWheelDiameter = 70_mm; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/OnBoardIO.h b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/OnBoardIO.h index 0bb5225bc9..8dd8e0b87d 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/OnBoardIO.h +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/OnBoardIO.h @@ -8,7 +8,7 @@ #include #include -#include +#include /** * This class represents the onboard IO of the Romi @@ -20,7 +20,7 @@ * DIO 2 - Button C (input) or Red LED (output) * DIO 3 - Yellow LED (output only) */ -class OnBoardIO : public frc2::SubsystemBase { +class OnBoardIO : public frc2::Subsystem { public: enum ChannelMode { INPUT, OUTPUT }; OnBoardIO(OnBoardIO::ChannelMode dio1, OnBoardIO::ChannelMode dio2); diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h index 57392c723b..63bac54f75 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceDifferentialDriveSimulation/include/subsystems/DriveSubsystem.h @@ -15,12 +15,12 @@ #include #include #include -#include +#include #include #include "Constants.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h index e9ed17b51d..6a29940e50 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h +++ b/wpilibcExamples/src/main/cpp/examples/SwerveControllerCommand/include/subsystems/DriveSubsystem.h @@ -14,12 +14,12 @@ #include #include #include -#include +#include #include "Constants.h" #include "SwerveModule.h" -class DriveSubsystem : public frc2::SubsystemBase { +class DriveSubsystem : public frc2::Subsystem { public: DriveSubsystem(); diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h index 8ecd864345..9426538a2e 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.h @@ -4,7 +4,7 @@ #pragma once -#include +#include #include #include "subsystems/ExampleSubsystem.h" @@ -12,12 +12,12 @@ /** * An example command that uses an example subsystem. * - *

Note that this extends CommandHelper, rather extending CommandBase + *

Note that this extends CommandHelper, rather extending Command * directly; this is crucially important, or else the decorator functions in * Command will *not* work! */ class ExampleCommand - : public frc2::CommandHelper { + : public frc2::CommandHelper { public: /** * Creates a new ExampleCommand. diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h b/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h index 669f2eda06..2dd60e233b 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.h @@ -5,9 +5,9 @@ #pragma once #include -#include +#include -class ExampleSubsystem : public frc2::SubsystemBase { +class ExampleSubsystem : public frc2::Subsystem { public: ExampleSubsystem(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command2/ReplaceMeCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command2/ReplaceMeCommand.java index a9a96ef35e..2d90dc27fa 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command2/ReplaceMeCommand.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/command2/ReplaceMeCommand.java @@ -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. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem2/ReplaceMeSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem2/ReplaceMeSubsystem.java index f72539d712..c87ca2bfc0 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem2/ReplaceMeSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/commands/subsystem2/ReplaceMeSubsystem.java @@ -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() {} diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java index 4ecaa77231..86b28c69a2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbot/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java index e3c9159537..805fe91769 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/armbotoffboard/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java index 520261d402..687448fc6f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/drivedistanceoffboard/subsystems/DriveSubsystem.java @@ -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); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java index 5773da182d..201e94c756 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/frisbeebot/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java index 47710f930f..28c76b7705 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/RobotContainer.java @@ -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. */ diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java index 8ef1deb52a..1110e5728a 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/CloseClaw.java @@ -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) { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java index a32330535e..66790c2cb5 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetElevatorSetpoint.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java index 4c45ddf005..a185ed5ff4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/SetWristSetpoint.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDrive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDrive.java index 009daada78..3830f82103 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDrive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/commands/TankDrive.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java index 06c627e480..092c01a411 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Claw.java @@ -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); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Drivetrain.java index ffde63d402..b95adacac9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gearsbot/subsystems/Drivetrain.java @@ -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. diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java index a2fdf6ef9f..393a3328aa 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/gyrodrivecommands/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java index 1376195dc1..2087cf82bc 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java index 5beef049f7..37de6a386b 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbotinlined/subsystems/HatchSubsystem.java @@ -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)); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java index 460e787bb4..72364264f1 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DefaultDrive.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DriveDistance.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DriveDistance.java index 04a3c0bf27..a766f809a3 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DriveDistance.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/DriveDistance.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java index 9cd1550611..e5175af200 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/GrabHatch.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/HalveDriveSpeed.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/HalveDriveSpeed.java index c34d951642..efaa2857de 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/HalveDriveSpeed.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/commands/HalveDriveSpeed.java @@ -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) { diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java index 8a5296d860..8eab2b4f00 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/HatchSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/HatchSubsystem.java index fcef9e244f..c5c026df83 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/HatchSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/hatchbottraditional/subsystems/HatchSubsystem.java @@ -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, diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java index 83b9c9fa3f..e95a15fb3d 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/mecanumcontrollercommand/subsystems/DriveSubsystem.java @@ -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); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java index 90625ce59a..7faf94b3bc 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/ramsetecommand/subsystems/DriveSubsystem.java @@ -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( 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 de0e93a271..12d7f662c6 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 @@ -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 { * *

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) 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 eaaa8ad747..4bb7f8c9bb 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,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 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 c8dcc215e1..e419f753fd 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,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(); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java index e98c8a70f7..b62f12fce9 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/rapidreactcommandbot/subsystems/Pneumatics.java @@ -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. 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 9191fb6094..fc34af6914 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,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( 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 9b45d66833..89683ee35c 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,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"); } } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/ArcadeDrive.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/ArcadeDrive.java index 4a82b38545..295a6f9bb2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/ArcadeDrive.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/ArcadeDrive.java @@ -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 m_xaxisSpeedSupplier; private final Supplier m_zaxisRotateSupplier; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveDistance.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveDistance.java index f316ce6279..d9c306b9d3 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveDistance.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveDistance.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveTime.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveTime.java index 80636f0da8..7fac2b876c 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveTime.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/DriveTime.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnDegrees.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnDegrees.java index 78ffa6cc86..a438f0141e 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnDegrees.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnDegrees.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnTime.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnTime.java index 10341f9b6e..f3a6aa7fe2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnTime.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/commands/TurnTime.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java index a7c84320a6..98b43d6c53 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/Drivetrain.java @@ -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 diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java index 0199f6a8ba..4c16953862 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/romireference/subsystems/OnBoardIO.java @@ -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; *

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); diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java index 406178a8ab..cd33abbbb2 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/statespacedifferentialdrivesimulation/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java index 326efee93f..c5ce070fa4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/examples/swervecontrollercommand/subsystems/DriveSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java index 330a4aeda7..1126d8dbb6 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/Autos.java @@ -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)); } diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java index 194cbf65f1..181de6dbb4 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/commands/ExampleCommand.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java index 57d86cc1c7..76e8020e1f 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/commandbased/subsystems/ExampleSubsystem.java @@ -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( diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/commands/ExampleCommand.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/commands/ExampleCommand.java index 0ebb5d2fca..c05a53a272 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/commands/ExampleCommand.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/commands/ExampleCommand.java @@ -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; diff --git a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java index 276e5cee7d..0b99a94a25 100644 --- a/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java +++ b/wpilibjExamples/src/main/java/edu/wpi/first/wpilibj/templates/romicommandbased/subsystems/RomiDrivetrain.java @@ -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