diff --git a/commandsv3/src/main/java/org/wpilib/command3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/command3/Mechanism.java
index 925b649b52..ad9664a6f8 100644
--- a/commandsv3/src/main/java/org/wpilib/command3/Mechanism.java
+++ b/commandsv3/src/main/java/org/wpilib/command3/Mechanism.java
@@ -10,61 +10,33 @@ import org.wpilib.annotation.NoDiscard;
import org.wpilib.units.measure.Time;
/**
- * Generic base class to represent mechanisms on a robot. Commands can require sole ownership of a
+ * Generic interface to represent mechanisms on a robot. Commands can require sole ownership of a
* mechanism; when a command that requires a mechanism is running, no other commands may use it at
* the same time.
*
- *
Even though this class is named "Mechanism", it may be used to represent other physical
+ *
Even though this interface is named "Mechanism", it may be used to represent other physical
* hardware on a robot that should be controlled with commands - for example, an LED strip or a
* vision processor that can switch between different pipelines could be represented as mechanisms.
*/
-public class Mechanism {
- private final String m_name;
-
- private final Scheduler m_registeredScheduler;
-
+public interface Mechanism {
/**
- * Creates a new mechanism registered with the default scheduler instance and named using the name
- * of the class. Intended to be used by subclasses to get sane defaults without needing to
- * manually declare a constructor.
- */
- @SuppressWarnings("this-escape")
- protected Mechanism() {
- m_name = getClass().getSimpleName();
- m_registeredScheduler = Scheduler.getDefault();
- setDefaultCommand(idle());
- }
-
- /**
- * Creates a new mechanism, registered with the default scheduler instance.
+ * Returns the scheduler under which this subsystem and its default commands are registered. The
+ * scheduler is also used to fetch running commands for the subsystem.
*
- * @param name The name of the mechanism. Cannot be null.
+ * @return The registered scheduler.
*/
- public Mechanism(String name) {
- this(name, Scheduler.getDefault());
+ default Scheduler getRegisteredScheduler() {
+ return Scheduler.getDefault();
}
/**
- * Creates a new mechanism, registered with the given scheduler instance.
- *
- * @param name The name of the mechanism. Cannot be null.
- * @param scheduler The registered scheduler. Cannot be null.
- */
- @SuppressWarnings("this-escape")
- public Mechanism(String name, Scheduler scheduler) {
- m_name = name;
- m_registeredScheduler = scheduler;
- setDefaultCommand(idle());
- }
-
- /**
- * Gets the name of this mechanism.
+ * Gets the name of this mechanism. This will default to the name of this mechanism's class.
*
* @return The name of the mechanism.
*/
@NoDiscard
- public String getName() {
- return m_name;
+ default String getName() {
+ return getClass().getSimpleName();
}
/**
@@ -79,8 +51,8 @@ public class Mechanism {
*
* @param defaultCommand the new default command
*/
- public void setDefaultCommand(Command defaultCommand) {
- m_registeredScheduler.setDefaultCommand(this, defaultCommand);
+ default void setDefaultCommand(Command defaultCommand) {
+ getRegisteredScheduler().setDefaultCommand(this, defaultCommand);
}
/**
@@ -89,8 +61,8 @@ public class Mechanism {
*
* @return The currently configured default command
*/
- public Command getDefaultCommand() {
- return m_registeredScheduler.getDefaultCommandFor(this);
+ default Command getDefaultCommand() {
+ return getRegisteredScheduler().getDefaultCommandFor(this);
}
/**
@@ -99,7 +71,7 @@ public class Mechanism {
* @param commandBody The main function body of the command.
* @return The command builder, for further configuration.
*/
- public NeedsNameBuilderStage run(Consumer commandBody) {
+ default NeedsNameBuilderStage run(Consumer commandBody) {
return new StagedCommandBuilder().requiring(this).executing(commandBody);
}
@@ -111,7 +83,7 @@ public class Mechanism {
* @param loopBody The body of the infinite loop.
* @return The command builder, for further configuration.
*/
- public NeedsNameBuilderStage runRepeatedly(Runnable loopBody) {
+ default NeedsNameBuilderStage runRepeatedly(Runnable loopBody) {
return run(
coroutine -> {
while (true) {
@@ -131,7 +103,7 @@ public class Mechanism {
*
* @return A new idle command.
*/
- public Command idle() {
+ default Command idle() {
return run(Coroutine::park).withPriority(Command.LOWEST_PRIORITY).named(getName() + "[IDLE]");
}
@@ -141,7 +113,7 @@ public class Mechanism {
* @param duration How long the mechanism should idle for.
* @return A new idle command.
*/
- public Command idleFor(Time duration) {
+ default Command idleFor(Time duration) {
return idle().withTimeout(duration);
}
@@ -154,12 +126,7 @@ public class Mechanism {
* @return The currently running commands that require the mechanism.
*/
@NoDiscard
- public List getRunningCommands() {
- return m_registeredScheduler.getRunningCommandsFor(this);
- }
-
- @Override
- public String toString() {
- return m_name;
+ default List getRunningCommands() {
+ return getRegisteredScheduler().getRunningCommandsFor(this);
}
}
diff --git a/commandsv3/src/test/java/org/wpilib/command3/ConflictDetectorTest.java b/commandsv3/src/test/java/org/wpilib/command3/ConflictDetectorTest.java
index c5b0d73a11..6b1a101c81 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/ConflictDetectorTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/ConflictDetectorTest.java
@@ -23,7 +23,7 @@ class ConflictDetectorTest extends CommandTestBase {
@Test
void singleInputHasNoConflicts() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var command = Command.requiring(mech).executing(Coroutine::park).named("Command");
var conflicts = findAllConflicts(List.of(command));
assertEquals(0, conflicts.size());
@@ -31,7 +31,7 @@ class ConflictDetectorTest extends CommandTestBase {
@Test
void commandDoesNotConflictWithSelf() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var command = Command.requiring(mech).executing(Coroutine::park).named("Command");
var conflicts = findAllConflicts(List.of(command, command));
assertEquals(0, conflicts.size());
@@ -39,8 +39,8 @@ class ConflictDetectorTest extends CommandTestBase {
@Test
void detectManyConflicts() {
- var mech1 = new Mechanism("Mech 1", m_scheduler);
- var mech2 = new Mechanism("Mech 2", m_scheduler);
+ var mech1 = new DummyMechanism("Mech 1", m_scheduler);
+ var mech2 = new DummyMechanism("Mech 2", m_scheduler);
var command1 = Command.requiring(mech1, mech2).executing(Coroutine::park).named("Command1");
var command2 = Command.requiring(mech1).executing(Coroutine::park).named("Command2");
diff --git a/commandsv3/src/test/java/org/wpilib/command3/DummyMechanism.java b/commandsv3/src/test/java/org/wpilib/command3/DummyMechanism.java
new file mode 100644
index 0000000000..4fe557d1b7
--- /dev/null
+++ b/commandsv3/src/test/java/org/wpilib/command3/DummyMechanism.java
@@ -0,0 +1,32 @@
+// 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 org.wpilib.command3;
+
+/** A dummy mechanism that allows inline scheduler and name specification, for use in unit tests. */
+class DummyMechanism implements Mechanism {
+ private final String m_name;
+ private final Scheduler m_scheduler;
+
+ /**
+ * Creates a dummy mechanism.
+ *
+ * @param name The name of this dummy mechanism.
+ * @param scheduler The registered scheduler. Cannot be null.
+ */
+ DummyMechanism(String name, Scheduler scheduler) {
+ m_name = name;
+ m_scheduler = scheduler;
+ }
+
+ @Override
+ public String getName() {
+ return m_name;
+ }
+
+ @Override
+ public Scheduler getRegisteredScheduler() {
+ return m_scheduler;
+ }
+}
diff --git a/commandsv3/src/test/java/org/wpilib/command3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/command3/ParallelGroupTest.java
index 7411e288d6..97a955a5fb 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/ParallelGroupTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/ParallelGroupTest.java
@@ -16,8 +16,8 @@ import org.junit.jupiter.api.Test;
class ParallelGroupTest extends CommandTestBase {
@Test
void parallelAll() {
- var r1 = new Mechanism("R1", m_scheduler);
- var r2 = new Mechanism("R2", m_scheduler);
+ var r1 = new DummyMechanism("R1", m_scheduler);
+ var r2 = new DummyMechanism("R2", m_scheduler);
var c1Count = new AtomicInteger(0);
var c2Count = new AtomicInteger(0);
@@ -81,8 +81,8 @@ class ParallelGroupTest extends CommandTestBase {
@Test
void race() {
- var r1 = new Mechanism("R1", m_scheduler);
- var r2 = new Mechanism("R2", m_scheduler);
+ var r1 = new DummyMechanism("R1", m_scheduler);
+ var r2 = new DummyMechanism("R2", m_scheduler);
var c1Count = new AtomicInteger(0);
var c2Count = new AtomicInteger(0);
@@ -134,7 +134,7 @@ class ParallelGroupTest extends CommandTestBase {
@Test
void nested() {
- var mechanism = new Mechanism("mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("mechanism", m_scheduler);
var count = new AtomicInteger(0);
@@ -213,8 +213,8 @@ class ParallelGroupTest extends CommandTestBase {
@Test
void inheritsRequirements() {
- var mech1 = new Mechanism("Mech 1", m_scheduler);
- var mech2 = new Mechanism("Mech 2", m_scheduler);
+ var mech1 = new DummyMechanism("Mech 1", m_scheduler);
+ var mech2 = new DummyMechanism("Mech 2", m_scheduler);
var command1 = mech1.run(Coroutine::park).named("Command 1");
var command2 = mech2.run(Coroutine::park).named("Command 2");
var group = new ParallelGroup("Group", Set.of(command1, command2), Set.of());
@@ -223,8 +223,8 @@ class ParallelGroupTest extends CommandTestBase {
@Test
void inheritsPriority() {
- var mech1 = new Mechanism("Mech 1", m_scheduler);
- var mech2 = new Mechanism("Mech 2", m_scheduler);
+ var mech1 = new DummyMechanism("Mech 1", m_scheduler);
+ var mech2 = new DummyMechanism("Mech 2", m_scheduler);
var command1 = mech1.run(Coroutine::park).withPriority(100).named("Command 1");
var command2 = mech2.run(Coroutine::park).withPriority(200).named("Command 2");
var group = new ParallelGroup("Group", Set.of(command1, command2), Set.of());
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerCancellationTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerCancellationTests.java
index 82d7754969..ebb28e47ac 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerCancellationTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerCancellationTests.java
@@ -23,7 +23,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void cancelOnInterruptDoesNotResume() {
var count = new AtomicInteger(0);
- var mechanism = new Mechanism("mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("mechanism", m_scheduler);
var interrupter =
Command.requiring(mechanism)
@@ -54,7 +54,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void defaultCommandResumesAfterInterruption() {
var count = new AtomicInteger(0);
- var mechanism = new Mechanism("mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("mechanism", m_scheduler);
var defaultCmd =
mechanism
.run(
@@ -166,7 +166,9 @@ class SchedulerCancellationTests extends CommandTestBase {
void cancelAllStartsDefaults() {
var mechanisms = new ArrayList(10);
for (int i = 1; i <= 10; i++) {
- mechanisms.add(new Mechanism("System " + i, m_scheduler));
+ var mechanism = new DummyMechanism("System " + i, m_scheduler);
+ mechanism.setDefaultCommand(mechanism.idle());
+ mechanisms.add(mechanism);
}
var command = Command.requiring(mechanisms).executing(Coroutine::yield).named("Big Command");
@@ -235,7 +237,7 @@ class SchedulerCancellationTests extends CommandTestBase {
@Test
void compositionsDoNotSelfCancel() {
- var mech = new Mechanism("The mechanism", m_scheduler);
+ var mech = new DummyMechanism("The mechanism", m_scheduler);
var group =
mech.run(
co -> {
@@ -261,7 +263,7 @@ class SchedulerCancellationTests extends CommandTestBase {
@Test
void compositionsDoNotCancelParent() {
- var mech = new Mechanism("The mechanism", m_scheduler);
+ var mech = new DummyMechanism("The mechanism", m_scheduler);
var group =
mech.run(
co -> {
@@ -284,7 +286,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void doesNotRunOnCancelWhenInterruptingOnDeck() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd");
var interrupter = mechanism.run(Coroutine::yield).named("Interrupter");
m_scheduler.schedule(cmd);
@@ -298,7 +300,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void doesNotRunOnCancelWhenCancelingOnDeck() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd");
m_scheduler.schedule(cmd);
// canceling before calling .run()
@@ -312,7 +314,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void runsOnCancelWhenInterruptingCommand() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::park).whenCanceled(() -> ran.set(true)).named("cmd");
var interrupter = mechanism.run(Coroutine::park).named("Interrupter");
m_scheduler.schedule(cmd);
@@ -327,7 +329,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void doesNotRunOnCancelWhenCompleting() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd");
m_scheduler.schedule(cmd);
m_scheduler.run();
@@ -341,7 +343,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void runsOnCancelWhenCanceling() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd");
m_scheduler.schedule(cmd);
m_scheduler.run();
@@ -354,7 +356,7 @@ class SchedulerCancellationTests extends CommandTestBase {
void runsOnCancelWhenCancelingParent() {
var ran = new AtomicBoolean(false);
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var cmd = mechanism.run(Coroutine::yield).whenCanceled(() -> ran.set(true)).named("cmd");
var group = new SequentialGroup("Seq", Collections.singletonList(cmd));
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerConflictTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerConflictTests.java
index 1bdbd22f03..e8e11f8e3d 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerConflictTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerConflictTests.java
@@ -17,7 +17,7 @@ import org.junit.jupiter.api.Test;
class SchedulerConflictTests extends CommandTestBase {
@Test
void compositionsCannotAwaitConflictingCommands() {
- var mech = new Mechanism("The Mechanism", m_scheduler);
+ var mech = new DummyMechanism("The Mechanism", m_scheduler);
var group =
Command.noRequirements(
@@ -40,7 +40,7 @@ class SchedulerConflictTests extends CommandTestBase {
@Test
void innerCommandMayInterruptOtherInnerCommand() {
- var mechanism = new Mechanism("The mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("The mechanism", m_scheduler);
var firstRan = new AtomicBoolean(false);
var secondRan = new AtomicBoolean(false);
@@ -118,7 +118,7 @@ class SchedulerConflictTests extends CommandTestBase {
@Test
void childConflictsWithHigherPriorityTopLevel() {
- var mechanism = new Mechanism("mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("mechanism", m_scheduler);
var top = mechanism.run(Coroutine::park).withPriority(10).named("Top");
// Child conflicts with and is lower priority than the Top command
@@ -137,7 +137,7 @@ class SchedulerConflictTests extends CommandTestBase {
@Test
void childConflictsWithLowerPriorityTopLevel() {
- var mechanism = new Mechanism("mechanism", m_scheduler);
+ var mechanism = new DummyMechanism("mechanism", m_scheduler);
var top = mechanism.run(Coroutine::park).withPriority(-10).named("Top");
// Child conflicts with and is higher priority than the Top command
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerDefaultCommandTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerDefaultCommandTests.java
index 1522603938..45a5e141c5 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerDefaultCommandTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerDefaultCommandTests.java
@@ -14,7 +14,7 @@ import org.junit.jupiter.api.Test;
class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void globalDefaultCommandIsAlwaysUsed() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var defaultCommand = mech.run(Coroutine::park).named("Custom Default Command");
mech.setDefaultCommand(defaultCommand);
@@ -34,7 +34,7 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void defaultCommandSetInOpmodeStops() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var initialDefaultCommand = mech.idle();
mech.setDefaultCommand(initialDefaultCommand);
@@ -57,7 +57,7 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void defaultCommandSetInCommandStops() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var initialDefaultCommand = mech.idle();
mech.setDefaultCommand(initialDefaultCommand);
@@ -86,7 +86,7 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void interruptingDefaultCommandInterruptsOwner() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var initialDefaultCommand = mech.idle();
mech.setDefaultCommand(initialDefaultCommand);
@@ -116,7 +116,7 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void defaultCommandStackup() {
- var mech = new Mechanism("Mech", m_scheduler);
+ var mech = new DummyMechanism("Mech", m_scheduler);
var initialDefaultCommand = mech.idle();
mech.setDefaultCommand(initialDefaultCommand);
@@ -168,7 +168,7 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
@Test
void defaultCommandChangingDefaultCommand() {
var mech =
- new Mechanism("Mech", m_scheduler) {
+ new DummyMechanism("Mech", m_scheduler) {
Command makeCommand1() {
return run(co -> {
setDefaultCommand(makeCommand2());
@@ -204,12 +204,12 @@ class SchedulerDefaultCommandTests extends CommandTestBase {
// we'd have 1 binding object per loop and quickly use a ton of memory
var defaultCommandBindings = m_scheduler.getDefaultCommandBindingsFor(mech);
assertEquals(
- List.of("Mech[IDLE]", "Command 1", "Command 2", "Command 1"),
+ List.of("Command 1", "Command 2", "Command 1"),
defaultCommandBindings.stream().map(b -> b.command().name()).toList());
m_scheduler.run();
assertEquals(
- List.of("Mech[IDLE]", "Command 1", "Command 2"),
+ List.of("Command 1", "Command 2"),
defaultCommandBindings.stream().map(b -> b.command().name()).toList());
}
}
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerErrorHandlingTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerErrorHandlingTests.java
index 1cc7ab6745..0835292b9d 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerErrorHandlingTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerErrorHandlingTests.java
@@ -15,7 +15,7 @@ import org.junit.jupiter.api.Test;
class SchedulerErrorHandlingTests extends CommandTestBase {
@Test
void errorDetection() {
- var mechanism = new Mechanism("X", m_scheduler);
+ var mechanism = new DummyMechanism("X", m_scheduler);
var command =
mechanism
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerPriorityLevelTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerPriorityLevelTests.java
index d9f1c1967a..2cb181128c 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerPriorityLevelTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerPriorityLevelTests.java
@@ -12,7 +12,7 @@ import org.junit.jupiter.api.Test;
class SchedulerPriorityLevelTests extends CommandTestBase {
@Test
void higherPriorityCancels() {
- final var subsystem = new Mechanism("Subsystem", m_scheduler);
+ final var subsystem = new DummyMechanism("Subsystem", m_scheduler);
final var lower = new PriorityCommand(-1000, subsystem);
final var higher = new PriorityCommand(+1000, subsystem);
@@ -29,7 +29,7 @@ class SchedulerPriorityLevelTests extends CommandTestBase {
@Test
void lowerPriorityDoesNotCancel() {
- final var subsystem = new Mechanism("Subsystem", m_scheduler);
+ final var subsystem = new DummyMechanism("Subsystem", m_scheduler);
final var lower = new PriorityCommand(-1000, subsystem);
final var higher = new PriorityCommand(+1000, subsystem);
@@ -47,7 +47,7 @@ class SchedulerPriorityLevelTests extends CommandTestBase {
@Test
void samePriorityCancels() {
- final var subsystem = new Mechanism("Subsystem", m_scheduler);
+ final var subsystem = new DummyMechanism("Subsystem", m_scheduler);
final var first = new PriorityCommand(512, subsystem);
final var second = new PriorityCommand(512, subsystem);
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerTelemetryTests.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerTelemetryTests.java
index aa370ba5c7..5b2c20aae6 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerTelemetryTests.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerTelemetryTests.java
@@ -11,7 +11,7 @@ import org.junit.jupiter.api.Test;
class SchedulerTelemetryTests extends CommandTestBase {
@Test
void protobuf() {
- var mech = new Mechanism("The mechanism", m_scheduler);
+ var mech = new DummyMechanism("The mechanism", m_scheduler);
var parkCommand = mech.run(Coroutine::park).named("Park");
var c3Command = mech.run(co -> co.await(parkCommand)).named("C3");
var c2Command = mech.run(co -> co.await(c3Command)).named("C2");
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/command3/SchedulerTest.java
index 5e222073a8..d69ea156ae 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SchedulerTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SchedulerTest.java
@@ -44,7 +44,7 @@ class SchedulerTest extends CommandTestBase {
@SuppressWarnings("PMD.ImmutableField") // PMD bugs
void atomicity() {
var mechanism =
- new Mechanism("X", m_scheduler) {
+ new DummyMechanism("X", m_scheduler) {
int m_x = 0;
};
@@ -80,7 +80,7 @@ class SchedulerTest extends CommandTestBase {
@SuppressWarnings("PMD.ImmutableField") // PMD bugs
void runMechanism() {
var example =
- new Mechanism("Counting", m_scheduler) {
+ new DummyMechanism("Counting", m_scheduler) {
int m_x = 0;
};
@@ -107,8 +107,8 @@ class SchedulerTest extends CommandTestBase {
@Test
void compositionsDoNotNeedRequirements() {
- var m1 = new Mechanism("M1", m_scheduler);
- var m2 = new Mechanism("m2", m_scheduler);
+ var m1 = new DummyMechanism("M1", m_scheduler);
+ var m2 = new DummyMechanism("m2", m_scheduler);
// the group has no requirements, but can schedule child commands that do
var group =
@@ -128,9 +128,15 @@ class SchedulerTest extends CommandTestBase {
@Test
void nestedMechanisms() {
var superstructure =
- new Mechanism("Superstructure", m_scheduler) {
- private final Mechanism m_elevator = new Mechanism("Elevator", m_scheduler);
- private final Mechanism m_arm = new Mechanism("Arm", m_scheduler);
+ new DummyMechanism("Superstructure", m_scheduler) {
+ private final Mechanism m_elevator = new DummyMechanism("Elevator", m_scheduler);
+ private final Mechanism m_arm = new DummyMechanism("Arm", m_scheduler);
+
+ {
+ m_arm.setDefaultCommand(m_arm.idle());
+ m_elevator.setDefaultCommand(m_elevator.idle());
+ setDefaultCommand(this.idle());
+ }
public Command superCommand() {
return run(co -> {
diff --git a/commandsv3/src/test/java/org/wpilib/command3/SequentialGroupTest.java b/commandsv3/src/test/java/org/wpilib/command3/SequentialGroupTest.java
index 16f0bb6d02..63ee3e130f 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/SequentialGroupTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/SequentialGroupTest.java
@@ -62,8 +62,8 @@ class SequentialGroupTest extends CommandTestBase {
@Test
void inheritsRequirements() {
- var mech1 = new Mechanism("Mech 1", m_scheduler);
- var mech2 = new Mechanism("Mech 2", m_scheduler);
+ var mech1 = new DummyMechanism("Mech 1", m_scheduler);
+ var mech2 = new DummyMechanism("Mech 2", m_scheduler);
var command1 = mech1.run(Coroutine::park).named("Command 1");
var command2 = mech2.run(Coroutine::park).named("Command 2");
var sequence = new SequentialGroup("Sequence", List.of(command1, command2));
@@ -72,8 +72,8 @@ class SequentialGroupTest extends CommandTestBase {
@Test
void inheritsPriority() {
- var mech1 = new Mechanism("Mech 1", m_scheduler);
- var mech2 = new Mechanism("Mech 2", m_scheduler);
+ var mech1 = new DummyMechanism("Mech 1", m_scheduler);
+ var mech2 = new DummyMechanism("Mech 2", m_scheduler);
var command1 = mech1.run(Coroutine::park).withPriority(100).named("Command 1");
var command2 = mech2.run(Coroutine::park).withPriority(200).named("Command 2");
var sequence = new SequentialGroup("Sequence", List.of(command1, command2));
diff --git a/commandsv3/src/test/java/org/wpilib/command3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/command3/StagedCommandBuilderTest.java
index 5c9919fbb4..a3c373fb5d 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/StagedCommandBuilderTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/StagedCommandBuilderTest.java
@@ -24,8 +24,8 @@ class StagedCommandBuilderTest {
@BeforeEach
void setUp() {
Scheduler scheduler = Scheduler.createIndependentScheduler();
- m_mech1 = new Mechanism("Mech 1", scheduler);
- m_mech2 = new Mechanism("Mech 2", scheduler);
+ m_mech1 = new DummyMechanism("Mech 1", scheduler);
+ m_mech2 = new DummyMechanism("Mech 2", scheduler);
}
// The next two tests are to check that various forms of builder usage are able to compile.
@@ -44,7 +44,7 @@ class StagedCommandBuilderTest {
@Test
void allOptions() {
- var mech = new Mechanism("Mech", Scheduler.createIndependentScheduler());
+ var mech = new DummyMechanism("Mech", Scheduler.createIndependentScheduler());
Command command =
new StagedCommandBuilder()
diff --git a/commandsv3/src/test/java/org/wpilib/command3/StateMachineTest.java b/commandsv3/src/test/java/org/wpilib/command3/StateMachineTest.java
index fcb09277fb..0ec7485391 100644
--- a/commandsv3/src/test/java/org/wpilib/command3/StateMachineTest.java
+++ b/commandsv3/src/test/java/org/wpilib/command3/StateMachineTest.java
@@ -26,7 +26,7 @@ class StateMachineTest extends CommandTestBase {
@Test
@SuppressWarnings(PostConstructionInitializer.SUPPRESSION_KEY)
void errorsWithoutInitialState() {
- Mechanism mech = new Mechanism("Mechanism", m_scheduler);
+ Mechanism mech = new DummyMechanism("Mechanism", m_scheduler);
Command command1 = mech.run(Coroutine::park).named("Command 1");
Command command2 = mech.run(Coroutine::park).named("Command 2");
@@ -49,7 +49,7 @@ class StateMachineTest extends CommandTestBase {
@Test
void initialStateCanBeOverridden() {
- Mechanism mech = new Mechanism("Mechanism", m_scheduler);
+ Mechanism mech = new DummyMechanism("Mechanism", m_scheduler);
Command command1 = mech.run(Coroutine::park).named("Command 1");
Command command2 = mech.run(Coroutine::park).named("Command 2");
@@ -72,7 +72,7 @@ class StateMachineTest extends CommandTestBase {
AtomicBoolean signalA = new AtomicBoolean(false);
AtomicBoolean signalB = new AtomicBoolean(false);
- Mechanism mech = new Mechanism("Mechanism", m_scheduler);
+ Mechanism mech = new DummyMechanism("Mechanism", m_scheduler);
var command1 = mech.run(Coroutine::park).named("Command 1");
var command2 = mech.run(Coroutine::park).named("Command 2");
var command3 = mech.run(Coroutine::park).named("Command 3");
@@ -565,7 +565,7 @@ class StateMachineTest extends CommandTestBase {
@Test
void onExitCanSchedule() {
- var mech = new Mechanism("Mechanism", m_scheduler);
+ var mech = new DummyMechanism("Mechanism", m_scheduler);
var mainMechCommand = mech.run(Coroutine::park).named("Main Mech Command");
var backgroundMechCommand = mech.run(Coroutine::park).named("Background Mech Command");
var nextStateCommand = Command.noRequirements(Coroutine::park).named("Next");
@@ -697,7 +697,7 @@ class StateMachineTest extends CommandTestBase {
@Test
void ledStateMachine() {
var leds =
- new Mechanism("LEDs", m_scheduler) {
+ new DummyMechanism("LEDs", m_scheduler) {
Command idleAnimation() {
return run(Coroutine::park).withPriority(-1).named("Default Animation");
}
diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/DriveSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/DriveSubsystem.java
index d8056e96d5..71075e06f9 100644
--- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/DriveSubsystem.java
+++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/DriveSubsystem.java
@@ -11,7 +11,7 @@ import org.wpilib.hardware.motor.PWMSparkMax;
import org.wpilib.hardware.rotation.Encoder;
import org.wpilib.util.sendable.SendableRegistry;
-public class DriveSubsystem extends Mechanism {
+public class DriveSubsystem implements Mechanism {
// The motors on the left side of the drive.
private final PWMSparkMax leftLeader = new PWMSparkMax(DriveConstants.kLeftMotor1Port);
private final PWMSparkMax leftFollower = new PWMSparkMax(DriveConstants.kLeftMotor2Port);
diff --git a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/HatchSubsystem.java b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/HatchSubsystem.java
index 3790748d22..14116b6e56 100644
--- a/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/HatchSubsystem.java
+++ b/wpilibjExamples/src/main/java/org/wpilib/examples/hatchbotcmdv3/subsystems/HatchSubsystem.java
@@ -14,7 +14,7 @@ import org.wpilib.hardware.pneumatic.DoubleSolenoid;
import org.wpilib.hardware.pneumatic.PneumaticsModuleType;
/** A hatch mechanism actuated by a single {@link org.wpilib.hardware.pneumatic.DoubleSolenoid}. */
-public class HatchSubsystem extends Mechanism {
+public class HatchSubsystem implements Mechanism {
private final DoubleSolenoid hatchSolenoid =
new DoubleSolenoid(
0,