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