diff --git a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
index 4d8e41ac4c3..bbbde1eca00 100644
--- a/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
+++ b/commandsv3/src/main/java/org/wpilib/commands3/Mechanism.java
@@ -10,61 +10,36 @@
import org.wpilib.annotation.NoDiscard;
/**
- * 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
+ *
Unlike the Subsystem interface of commands v2, Mechanism does not need to be explicitly
+ * registered in the constructor.
+ *
+ *
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;
-
- /**
- * 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());
- }
-
+public interface Mechanism {
/**
- * 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 +54,8 @@ public String getName() {
*
* @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 +64,8 @@ public void setDefaultCommand(Command defaultCommand) {
*
* @return The currently configured default command
*/
- public Command getDefaultCommand() {
- return m_registeredScheduler.getDefaultCommandFor(this);
+ default Command getDefaultCommand() {
+ return getRegisteredScheduler().getDefaultCommandFor(this);
}
/**
@@ -99,7 +74,7 @@ public Command getDefaultCommand() {
* @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 +86,7 @@ public NeedsNameBuilderStage run(Consumer commandBody) {
* @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 +106,7 @@ public NeedsNameBuilderStage runRepeatedly(Runnable loopBody) {
*
* @return A new idle command.
*/
- public Command idle() {
+ default Command idle() {
return run(Coroutine::park).withPriority(Command.LOWEST_PRIORITY).named(getName() + "[IDLE]");
}
@@ -141,7 +116,7 @@ public Command idle() {
* @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 +129,7 @@ public Command idleFor(Time duration) {
* @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/commands3/ConflictDetectorTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java
index ae1e5ef8627..e0319e3ee14 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/ConflictDetectorTest.java
@@ -23,7 +23,7 @@ void emptyInputHasNoConflicts() {
@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 @@ void singleInputHasNoConflicts() {
@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 @@ void commandDoesNotConflictWithSelf() {
@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/commands3/DummyMechanism.java b/commandsv3/src/test/java/org/wpilib/commands3/DummyMechanism.java
new file mode 100644
index 00000000000..49699e8a7a8
--- /dev/null
+++ b/commandsv3/src/test/java/org/wpilib/commands3/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.commands3;
+
+/** 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/commands3/ParallelGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
index f89bd647f0d..8598c71ce35 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/ParallelGroupTest.java
@@ -16,8 +16,8 @@
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 @@ void parallelAll() {
@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 @@ void race() {
@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 @@ void automaticNameDeadline() {
@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 @@ void inheritsRequirements() {
@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/commands3/SchedulerCancellationTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java
index 90d2dfffef9..4334fd58f84 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerCancellationTests.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/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 @@ void cancelOnInterruptDoesNotResume() {
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(
@@ -169,7 +169,9 @@ void cancelAllDoesNotCallOnCancelHookForQueuedCommands() {
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");
@@ -237,7 +239,7 @@ void cancelDeeplyNestedCompositions() {
@Test
void compositionsDoNotSelfCancel() {
- var mech = new Mechanism("The mechanism", m_scheduler);
+ var mech = new DummyMechanism("The mechanism", m_scheduler);
var group =
mech.run(
co -> {
@@ -263,7 +265,7 @@ void compositionsDoNotSelfCancel() {
@Test
void compositionsDoNotCancelParent() {
- var mech = new Mechanism("The mechanism", m_scheduler);
+ var mech = new DummyMechanism("The mechanism", m_scheduler);
var group =
mech.run(
co -> {
@@ -286,7 +288,7 @@ void compositionsDoNotCancelParent() {
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);
@@ -300,7 +302,7 @@ void doesNotRunOnCancelWhenInterruptingOnDeck() {
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()
@@ -314,7 +316,7 @@ void doesNotRunOnCancelWhenCancelingOnDeck() {
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);
@@ -329,7 +331,7 @@ void runsOnCancelWhenInterruptingCommand() {
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();
@@ -343,7 +345,7 @@ void doesNotRunOnCancelWhenCompleting() {
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();
@@ -356,7 +358,7 @@ void runsOnCancelWhenCanceling() {
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/commands3/SchedulerConflictTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java
index a4823fea4d0..3b216cae7c5 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerConflictTests.java
@@ -17,7 +17,7 @@
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()
@@ -41,7 +41,7 @@ void compositionsCannotAwaitConflictingCommands() {
@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);
@@ -124,7 +124,7 @@ void nestedOneShotCompositionsAllRunInOneCycle() {
@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
@@ -143,7 +143,7 @@ void childConflictsWithHigherPriorityTopLevel() {
@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/commands3/SchedulerErrorHandlingTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java
index 758639dc420..6d9bc0e6da0 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerErrorHandlingTests.java
@@ -15,7 +15,7 @@
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/commands3/SchedulerPriorityLevelTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java
index 3e65aa81632..a5fe62c5d40 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerPriorityLevelTests.java
@@ -12,7 +12,7 @@
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 @@ void higherPriorityCancels() {
@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 @@ void lowerPriorityDoesNotCancel() {
@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/commands3/SchedulerTelemetryTests.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java
index 9c7f07bff4f..be4c452c185 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTelemetryTests.java
@@ -11,7 +11,7 @@
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/commands3/SchedulerTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
index 4d5fd92a7b8..9fd5ea909e0 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SchedulerTest.java
@@ -45,7 +45,7 @@ void basic() {
@SuppressWarnings("PMD.ImmutableField") // PMD bugs
void atomicity() {
var mechanism =
- new Mechanism("X", m_scheduler) {
+ new DummyMechanism("X", m_scheduler) {
int m_x = 0;
};
@@ -82,7 +82,7 @@ void atomicity() {
@SuppressWarnings("PMD.ImmutableField") // PMD bugs
void runMechanism() {
var example =
- new Mechanism("Counting", m_scheduler) {
+ new DummyMechanism("Counting", m_scheduler) {
int m_x = 0;
};
@@ -109,8 +109,8 @@ void runMechanism() {
@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 =
@@ -131,9 +131,15 @@ void compositionsDoNotNeedRequirements() {
@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/commands3/SequentialGroupTest.java b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java
index 4481ee8181f..f45357675fb 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/SequentialGroupTest.java
@@ -62,8 +62,8 @@ void twoCommands() {
@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 @@ void inheritsRequirements() {
@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/commands3/StagedCommandBuilderTest.java b/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java
index 44fef542a89..aa68a590e9b 100644
--- a/commandsv3/src/test/java/org/wpilib/commands3/StagedCommandBuilderTest.java
+++ b/commandsv3/src/test/java/org/wpilib/commands3/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 @@ void streamlined() {
@Test
void allOptions() {
- var mech = new Mechanism("Mech", Scheduler.createIndependentScheduler());
+ var mech = new DummyMechanism("Mech", Scheduler.createIndependentScheduler());
Command command =
new StagedCommandBuilder()