From 93caf710a6693ed14666ab54412d52bd60d7a7c7 Mon Sep 17 00:00:00 2001 From: Oblarg Date: Mon, 13 May 2024 14:22:51 -0400 Subject: [PATCH] nonbreakingly rename `Subsystem` to `Resource` --- .../wpi/first/wpilibj2/command/Command.java | 14 +- .../wpilibj2/command/CommandScheduler.java | 176 ++++++++++-------- .../wpi/first/wpilibj2/command/Commands.java | 14 +- .../wpilibj2/command/DeferredCommand.java | 4 +- .../wpilibj2/command/FunctionalCommand.java | 2 +- .../wpilibj2/command/InstantCommand.java | 2 +- .../command/MecanumControllerCommand.java | 8 +- .../wpilibj2/command/NotifierCommand.java | 2 +- .../first/wpilibj2/command/PIDCommand.java | 4 +- .../wpilibj2/command/ProfiledPIDCommand.java | 8 +- .../wpilibj2/command/RamseteCommand.java | 4 +- .../wpi/first/wpilibj2/command/Resource.java | 171 +++++++++++++++++ .../first/wpilibj2/command/RunCommand.java | 2 +- .../wpilibj2/command/StartEndCommand.java | 2 +- .../wpi/first/wpilibj2/command/Subsystem.java | 159 +--------------- .../first/wpilibj2/command/SubsystemBase.java | 6 +- .../command/SwerveControllerCommand.java | 8 +- .../command/TrapezoidProfileCommand.java | 2 +- .../wpilibj2/command/WrapperCommand.java | 2 +- .../wpilibj2/command/sysid/SysIdRoutine.java | 27 +-- .../command/CommandRequirementsTest.java | 6 +- .../wpilibj2/command/CommandTestBase.java | 2 +- .../command/ConditionalCommandTest.java | 6 +- .../wpilibj2/command/DefaultCommandTest.java | 6 +- .../wpilibj2/command/DeferredCommandTest.java | 6 +- .../command/MecanumControllerCommandTest.java | 2 +- .../command/ParallelCommandGroupTest.java | 14 +- .../command/ParallelDeadlineGroupTest.java | 14 +- .../command/ParallelRaceGroupTest.java | 18 +- .../first/wpilibj2/command/SchedulerTest.java | 20 +- .../command/SchedulingRecursionTest.java | 16 +- .../wpilibj2/command/SelectCommandTest.java | 8 +- .../command/SequentialCommandGroupTest.java | 8 +- .../command/SwerveControllerCommandTest.java | 2 +- .../command/sysid/SysIdRoutineTest.java | 6 +- 35 files changed, 402 insertions(+), 349 deletions(-) create mode 100644 wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Resource.java 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 255291b933e..14795b19b77 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 @@ -29,7 +29,7 @@ */ public abstract class Command implements Sendable { /** Requirements set. */ - protected Set m_requirements = new HashSet<>(); + protected Set m_requirements = new HashSet<>(); /** Default constructor. */ @SuppressWarnings("this-escape") @@ -77,7 +77,7 @@ public boolean isFinished() { * @return the set of subsystems that are required * @see InterruptionBehavior */ - public Set getRequirements() { + public Set getRequirements() { return m_requirements; } @@ -90,8 +90,8 @@ public Set getRequirements() { * * @param requirements the requirements to add */ - public final void addRequirements(Subsystem... requirements) { - for (Subsystem requirement : requirements) { + public final void addRequirements(Resource... requirements) { + for (Resource requirement : requirements) { m_requirements.add(requireNonNullParam(requirement, "requirement", "addRequirements")); } } @@ -218,7 +218,7 @@ public ParallelRaceGroup onlyWhile(BooleanSupplier condition) { * @param requirements the required subsystems * @return the decorated command */ - public SequentialCommandGroup beforeStarting(Runnable toRun, Subsystem... requirements) { + public SequentialCommandGroup beforeStarting(Runnable toRun, Resource... requirements) { return beforeStarting(new InstantCommand(toRun, requirements)); } @@ -251,7 +251,7 @@ public SequentialCommandGroup beforeStarting(Command before) { * @param requirements the required subsystems * @return the decorated command */ - public SequentialCommandGroup andThen(Runnable toRun, Subsystem... requirements) { + public SequentialCommandGroup andThen(Runnable toRun, Resource... requirements) { return andThen(new InstantCommand(toRun, requirements)); } @@ -532,7 +532,7 @@ public boolean isScheduled() { * @param requirement the subsystem to inquire about * @return whether the subsystem is required */ - public boolean hasRequirement(Subsystem requirement) { + public boolean hasRequirement(Resource requirement) { return getRequirements().contains(requirement); } 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 7e634cf5c92..c89fcff3229 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 @@ -41,7 +41,7 @@ * The scheduler responsible for running {@link Command}s. A Command-based robot should call {@link * CommandScheduler#run()} on the singleton instance in its periodic block in order to run commands * synchronously from the main loop. Subsystems should be registered with the scheduler using {@link - * CommandScheduler#registerSubsystem(Subsystem...)} in order for their {@link Subsystem#periodic()} + * CommandScheduler#registerResources(Resource...)} in order for their {@link Resource#periodic()} * methods to be called and for their default commands to be scheduled. * *

This class is provided by the NewCommands VendorDep @@ -69,13 +69,13 @@ public static synchronized CommandScheduler getInstance() { // A set of the currently-running commands. private final Set m_scheduledCommands = new LinkedHashSet<>(); - // A map from required subsystems to their requiring commands. Also used as a set of the - // currently-required subsystems. - private final Map m_requirements = new LinkedHashMap<>(); + // A map from required resources to their requiring commands. Also used as a set of the + // currently-required resources. + private final Map m_requirements = new LinkedHashMap<>(); - // A map from subsystems registered with the scheduler to their default commands. Also used - // as a list of currently-registered subsystems. - private final Map m_subsystems = new LinkedHashMap<>(); + // A map from resources registered with the scheduler to their default commands. Also used + // as a list of currently-registered resources. + private final Map m_resources = new LinkedHashMap<>(); private final EventLoop m_defaultButtonLoop = new EventLoop(); // The set of currently-registered buttons that will be polled every iteration. @@ -161,9 +161,9 @@ public void setActiveButtonLoop(EventLoop loop) { * @param command The command to initialize * @param requirements The command requirements */ - private void initCommand(Command command, Set requirements) { + private void initCommand(Command command, Set requirements) { m_scheduledCommands.add(command); - for (Subsystem requirement : requirements) { + for (Resource requirement : requirements) { m_requirements.put(requirement, command); } command.initialize(); @@ -202,7 +202,7 @@ private void schedule(Command command) { return; } - Set requirements = command.getRequirements(); + Set requirements = command.getRequirements(); // Schedule the command if the requirements are not currently in-use. if (Collections.disjoint(m_requirements.keySet(), requirements)) { @@ -210,14 +210,14 @@ private void schedule(Command command) { } else { // Else check if the requirements that are in use have all have interruptible commands, // and if so, interrupt those commands and schedule the new command. - for (Subsystem requirement : requirements) { + for (Resource requirement : requirements) { Command requiring = requiring(requirement); if (requiring != null && requiring.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) { return; } } - for (Subsystem requirement : requirements) { + for (Resource requirement : requirements) { Command requiring = requiring(requirement); if (requiring != null) { cancel(requiring, Optional.of(command)); @@ -241,7 +241,7 @@ public void schedule(Command... commands) { /** * Runs a single iteration of the scheduler. The execution occurs in the following order: * - *

Subsystem periodic methods are called. + *

Resource periodic methods are called. * *

Button bindings are polled, and new commands are scheduled from them. * @@ -250,7 +250,7 @@ public void schedule(Command... commands) { *

End conditions are checked on currently-scheduled commands, and commands that are finished * have their end methods called and are removed. * - *

Any subsystems not being used as requirements have their default methods started. + *

Any resources not being used as requirements have their default methods started. */ public void run() { if (m_disabled) { @@ -258,13 +258,13 @@ public void run() { } m_watchdog.reset(); - // Run the periodic method of all registered subsystems. - for (Subsystem subsystem : m_subsystems.keySet()) { - subsystem.periodic(); + // Run the periodic method of all registered resources. + for (Resource resource : m_resources.keySet()) { + resource.periodic(); if (RobotBase.isSimulation()) { - subsystem.simulationPeriodic(); + resource.simulationPeriodic(); } - m_watchdog.addEpoch(subsystem.getName() + ".periodic()"); + m_watchdog.addEpoch(resource.getName() + ".periodic()"); } // Cache the active instance to avoid concurrency problems if setActiveLoop() is called from @@ -318,11 +318,11 @@ public void run() { m_toCancelCommands.clear(); m_toCancelInterruptors.clear(); - // Add default commands for un-required registered subsystems. - for (Map.Entry subsystemCommand : m_subsystems.entrySet()) { - if (!m_requirements.containsKey(subsystemCommand.getKey()) - && subsystemCommand.getValue() != null) { - schedule(subsystemCommand.getValue()); + // Add default commands for un-required registered resources. + for (Map.Entry resourceCommand : m_resources.entrySet()) { + if (!m_requirements.containsKey(resourceCommand.getKey()) + && resourceCommand.getValue() != null) { + schedule(resourceCommand.getValue()); } } @@ -334,58 +334,86 @@ public void run() { } /** - * Registers subsystems with the scheduler. This must be called for the subsystem's periodic block - * to run when the scheduler is run, and for the subsystem's default command to be scheduled. It - * is recommended to call this from the constructor of your subsystem implementations. + * Registers resources with the scheduler. This must be called for the resource's periodic block + * to run when the scheduler is run, and for the resource's default command to be scheduled. It + * is recommended to call this from the constructor of your resource implementations. * - * @param subsystems the subsystem to register + * @param resources the resources to register */ - public void registerSubsystem(Subsystem... subsystems) { - for (Subsystem subsystem : subsystems) { - if (subsystem == null) { - DriverStation.reportWarning("Tried to register a null subsystem", true); + public void registerResources(Resource... resources) { + for (Resource resource : resources) { + if (resource == null) { + DriverStation.reportWarning("Tried to register a null resource", true); continue; } - if (m_subsystems.containsKey(subsystem)) { - DriverStation.reportWarning("Tried to register an already-registered subsystem", true); + if (m_resources.containsKey(resource)) { + DriverStation.reportWarning("Tried to register an already-registered resource", true); continue; } - m_subsystems.put(subsystem, null); + m_resources.put(resource, null); } } /** - * Un-registers subsystems with the scheduler. The subsystem will no longer have its periodic - * block called, and will not have its default command scheduled. + * Alias of {@link CommandScheduler#registerResources(Resource...)}. See {@link Subsystem} for + * details regarding the name change. + * + * @param subsystems the subsystem(s to register + */ + public void registerSubsystem(Subsystem... subsystems) { + registerResources(subsystems); + } + + /** + * Un-registers resources with the scheduler. The resources will no longer have their periodic + * block called, and will not have their default command scheduled. + * + * @param resources the resources to un-register + */ + public void unregisterResources(Resource... resources) { + m_resources.keySet().removeAll(Set.of(resources)); + } + + /** + * Alias of {@link CommandScheduler#unregisterResources(Resource...)}. See {@link Subsystem} for + * details regarding the name change. * - * @param subsystems the subsystem to un-register + * @param subsystems the subsystems to un-register + */ + public void unregisterSubsystem(Resource... subsystems) { + unregisterResources(subsystems); + } + + /** + * Un-registers all registered {@link Resource}s with the scheduler. All currently registered + * resources will no longer have their periodic block called, and will not have their default + * command scheduled. */ - public void unregisterSubsystem(Subsystem... subsystems) { - m_subsystems.keySet().removeAll(Set.of(subsystems)); + public void unregisterAllResources() { + m_resources.clear(); } /** - * 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. + * Alias of {@link CommandScheduler#unregisterAllResources()}. See {@link Subsystem} for + * details regarding the name change. */ public void unregisterAllSubsystems() { - m_subsystems.clear(); + unregisterAllResources(); } /** - * Sets the default command for a subsystem. Registers that subsystem if it is not already + * Sets the default command for a resource. Registers that resource if it is not already * registered. Default commands will run whenever there is no other command currently scheduled - * that requires the subsystem. Default commands should be written to never end (i.e. their {@link + * that requires the resource. Default commands should be written to never end (i.e. their {@link * Command#isFinished()} method should return false), as they would simply be re-scheduled if they - * do. Default commands must also require their subsystem. + * do. Default commands must also require their resource. * - * @param subsystem the subsystem whose default command will be set - * @param defaultCommand the default command to associate with the subsystem + * @param resource the resource whose default command will be set + * @param defaultCommand the default command to associate with the resource */ - public void setDefaultCommand(Subsystem subsystem, Command defaultCommand) { - if (subsystem == null) { - DriverStation.reportWarning("Tried to set a default command for a null subsystem", true); + public void setDefaultCommand(Resource resource, Command defaultCommand) { + if (resource == null) { + DriverStation.reportWarning("Tried to set a default command for a null resource", true); return; } if (defaultCommand == null) { @@ -395,46 +423,46 @@ public void setDefaultCommand(Subsystem subsystem, Command defaultCommand) { requireNotComposed(defaultCommand); - if (!defaultCommand.getRequirements().contains(subsystem)) { - throw new IllegalArgumentException("Default commands must require their subsystem!"); + if (!defaultCommand.getRequirements().contains(resource)) { + throw new IllegalArgumentException("Default commands must require their resource!"); } if (defaultCommand.getInterruptionBehavior() == InterruptionBehavior.kCancelIncoming) { DriverStation.reportWarning( "Registering a non-interruptible default command!\n" - + "This will likely prevent any other commands from requiring this subsystem.", + + "This will likely prevent any other commands from requiring this resource.", true); // Warn, but allow -- there might be a use case for this. } - m_subsystems.put(subsystem, defaultCommand); + m_resources.put(resource, defaultCommand); } /** - * Removes the default command for a subsystem. The current default command will run until another - * command is scheduled that requires the subsystem, at which point the current default command + * Removes the default command for a resource. The current default command will run until another + * command is scheduled that requires the resource, at which point the current default command * will not be re-scheduled. * - * @param subsystem the subsystem whose default command will be removed + * @param resource the resource whose default command will be removed */ - public void removeDefaultCommand(Subsystem subsystem) { - if (subsystem == null) { - DriverStation.reportWarning("Tried to remove a default command for a null subsystem", true); + public void removeDefaultCommand(Resource resource) { + if (resource == null) { + DriverStation.reportWarning("Tried to remove a default command for a null resource", true); return; } - m_subsystems.put(subsystem, null); + m_resources.put(resource, null); } /** - * Gets the default command associated with this subsystem. Null if this subsystem has no default + * Gets the default command associated with this resource. Null if this resource has no default * command associated with it. * - * @param subsystem the subsystem to inquire about - * @return the default command associated with the subsystem + * @param resource the resource to inquire about + * @return the default command associated with the resource */ - public Command getDefaultCommand(Subsystem subsystem) { - return m_subsystems.get(subsystem); + public Command getDefaultCommand(Resource resource) { + return m_resources.get(resource); } /** @@ -509,15 +537,15 @@ public boolean isScheduled(Command... commands) { } /** - * Returns the command currently requiring a given subsystem. Null if no command is currently - * requiring the subsystem + * Returns the command currently requiring a given resource. Null if no command is currently + * requiring the resource * - * @param subsystem the subsystem to be inquired about - * @return the command currently requiring the subsystem, or null if no command is currently + * @param resource the resource to be inquired about + * @return the command currently requiring the resource, or null if no command is currently * scheduled */ - public Command requiring(Subsystem subsystem) { - return m_requirements.get(subsystem); + public Command requiring(Resource resource) { + return m_requirements.get(resource); } /** Disables the command scheduler. */ 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 0d2178f6b57..b0e5fbc101c 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 @@ -34,7 +34,7 @@ public static Command none() { * @param requirements Subsystems to require * @return the command */ - public static Command idle(Subsystem... requirements) { + public static Command idle(Resource... requirements) { return run(() -> {}, requirements); } @@ -48,7 +48,7 @@ public static Command idle(Subsystem... requirements) { * @return the command * @see InstantCommand */ - public static Command runOnce(Runnable action, Subsystem... requirements) { + public static Command runOnce(Runnable action, Resource... requirements) { return new InstantCommand(action, requirements); } @@ -60,7 +60,7 @@ public static Command runOnce(Runnable action, Subsystem... requirements) { * @return the command * @see RunCommand */ - public static Command run(Runnable action, Subsystem... requirements) { + public static Command run(Runnable action, Resource... requirements) { return new RunCommand(action, requirements); } @@ -74,7 +74,7 @@ public static Command run(Runnable action, Subsystem... requirements) { * @return the command * @see StartEndCommand */ - public static Command startEnd(Runnable start, Runnable end, Subsystem... requirements) { + public static Command startEnd(Runnable start, Runnable end, Resource... requirements) { return new StartEndCommand(start, end, requirements); } @@ -87,7 +87,7 @@ public static Command startEnd(Runnable start, Runnable end, Subsystem... requir * @param requirements subsystems the action requires * @return the command */ - public static Command runEnd(Runnable run, Runnable end, Subsystem... requirements) { + public static Command runEnd(Runnable run, Runnable end, Resource... requirements) { requireNonNullParam(end, "end", "Command.runEnd"); return new FunctionalCommand( () -> {}, run, interrupted -> end.run(), () -> false, requirements); @@ -102,7 +102,7 @@ public static Command runEnd(Runnable run, Runnable end, Subsystem... requiremen * @param requirements subsystems the action requires * @return the command */ - public static Command startRun(Runnable start, Runnable run, Subsystem... requirements) { + public static Command startRun(Runnable start, Runnable run, Resource... requirements) { return new FunctionalCommand(start, run, interrupted -> {}, () -> false, requirements); } @@ -188,7 +188,7 @@ public static Command select(Map commands, Supplier * @return the command * @see DeferredCommand */ - public static Command defer(Supplier supplier, Set requirements) { + public static Command defer(Supplier supplier, Set requirements) { return new DeferredCommand(supplier, requirements); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java index f76cf909238..82c6df74f96 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/DeferredCommand.java @@ -39,9 +39,9 @@ public class DeferredCommand extends Command { * set. */ @SuppressWarnings("this-escape") - public DeferredCommand(Supplier supplier, Set requirements) { + public DeferredCommand(Supplier supplier, Set requirements) { m_supplier = requireNonNullParam(supplier, "supplier", "DeferredCommand"); - addRequirements(requirements.toArray(new Subsystem[0])); + addRequirements(requirements.toArray(new Resource[0])); } @Override 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 9f1d8a8130a..1e3f07912bd 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 @@ -38,7 +38,7 @@ public FunctionalCommand( Runnable onExecute, Consumer onEnd, BooleanSupplier isFinished, - Subsystem... requirements) { + Resource... requirements) { m_onInit = requireNonNullParam(onInit, "onInit", "FunctionalCommand"); m_onExecute = requireNonNullParam(onExecute, "onExecute", "FunctionalCommand"); m_onEnd = requireNonNullParam(onEnd, "onEnd", "FunctionalCommand"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java index 25f7c9a1092..553ac8d8dd8 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/InstantCommand.java @@ -18,7 +18,7 @@ public class InstantCommand extends FunctionalCommand { * @param toRun the Runnable to run * @param requirements the subsystems required by this command */ - public InstantCommand(Runnable toRun, Subsystem... requirements) { + public InstantCommand(Runnable toRun, Resource... requirements) { super(toRun, () -> {}, interrupted -> {}, () -> true, requirements); } 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 06663c9a800..65f8135ceca 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 @@ -103,7 +103,7 @@ public MecanumControllerCommand( PIDController rearRightController, Supplier currentWheelSpeeds, Consumer outputDriveVoltages, - Subsystem... requirements) { + Resource... requirements) { m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand"); m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand"); m_feedforward = requireNonNullParam(feedforward, "feedforward", "MecanumControllerCommand"); @@ -189,7 +189,7 @@ public MecanumControllerCommand( PIDController rearRightController, Supplier currentWheelSpeeds, Consumer outputDriveVoltages, - Subsystem... requirements) { + Resource... requirements) { this( trajectory, pose, @@ -241,7 +241,7 @@ public MecanumControllerCommand( Supplier desiredRotation, double maxWheelVelocityMetersPerSecond, Consumer outputWheelSpeeds, - Subsystem... requirements) { + Resource... requirements) { m_trajectory = requireNonNullParam(trajectory, "trajectory", "MecanumControllerCommand"); m_pose = requireNonNullParam(pose, "pose", "MecanumControllerCommand"); m_feedforward = new SimpleMotorFeedforward(0, 0, 0); @@ -307,7 +307,7 @@ public MecanumControllerCommand( ProfiledPIDController thetaController, double maxWheelVelocityMetersPerSecond, Consumer outputWheelSpeeds, - Subsystem... requirements) { + Resource... requirements) { this( trajectory, pose, 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 4109091cd11..42e8e9ab9de 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 @@ -29,7 +29,7 @@ public class NotifierCommand extends Command { * @param requirements the subsystems required by this command */ @SuppressWarnings("this-escape") - public NotifierCommand(Runnable toRun, double period, Subsystem... requirements) { + public NotifierCommand(Runnable toRun, double period, Resource... requirements) { m_notifier = new Notifier(toRun); m_period = period; addRequirements(requirements); 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 26627fa30ff..57d17ce2677 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 @@ -45,7 +45,7 @@ public PIDCommand( DoubleSupplier measurementSource, DoubleSupplier setpointSource, DoubleConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { requireNonNullParam(controller, "controller", "PIDCommand"); requireNonNullParam(measurementSource, "measurementSource", "PIDCommand"); requireNonNullParam(setpointSource, "setpointSource", "PIDCommand"); @@ -72,7 +72,7 @@ public PIDCommand( DoubleSupplier measurementSource, double setpoint, DoubleConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { this(controller, measurementSource, () -> setpoint, useOutput, requirements); } 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 4e82811739b..0076305583e 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 @@ -48,7 +48,7 @@ public ProfiledPIDCommand( DoubleSupplier measurementSource, Supplier goalSource, BiConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { requireNonNullParam(controller, "controller", "ProfiledPIDCommand"); requireNonNullParam(measurementSource, "measurementSource", "ProfiledPIDCommand"); requireNonNullParam(goalSource, "goalSource", "ProfiledPIDCommand"); @@ -76,7 +76,7 @@ public ProfiledPIDCommand( DoubleSupplier measurementSource, DoubleSupplier goalSource, BiConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { requireNonNullParam(controller, "controller", "SynchronousPIDCommand"); requireNonNullParam(measurementSource, "measurementSource", "SynchronousPIDCommand"); requireNonNullParam(goalSource, "goalSource", "SynchronousPIDCommand"); @@ -104,7 +104,7 @@ public ProfiledPIDCommand( DoubleSupplier measurementSource, State goal, BiConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { this(controller, measurementSource, () -> goal, useOutput, requirements); } @@ -123,7 +123,7 @@ public ProfiledPIDCommand( DoubleSupplier measurementSource, double goal, BiConsumer useOutput, - Subsystem... requirements) { + Resource... requirements) { this(controller, measurementSource, () -> goal, useOutput, requirements); } 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 050e97048d8..1ae23c81f87 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 @@ -83,7 +83,7 @@ public RamseteCommand( PIDController leftController, PIDController rightController, BiConsumer outputVolts, - Subsystem... requirements) { + Resource... requirements) { m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand"); m_pose = requireNonNullParam(pose, "pose", "RamseteCommand"); m_follower = requireNonNullParam(controller, "controller", "RamseteCommand"); @@ -121,7 +121,7 @@ public RamseteCommand( RamseteController follower, DifferentialDriveKinematics kinematics, BiConsumer outputMetersPerSecond, - Subsystem... requirements) { + Resource... requirements) { m_trajectory = requireNonNullParam(trajectory, "trajectory", "RamseteCommand"); m_pose = requireNonNullParam(pose, "pose", "RamseteCommand"); m_follower = requireNonNullParam(follower, "follower", "RamseteCommand"); diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Resource.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Resource.java new file mode 100644 index 00000000000..e186df517d2 --- /dev/null +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/Resource.java @@ -0,0 +1,171 @@ +// Copyright (c) FIRST and other WPILib contributors. +// Open Source Software; you can modify and/or share it under the terms of +// the WPILib BSD license file in the root directory of this project. + +package edu.wpi.first.wpilibj2.command; + +import java.util.Set; +import java.util.function.Supplier; + +/** + * `Resource` is the locking + * implementation for the Command-based concurrency model, encapsulating program state that should + * only be controlled by one {@link Command} at a time. If multiple commands requiring the same + * resource are scheduled at the same time, the {@link CommandScheduler} will resolve the resource + * contention by interrupting (or refusing to schedule) all but one of the commands. + * + *

Typically, protected state represents hardware resources (like motors) for which control + * disputes would present an operational hazard. But, it may also be appropriate to + * protect software resources, like vision pipelines, whose outputs might become invalid if + * their configurations are changed inappropriately during a task. + * + *

Classes containing protected state should implement this interface. Commands that require + * said state should be written using the Command factories (e.g. {@link Resource#run(Runnable)} + * defined on this interface, which automatically declare the resource requirement. + */ +public interface Resource { + /** + * This method is called periodically by the {@link CommandScheduler}. Useful for updating + * resource-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() {} + + /** + * This method is called periodically by the {@link CommandScheduler}. Useful for updating + * resource-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() {} + + /** + * Gets the name of this resource for telemetry. + * + * @return resource name + */ + default String getName() { + return this.getClass().getSimpleName(); + } + + /** + * Sets the default {@link Command} of the resource. The default command will be automatically + * scheduled when no other commands are scheduled that require the resource. Default commands + * should generally not end on their own, i.e. their {@link Command#isFinished()} method should + * always return false. Will automatically register this resource with the {@link + * CommandScheduler}. + * + * @param defaultCommand the default command to associate with this resource + */ + default void setDefaultCommand(Command defaultCommand) { + CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand); + } + + /** + * Removes the default command for the resource. This will not cancel the default command if it + * is currently running. + */ + default void removeDefaultCommand() { + CommandScheduler.getInstance().removeDefaultCommand(this); + } + + /** + * Gets the default command for this resource. Returns null if no default command is currently + * associated with the resource. + * + * @return the default command associated with this resource + */ + default Command getDefaultCommand() { + return CommandScheduler.getInstance().getDefaultCommand(this); + } + + /** + * Returns the command currently running on this resource. Returns null if no command is + * currently scheduled that requires this resource. + * + * @return the scheduled command currently requiring this resource + */ + default Command getCurrentCommand() { + return CommandScheduler.getInstance().requiring(this); + } + + /** + * Registers this resource with the {@link CommandScheduler}, allowing its {@link + * Resource#periodic()} method to be called when the scheduler runs. + */ + default void register() { + CommandScheduler.getInstance().registerResources(this); + } + + /** + * Constructs a command that runs an action once and finishes. Requires this resource. + * + * @param action the action to run + * @return the command + * @see InstantCommand + */ + default Command runOnce(Runnable action) { + return Commands.runOnce(action, this); + } + + /** + * Constructs a command that runs an action every iteration until interrupted. Requires this + * resource. + * + * @param action the action to run + * @return the command + * @see RunCommand + */ + default Command run(Runnable action) { + return Commands.run(action, this); + } + + /** + * Constructs a command that runs an action once and another action when the command is + * interrupted. Requires this resource. + * + * @param start the action to run on start + * @param end the action to run on interrupt + * @return the command + * @see StartEndCommand + */ + default Command startEnd(Runnable start, Runnable end) { + return Commands.startEnd(start, end, this); + } + + /** + * Constructs a command that runs an action every iteration until interrupted, and then runs a + * second action. Requires this resource. + * + * @param run the action to run every iteration + * @param end the action to run on interrupt + * @return the command + */ + default Command runEnd(Runnable run, Runnable end) { + return Commands.runEnd(run, end, this); + } + + /** + * Constructs a command that runs an action once and then runs another action every iteration + * until interrupted. Requires this resource. + * + * @param start the action to run on start + * @param run the action to run every iteration + * @return the command + */ + default Command startRun(Runnable start, Runnable run) { + return Commands.startRun(start, run, this); + } + + /** + * Constructs a {@link DeferredCommand} with the provided supplier. This resource is added as a + * requirement. + * + * @param supplier the command supplier. + * @return the command. + * @see DeferredCommand + */ + default Command defer(Supplier supplier) { + return Commands.defer(supplier, Set.of(this)); + } +} diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java index c0a17b57c18..d25ee4fe5a2 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/RunCommand.java @@ -21,7 +21,7 @@ public class RunCommand extends FunctionalCommand { * @param toRun the Runnable to run * @param requirements the subsystems to require */ - public RunCommand(Runnable toRun, Subsystem... requirements) { + public RunCommand(Runnable toRun, Resource... requirements) { super(() -> {}, toRun, interrupted -> {}, () -> false, requirements); } } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java index 9eff70d9d94..e04b0cab35c 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/StartEndCommand.java @@ -25,7 +25,7 @@ public class StartEndCommand extends FunctionalCommand { * @param onEnd the Runnable to run on command end * @param requirements the subsystems required by this command */ - public StartEndCommand(Runnable onInit, Runnable onEnd, Subsystem... requirements) { + public StartEndCommand(Runnable onInit, Runnable onEnd, Resource... requirements) { super( onInit, () -> {}, 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 c0e694774c3..83936f723f8 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 @@ -1,14 +1,11 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - package edu.wpi.first.wpilibj2.command; -import java.util.Set; -import java.util.function.Supplier; - /** - * A robot subsystem. Subsystems are the basic unit of robot organization in the Command-based + * NOTE: The `Subsystem` interface has been renamed to {@link Resource}; this interface remains as + * an alias for backwards-compatibility. The new name better represents the in-code purpose of + * the interface. + * + *

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 * provide methods through which they can be used by {@link Command}s. Subsystems are used by the * {@link CommandScheduler}'s resource management system to ensure multiple robot actions are not @@ -24,149 +21,5 @@ * *

This class is provided by the NewCommands VendorDep */ -public interface Subsystem { - /** - * 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() {} - - /** - * 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() {} - - /** - * Gets the subsystem name of this Subsystem. - * - * @return Subsystem name - */ - default String getName() { - return this.getClass().getSimpleName(); - } - - /** - * Sets the default {@link Command} of the subsystem. The default command will be automatically - * scheduled when no other commands are scheduled that require the subsystem. Default commands - * should generally not end on their own, i.e. their {@link Command#isFinished()} method should - * always return false. Will automatically register this subsystem with the {@link - * CommandScheduler}. - * - * @param defaultCommand the default command to associate with this subsystem - */ - default void setDefaultCommand(Command defaultCommand) { - CommandScheduler.getInstance().setDefaultCommand(this, defaultCommand); - } - - /** - * Removes the default command for the subsystem. This will not cancel the default command if it - * is currently running. - */ - default void removeDefaultCommand() { - CommandScheduler.getInstance().removeDefaultCommand(this); - } - - /** - * Gets the default command for this subsystem. Returns null if no default command is currently - * associated with the subsystem. - * - * @return the default command associated with this subsystem - */ - default Command getDefaultCommand() { - return CommandScheduler.getInstance().getDefaultCommand(this); - } - - /** - * Returns the command currently running on this subsystem. Returns null if no command is - * currently scheduled that requires this subsystem. - * - * @return the scheduled command currently requiring this subsystem - */ - default Command getCurrentCommand() { - return CommandScheduler.getInstance().requiring(this); - } - - /** - * Registers this subsystem with the {@link CommandScheduler}, allowing its {@link - * Subsystem#periodic()} method to be called when the scheduler runs. - */ - default void register() { - CommandScheduler.getInstance().registerSubsystem(this); - } - - /** - * Constructs a command that runs an action once and finishes. Requires this subsystem. - * - * @param action the action to run - * @return the command - * @see InstantCommand - */ - default Command runOnce(Runnable action) { - return Commands.runOnce(action, this); - } - - /** - * Constructs a command that runs an action every iteration until interrupted. Requires this - * subsystem. - * - * @param action the action to run - * @return the command - * @see RunCommand - */ - default Command run(Runnable action) { - return Commands.run(action, this); - } - - /** - * Constructs a command that runs an action once and another action when the command is - * interrupted. Requires this subsystem. - * - * @param start the action to run on start - * @param end the action to run on interrupt - * @return the command - * @see StartEndCommand - */ - default Command startEnd(Runnable start, Runnable end) { - return Commands.startEnd(start, end, this); - } - - /** - * Constructs a command that runs an action every iteration until interrupted, and then runs a - * second action. Requires this subsystem. - * - * @param run the action to run every iteration - * @param end the action to run on interrupt - * @return the command - */ - default Command runEnd(Runnable run, Runnable end) { - return Commands.runEnd(run, end, this); - } - - /** - * Constructs a command that runs an action once and then runs another action every iteration - * until interrupted. Requires this subsystem. - * - * @param start the action to run on start - * @param run the action to run every iteration - * @return the command - */ - default Command startRun(Runnable start, Runnable run) { - return Commands.startRun(start, run, this); - } - - /** - * Constructs a {@link DeferredCommand} with the provided supplier. This subsystem is added as a - * requirement. - * - * @param supplier the command supplier. - * @return the command. - * @see DeferredCommand - */ - default Command defer(Supplier supplier) { - return Commands.defer(supplier, Set.of(this)); - } +public interface Subsystem extends Resource { } 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 3a024e5f665..469b13d492a 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 @@ -14,14 +14,14 @@ * *

This class is provided by the NewCommands VendorDep */ -public abstract class SubsystemBase implements Subsystem, Sendable { +public abstract class SubsystemBase implements Resource, Sendable { /** Constructor. Telemetry/log name defaults to the classname. */ @SuppressWarnings("this-escape") public SubsystemBase() { String name = this.getClass().getSimpleName(); name = name.substring(name.lastIndexOf('.') + 1); SendableRegistry.addLW(this, name, name); - CommandScheduler.getInstance().registerSubsystem(this); + CommandScheduler.getInstance().registerResources(this); } /** @@ -32,7 +32,7 @@ public SubsystemBase() { @SuppressWarnings("this-escape") public SubsystemBase(String name) { SendableRegistry.addLW(this, name, name); - CommandScheduler.getInstance().registerSubsystem(this); + CommandScheduler.getInstance().registerResources(this); } /** 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 424a288b03b..24bccc338ca 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 @@ -70,7 +70,7 @@ public SwerveControllerCommand( ProfiledPIDController thetaController, Supplier desiredRotation, Consumer outputModuleStates, - Subsystem... requirements) { + Resource... requirements) { this( trajectory, pose, @@ -115,7 +115,7 @@ public SwerveControllerCommand( PIDController yController, ProfiledPIDController thetaController, Consumer outputModuleStates, - Subsystem... requirements) { + Resource... requirements) { this( trajectory, pose, @@ -156,7 +156,7 @@ public SwerveControllerCommand( SwerveDriveKinematics kinematics, HolonomicDriveController controller, Consumer outputModuleStates, - Subsystem... requirements) { + Resource... requirements) { this( trajectory, pose, @@ -194,7 +194,7 @@ public SwerveControllerCommand( HolonomicDriveController controller, Supplier desiredRotation, Consumer outputModuleStates, - Subsystem... requirements) { + Resource... requirements) { m_trajectory = requireNonNullParam(trajectory, "trajectory", "SwerveControllerCommand"); m_pose = requireNonNullParam(pose, "pose", "SwerveControllerCommand"); m_kinematics = requireNonNullParam(kinematics, "kinematics", "SwerveControllerCommand"); 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 8e49706958c..b2cab0459b8 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 @@ -40,7 +40,7 @@ public TrapezoidProfileCommand( Consumer output, Supplier goal, Supplier currentState, - Subsystem... requirements) { + Resource... requirements) { m_profile = requireNonNullParam(profile, "profile", "TrapezoidProfileCommand"); m_output = requireNonNullParam(output, "output", "TrapezoidProfileCommand"); m_goal = goal; 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 00a1d887728..883afcdfad2 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 @@ -82,7 +82,7 @@ public boolean isFinished() { * @return the set of subsystems that are required */ @Override - public Set getRequirements() { + public Set getRequirements() { return m_command.getRequirements(); } diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutine.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutine.java index 053a404c779..cb6d9305b96 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutine.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutine.java @@ -18,7 +18,8 @@ import edu.wpi.first.wpilibj.Timer; import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Subsystem; +import edu.wpi.first.wpilibj2.command.Resource; + import java.util.Map; import java.util.function.Consumer; @@ -141,7 +142,7 @@ public static class Mechanism { public final Consumer m_log; /** The subsystem containing the motor(s) that is (or are) being characterized. */ - public final Subsystem m_subsystem; + public final Resource m_resource; /** The name of the mechanism being tested. */ public final String m_name; @@ -156,7 +157,7 @@ public static class Mechanism { * call one or more of the chainable logging handles (e.g. `voltage`) on the returned * `MotorLog`. Multiple motors can be logged in a single callback by calling `motor` * multiple times. - * @param subsystem The subsystem containing the motor(s) that is (or are) being characterized. + * @param resource The subsystem containing the motor(s) that is (or are) being characterized. * Will be declared as a requirement for the returned test commands. * @param name The name of the mechanism being tested. Will be appended to the log entry title * for the routine's test state, e.g. "sysid-test-state-mechanism". Defaults to the name of @@ -165,12 +166,12 @@ public static class Mechanism { public Mechanism( Consumer> drive, Consumer log, - Subsystem subsystem, + Resource resource, String name) { m_drive = drive; m_log = log != null ? log : l -> {}; - m_subsystem = subsystem; - m_name = name != null ? name : subsystem.getName(); + m_resource = resource; + m_name = name != null ? name : resource.getName(); } /** @@ -184,14 +185,14 @@ public Mechanism( * call one or more of the chainable logging handles (e.g. `voltage`) on the returned * `MotorLog`. Multiple motors can be logged in a single callback by calling `motor` * multiple times. - * @param subsystem The subsystem containing the motor(s) that is (or are) being characterized. + * @param resource The subsystem containing the motor(s) that is (or are) being characterized. * Will be declared as a requirement for the returned test commands. The subsystem's `name` * will be appended to the log entry title for the routine's test state, e.g. * "sysid-test-state-subsystem". */ public Mechanism( - Consumer> drive, Consumer log, Subsystem subsystem) { - this(drive, log, subsystem, null); + Consumer> drive, Consumer log, Resource resource) { + this(drive, log, resource, null); } } @@ -225,10 +226,10 @@ public Command quasistatic(Direction direction) { Timer timer = new Timer(); return m_mechanism - .m_subsystem + .m_resource .runOnce(timer::restart) .andThen( - m_mechanism.m_subsystem.run( + m_mechanism.m_resource.run( () -> { m_mechanism.m_drive.accept( m_outputVolts.mut_replace( @@ -266,11 +267,11 @@ public Command dynamic(Direction direction) { .get(direction); return m_mechanism - .m_subsystem + .m_resource .runOnce( () -> m_outputVolts.mut_replace(m_config.m_stepVoltage.in(Volts) * outputSign, Volts)) .andThen( - m_mechanism.m_subsystem.run( + m_mechanism.m_resource.run( () -> { m_mechanism.m_drive.accept(m_outputVolts); m_mechanism.m_log.accept(this); 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 47657e19ed8..de74baf4e69 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() {}; + Resource requirement = new SubsystemBase() {}; MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement); Command interrupted = interruptedHolder.getMock(); @@ -42,7 +42,7 @@ void requirementInterruptTest() { @Test void requirementUninterruptibleTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; Command notInterrupted = new RunCommand(() -> {}, requirement) @@ -61,7 +61,7 @@ void requirementUninterruptibleTest() { @Test void defaultCommandRequirementErrorTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem system = new SubsystemBase() {}; + Resource system = new SubsystemBase() {}; Command missingRequirement = new WaitUntilCommand(() -> false); 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 13f65977385..8e2700b32c9 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 @@ -45,7 +45,7 @@ public void setDSEnabled(boolean enabled) { public static class MockCommandHolder { private final Command m_mockCommand = mock(Command.class); - public MockCommandHolder(boolean runWhenDisabled, Subsystem... requirements) { + public MockCommandHolder(boolean runWhenDisabled, Resource... requirements) { when(m_mockCommand.getRequirements()).thenReturn(Set.of(requirements)); when(m_mockCommand.isFinished()).thenReturn(false); when(m_mockCommand.runsWhenDisabled()).thenReturn(runWhenDisabled); 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 4659f0ec3d4..677bbebc4af 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 @@ void conditionalCommandTest() { @Test void conditionalCommandRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; 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 23ae47d6489..f07d1679790 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() {}; + Resource hasDefaultCommand = new SubsystemBase() {}; MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); @@ -29,7 +29,7 @@ void defaultCommandScheduleTest() { @Test void defaultCommandInterruptResumeTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Resource hasDefaultCommand = new SubsystemBase() {}; MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); @@ -54,7 +54,7 @@ void defaultCommandInterruptResumeTest() { @Test void defaultCommandDisableResumeTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Resource hasDefaultCommand = new SubsystemBase() {}; MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand); Command defaultCommand = defaultHolder.getMock(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java index 259ba0fdcef..f143e6e91b4 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java @@ -65,10 +65,10 @@ void deferredSupplierOnlyCalledDuringInit() { @Test void deferredRequirementsTest() { - Subsystem subsystem = new Subsystem() {}; - DeferredCommand command = new DeferredCommand(Commands::none, Set.of(subsystem)); + Resource resource = new Resource() {}; + DeferredCommand command = new DeferredCommand(Commands::none, Set.of(resource)); - assertTrue(command.getRequirements().contains(subsystem)); + assertTrue(command.getRequirements().contains(resource)); } @Test diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java index 9ac412ce50b..2260cc741b1 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MecanumControllerCommandTest.java @@ -93,7 +93,7 @@ public Pose2d getRobotPose() { @Test @ResourceLock("timing") void testReachesReference() { - final var subsystem = new Subsystem() {}; + final var subsystem = new Resource() {}; final var waypoints = new ArrayList(); waypoints.add(Pose2d.kZero); 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 a837baac8aa..d78b24eb1c4 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 @@ -89,10 +89,10 @@ void notScheduledCancelTest() { @Test void parallelGroupRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; + Resource system4 = new SubsystemBase() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -114,9 +114,9 @@ void parallelGroupRequirementTest() { @Test void parallelGroupRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; 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 206d801015b..912a1eff677 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 @@ void parallelDeadlineInterruptTest() { @Test void parallelDeadlineRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; + Resource system4 = new SubsystemBase() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -112,9 +112,9 @@ void parallelDeadlineRequirementTest() { @Test void parallelDeadlineRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; 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 ea780c6216e..5270a1caf0e 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 @@ -91,10 +91,10 @@ void notScheduledCancelTest() { @Test void parallelRaceRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; + Resource system4 = new SubsystemBase() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); @@ -116,9 +116,9 @@ void parallelRaceRequirementTest() { @Test void parallelRaceRequirementErrorTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); Command command1 = command1Holder.getMock(); @@ -130,8 +130,8 @@ void parallelRaceRequirementErrorTest() { @Test void parallelRaceOnlyCallsEndOnceTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; 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 1e0b33332e8..d175e52df6e 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 @@ -71,9 +71,9 @@ void schedulerInterruptCauseLambdaTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem subsystem = new Subsystem() {}; - Command command = subsystem.run(() -> {}); - Command interruptor = subsystem.runOnce(() -> {}); + Resource resource = new Resource() {}; + Command command = resource.run(() -> {}); + Command interruptor = resource.runOnce(() -> {}); scheduler.onCommandInterrupt( (interrupted, cause) -> { @@ -94,9 +94,9 @@ void schedulerInterruptCauseLambdaInRunLoopTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem subsystem = new Subsystem() {}; - Command command = subsystem.run(() -> {}); - Command interruptor = subsystem.runOnce(() -> {}); + Resource resource = new Resource() {}; + Command command = resource.run(() -> {}); + Command interruptor = resource.runOnce(() -> {}); // This command will schedule interruptor in execute() inside the run loop Command interruptorScheduler = Commands.runOnce(() -> scheduler.schedule(interruptor)); @@ -120,7 +120,7 @@ void schedulerInterruptCauseLambdaInRunLoopTest() { void registerSubsystemTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(0); - Subsystem system = + Resource system = new SubsystemBase() { @Override public void periodic() { @@ -128,7 +128,7 @@ public void periodic() { } }; - assertDoesNotThrow(() -> scheduler.registerSubsystem(system)); + assertDoesNotThrow(() -> scheduler.registerResources(system)); scheduler.run(); assertEquals(1, counter.get()); @@ -139,14 +139,14 @@ public void periodic() { void unregisterSubsystemTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(0); - Subsystem system = + Resource system = new SubsystemBase() { @Override public void periodic() { counter.incrementAndGet(); } }; - scheduler.registerSubsystem(system); + scheduler.registerResources(system); assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system)); scheduler.run(); 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 a253740c028..44c4a9b5d7f 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 @@ -26,7 +26,7 @@ void cancelFromInitialize(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean hasOtherRun = new AtomicBoolean(); AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; Command selfCancels = new Command() { { @@ -70,7 +70,7 @@ void cancelFromInitializeAction(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean hasOtherRun = new AtomicBoolean(); AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new Subsystem() {}; + Resource requirement = new Resource() {}; Command selfCancels = new Command() { { @@ -110,7 +110,7 @@ void defaultCommandGetsRescheduledAfterSelfCanceling(InterruptionBehavior interr try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean hasOtherRun = new AtomicBoolean(); AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; Command selfCancels = new Command() { { @@ -328,7 +328,7 @@ public void end(boolean interrupted) { void scheduleFromEndCancel() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; InstantCommand other = new InstantCommand(() -> {}, requirement); FunctionalCommand selfCancels = new FunctionalCommand( @@ -353,7 +353,7 @@ void scheduleFromEndCancel() { void scheduleFromEndInterrupt() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; InstantCommand other = new InstantCommand(() -> {}, requirement); FunctionalCommand selfCancels = new FunctionalCommand( @@ -379,7 +379,7 @@ void scheduleFromEndInterrupt() { void scheduleFromEndInterruptAction() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new Subsystem() {}; + Resource requirement = new Resource() {}; InstantCommand other = new InstantCommand(() -> {}, requirement); InstantCommand selfCancels = new InstantCommand(() -> {}, requirement); scheduler.onCommandInterrupt( @@ -401,7 +401,7 @@ void scheduleFromEndInterruptAction() { void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehavior) { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; + Resource requirement = new SubsystemBase() {}; Command other = new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior); FunctionalCommand defaultCommand = @@ -430,7 +430,7 @@ void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehav void cancelDefaultCommandFromEnd() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new Subsystem() {}; + Resource requirement = new Resource() {}; Command defaultCommand = new FunctionalCommand( () -> {}, 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 e364468186c..1b4be814b8c 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 @@ void selectCommandInvalidKeyTest() { @Test void selectCommandRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; + Resource system4 = new SubsystemBase() {}; 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 abbc49062c7..2f40bed2595 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 @@ -99,10 +99,10 @@ void notScheduledCancelTest() { @Test void sequentialGroupRequirementTest() { - Subsystem system1 = new SubsystemBase() {}; - Subsystem system2 = new SubsystemBase() {}; - Subsystem system3 = new SubsystemBase() {}; - Subsystem system4 = new SubsystemBase() {}; + Resource system1 = new SubsystemBase() {}; + Resource system2 = new SubsystemBase() {}; + Resource system3 = new SubsystemBase() {}; + Resource system4 = new SubsystemBase() {}; try (CommandScheduler scheduler = new CommandScheduler()) { MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java index 2f6c6965656..30808b156a5 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SwerveControllerCommandTest.java @@ -92,7 +92,7 @@ public Pose2d getRobotPose() { @Test @ResourceLock("timing") void testReachesReference() { - final var subsystem = new Subsystem() {}; + final var subsystem = new Resource() {}; final var waypoints = new ArrayList(); waypoints.add(Pose2d.kZero); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutineTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutineTest.java index 3d885b21bd9..2bd4252b4ea 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutineTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/sysid/SysIdRoutineTest.java @@ -19,13 +19,13 @@ import edu.wpi.first.wpilibj.simulation.SimHooks; import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.Subsystem; +import edu.wpi.first.wpilibj2.command.Resource; import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; import org.junit.jupiter.api.Test; class SysIdRoutineTest { - interface Mechanism extends Subsystem { + interface Mechanism extends Resource { void recordState(SysIdRoutineLog.State state); void drive(Measure voltage); @@ -57,7 +57,7 @@ void setup() { m_sysidRoutine = new SysIdRoutine( new SysIdRoutine.Config(null, null, null, m_mechanism::recordState), - new SysIdRoutine.Mechanism(m_mechanism::drive, m_mechanism::log, new Subsystem() {})); + new SysIdRoutine.Mechanism(m_mechanism::drive, m_mechanism::log, new Resource() {})); m_quasistaticForward = m_sysidRoutine.quasistatic(SysIdRoutine.Direction.kForward); m_quasistaticReverse = m_sysidRoutine.quasistatic(SysIdRoutine.Direction.kReverse); m_dynamicForward = m_sysidRoutine.dynamic(SysIdRoutine.Direction.kForward);