diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java index 4d9ad2c06f9..704c690f5f1 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandDecoratorTest.java @@ -23,7 +23,7 @@ void withTimeoutTest() { HAL.initialize(500, 0); SimHooks.pauseTiming(); try (CommandScheduler scheduler = new CommandScheduler()) { - Command timeout = new RunCommand(() -> {}).withTimeout(0.1); + Command timeout = Commands.idle().withTimeout(0.1); scheduler.schedule(timeout); scheduler.run(); @@ -44,7 +44,7 @@ void untilTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean finish = new AtomicBoolean(); - Command command = new RunCommand(() -> {}).until(finish::get); + Command command = Commands.idle().until(finish::get); scheduler.schedule(command); scheduler.run(); @@ -93,7 +93,7 @@ void onlyWhileTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean run = new AtomicBoolean(true); - Command command = new RunCommand(() -> {}).onlyWhile(run::get); + Command command = Commands.idle().onlyWhile(run::get); scheduler.schedule(command); scheduler.run(); @@ -140,7 +140,7 @@ void onlyWhileOrderTest() { @Test void ignoringDisableTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - var command = new RunCommand(() -> {}).ignoringDisable(true); + var command = Commands.idle().ignoringDisable(true); setDSEnabled(false); @@ -157,7 +157,7 @@ void beforeStartingTest() { AtomicBoolean finished = new AtomicBoolean(); finished.set(false); - Command command = new InstantCommand().beforeStarting(() -> finished.set(true)); + Command command = Commands.none().beforeStarting(() -> finished.set(true)); scheduler.schedule(command); @@ -178,7 +178,7 @@ void andThenLambdaTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean finished = new AtomicBoolean(false); - Command command = new InstantCommand().andThen(() -> finished.set(true)); + Command command = Commands.none().andThen(() -> finished.set(true)); scheduler.schedule(command); @@ -199,8 +199,8 @@ void andThenTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean condition = new AtomicBoolean(false); - Command command1 = new InstantCommand(); - Command command2 = new InstantCommand(() -> condition.set(true)); + Command command1 = Commands.none(); + Command command2 = Commands.runOnce(() -> condition.set(true)); Command group = command1.andThen(command2); scheduler.schedule(group); @@ -222,9 +222,9 @@ void deadlineForTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean finish = new AtomicBoolean(false); - Command dictator = new WaitUntilCommand(finish::get); - Command endsBefore = new InstantCommand(); - Command endsAfter = new WaitUntilCommand(() -> false); + Command dictator = Commands.waitUntil(finish::get); + Command endsBefore = Commands.none(); + Command endsAfter = Commands.idle(); Command group = dictator.deadlineFor(endsBefore, endsAfter); @@ -256,7 +256,7 @@ void deadlineForOrderTest() { return true; }); Command other = - new RunCommand( + Commands.run( () -> assertAll( () -> assertTrue(dictatorHasRun.get()), @@ -327,8 +327,8 @@ void alongWithTest() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicBoolean finish = new AtomicBoolean(false); - Command command1 = new WaitUntilCommand(finish::get); - Command command2 = new InstantCommand(); + Command command1 = Commands.waitUntil(finish::get); + Command command2 = Commands.none(); Command group = command1.alongWith(command2); @@ -360,7 +360,7 @@ void alongWithOrderTest() { return true; }); Command command2 = - new RunCommand( + Commands.run( () -> assertAll( () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get()))); @@ -377,8 +377,8 @@ void alongWithOrderTest() { @Test void raceWithTest() { try (CommandScheduler scheduler = new CommandScheduler()) { - Command command1 = new WaitUntilCommand(() -> false); - Command command2 = new InstantCommand(); + Command command1 = Commands.idle(); + Command command2 = Commands.none(); Command group = command1.raceWith(command2); @@ -405,7 +405,7 @@ void raceWithOrderTest() { return true; }); Command command2 = - new RunCommand( + Commands.run( () -> { assertTrue(firstHasRun.get()); assertTrue(firstWasPolled.get()); @@ -426,7 +426,7 @@ void unlessTest() { AtomicBoolean hasRun = new AtomicBoolean(false); AtomicBoolean unlessCondition = new AtomicBoolean(true); - Command command = new InstantCommand(() -> hasRun.set(true)).unless(unlessCondition::get); + Command command = Commands.runOnce(() -> hasRun.set(true)).unless(unlessCondition::get); scheduler.schedule(command); scheduler.run(); @@ -445,7 +445,7 @@ void onlyIfTest() { AtomicBoolean hasRun = new AtomicBoolean(false); AtomicBoolean onlyIfCondition = new AtomicBoolean(false); - Command command = new InstantCommand(() -> hasRun.set(true)).onlyIf(onlyIfCondition::get); + Command command = Commands.runOnce(() -> hasRun.set(true)).onlyIf(onlyIfCondition::get); scheduler.schedule(command); scheduler.run(); @@ -531,7 +531,7 @@ void handleInterruptTest() { @Test void withNameTest() { - InstantCommand command = new InstantCommand(); + Command command = Commands.none(); String name = "Named"; Command named = command.withName(name); assertEquals(name, named.getName()); 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..45f017c3880 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 @@ -45,7 +45,7 @@ void requirementUninterruptibleTest() { Subsystem requirement = new SubsystemBase() {}; Command notInterrupted = - new RunCommand(() -> {}, requirement) + Commands.idle(requirement) .withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming); MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement); Command interrupter = interrupterHolder.getMock(); @@ -63,7 +63,7 @@ void defaultCommandRequirementErrorTest() { try (CommandScheduler scheduler = new CommandScheduler()) { Subsystem system = new SubsystemBase() {}; - Command missingRequirement = new WaitUntilCommand(() -> false); + Command missingRequirement = Commands.idle(); assertThrows( IllegalArgumentException.class, 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..7b9817f5645 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 @@ -74,34 +74,26 @@ static Stream interruptible() { arguments( "AllCancelSelf", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), (BooleanSupplier) () -> true), arguments( "AllCancelIncoming", InterruptionBehavior.kCancelIncoming, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), (BooleanSupplier) () -> true), arguments( "OneCancelSelfOneIncoming", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), (BooleanSupplier) () -> true), arguments( "OneCancelIncomingOneSelf", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), (BooleanSupplier) () -> true)); } @@ -122,26 +114,26 @@ static Stream runsWhenDisabled() { arguments( "AllFalse", false, - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(false), + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(false), (BooleanSupplier) () -> true), arguments( "AllTrue", true, - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(true), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(true), (BooleanSupplier) () -> true), arguments( "OneTrueOneFalse", false, - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(false), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(false), (BooleanSupplier) () -> true), arguments( "OneFalseOneTrue", false, - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(true), + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(true), (BooleanSupplier) () -> true)); } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java index 9fafc5905c3..1b0e8e91419 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/MultiCompositionTestBase.java @@ -27,39 +27,27 @@ static Stream interruptible() { arguments( "AllCancelSelf", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf)), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf)), arguments( "AllCancelIncoming", InterruptionBehavior.kCancelIncoming, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming)), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming)), arguments( "TwoCancelSelfOneIncoming", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming)), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming)), arguments( "TwoCancelIncomingOneSelf", InterruptionBehavior.kCancelSelf, - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelIncoming), - new WaitUntilCommand(() -> false) - .withInterruptBehavior(InterruptionBehavior.kCancelSelf))); + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming), + Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf))); } @MethodSource @@ -79,27 +67,27 @@ static Stream runsWhenDisabled() { arguments( "AllFalse", false, - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(false)), + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(false)), arguments( "AllTrue", true, - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(true)), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(true)), arguments( "TwoTrueOneFalse", false, - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(true), - new WaitUntilCommand(() -> false).ignoringDisable(false)), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(true), + Commands.idle().ignoringDisable(false)), arguments( "TwoFalseOneTrue", false, - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(false), - new WaitUntilCommand(() -> false).ignoringDisable(true))); + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(false), + Commands.idle().ignoringDisable(true))); } @MethodSource @@ -115,8 +103,8 @@ void runsWhenDisabled( } static Stream composeDuplicates() { - Command a = new InstantCommand(() -> {}); - Command b = new InstantCommand(() -> {}); + Command a = Commands.none(); + Command b = Commands.none(); return Stream.of( arguments("AA", new Command[] {a, a}), arguments("ABA", new Command[] {a, b, a}), 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..b3d7dfb5563 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 @@ -127,15 +127,15 @@ void parallelDeadlineRequirementErrorTest() { @Test void parallelDeadlineSetDeadlineToDeadlineTest() { - Command a = new InstantCommand(() -> {}); + Command a = Commands.none(); ParallelDeadlineGroup group = new ParallelDeadlineGroup(a); assertDoesNotThrow(() -> group.setDeadline(a)); } @Test void parallelDeadlineSetDeadlineDuplicateTest() { - Command a = new InstantCommand(() -> {}); - Command b = new InstantCommand(() -> {}); + Command a = Commands.none(); + Command b = Commands.none(); ParallelDeadlineGroup group = new ParallelDeadlineGroup(a, b); assertThrows(IllegalArgumentException.class, () -> group.setDeadline(b)); } 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..bd44a128b8c 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 @@ -140,7 +140,7 @@ void parallelRaceOnlyCallsEndOnceTest() { MockCommandHolder command3Holder = new MockCommandHolder(true); Command command3 = command3Holder.getMock(); - Command group1 = new SequentialCommandGroup(command1, command2); + Command group1 = Commands.sequence(command1, command2); assertNotNull(group1); assertNotNull(command3); Command group2 = new ParallelRaceGroup(group1, command3); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java index c4b43a609b7..2eae20bbc85 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ProxyCommandTest.java @@ -31,7 +31,7 @@ void proxyCommandEndTest() { try (CommandScheduler scheduler = CommandScheduler.getInstance()) { AtomicBoolean cond = new AtomicBoolean(); - WaitUntilCommand command = new WaitUntilCommand(cond::get); + Command command = Commands.waitUntil(cond::get); ProxyCommand scheduleCommand = new ProxyCommand(command); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java index 9014bc7b96e..875b2e5ea9b 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ScheduleCommandTest.java @@ -30,13 +30,12 @@ void scheduleCommandScheduleTest() { @Test void scheduleCommandDuringRunTest() { try (CommandScheduler scheduler = CommandScheduler.getInstance()) { - InstantCommand toSchedule = new InstantCommand(); + Command toSchedule = Commands.none(); ScheduleCommand scheduleCommand = new ScheduleCommand(toSchedule); - SequentialCommandGroup group = - new SequentialCommandGroup(new InstantCommand(), scheduleCommand); + Command group = Commands.sequence(Commands.none(), scheduleCommand); scheduler.schedule(group); - scheduler.schedule(new RunCommand(() -> {})); + scheduler.schedule(Commands.idle()); scheduler.run(); assertDoesNotThrow(scheduler::run); } 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..0a6eb3df5ca 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 @@ -23,7 +23,7 @@ void schedulerLambdaTestNoInterrupt() { scheduler.onCommandExecute(command -> counter.incrementAndGet()); scheduler.onCommandFinish(command -> counter.incrementAndGet()); - scheduler.schedule(new InstantCommand()); + scheduler.schedule(Commands.none()); scheduler.run(); assertEquals(counter.get(), 3); @@ -37,7 +37,7 @@ void schedulerInterruptLambdaTest() { scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); - Command command = new WaitCommand(10); + Command command = Commands.idle(); scheduler.schedule(command); scheduler.cancel(command); @@ -162,8 +162,8 @@ void schedulerCancelAllTest() { scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); scheduler.onCommandInterrupt((command, interruptor) -> assertFalse(interruptor.isPresent())); - Command command = new WaitCommand(10); - Command command2 = new WaitCommand(10); + Command command = Commands.idle(); + Command command2 = Commands.idle(); scheduler.schedule(command); scheduler.schedule(command2); 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..06f4023f6b8 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 @@ -48,7 +48,7 @@ public InterruptionBehavior getInterruptionBehavior() { return interruptionBehavior; } }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + Command other = requirement.run(() -> hasOtherRun.set(true)); assertDoesNotThrow( () -> { @@ -87,7 +87,7 @@ public InterruptionBehavior getInterruptionBehavior() { return interruptionBehavior; } }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + Command other = requirement.run(() -> hasOtherRun.set(true)); assertDoesNotThrow( () -> { @@ -132,7 +132,7 @@ public InterruptionBehavior getInterruptionBehavior() { return interruptionBehavior; } }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + Command other = requirement.run(() -> hasOtherRun.set(true)); scheduler.setDefaultCommand(requirement, other); assertDoesNotThrow( @@ -173,7 +173,7 @@ public void end(boolean interrupted) { void cancelFromInterruptAction() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); - Command selfCancels = new RunCommand(() -> {}); + Command selfCancels = Commands.idle(); scheduler.onCommandInterrupt( cmd -> { counter.incrementAndGet(); @@ -329,7 +329,7 @@ void scheduleFromEndCancel() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); Subsystem requirement = new SubsystemBase() {}; - InstantCommand other = new InstantCommand(() -> {}, requirement); + Command other = requirement.runOnce(() -> {}); FunctionalCommand selfCancels = new FunctionalCommand( () -> {}, @@ -354,7 +354,7 @@ void scheduleFromEndInterrupt() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); Subsystem requirement = new SubsystemBase() {}; - InstantCommand other = new InstantCommand(() -> {}, requirement); + Command other = requirement.runOnce(() -> {}); FunctionalCommand selfCancels = new FunctionalCommand( () -> {}, @@ -380,8 +380,8 @@ void scheduleFromEndInterruptAction() { try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); Subsystem requirement = new Subsystem() {}; - InstantCommand other = new InstantCommand(() -> {}, requirement); - InstantCommand selfCancels = new InstantCommand(() -> {}, requirement); + Command other = requirement.runOnce(() -> {}); + Command selfCancels = requirement.runOnce(() -> {}); scheduler.onCommandInterrupt( cmd -> { counter.incrementAndGet(); @@ -402,8 +402,7 @@ void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehav try (CommandScheduler scheduler = new CommandScheduler()) { AtomicInteger counter = new AtomicInteger(); Subsystem requirement = new SubsystemBase() {}; - Command other = - new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior); + Command other = requirement.runOnce(() -> {}).withInterruptBehavior(interruptionBehavior); FunctionalCommand defaultCommand = new FunctionalCommand( () -> { @@ -438,7 +437,7 @@ void cancelDefaultCommandFromEnd() { interrupted -> counter.incrementAndGet(), () -> false, requirement); - Command other = new InstantCommand(() -> {}, requirement); + Command other = requirement.runOnce(() -> {}); Command cancelDefaultCommand = 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..f6f551bd6e9 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 @@ -97,7 +97,7 @@ void selectCommandRequirementTest() { () -> "one"); scheduler.schedule(selectCommand); - scheduler.schedule(new InstantCommand(() -> {}, system3)); + scheduler.schedule(system3.runOnce(() -> {})); assertFalse(scheduler.isScheduled(selectCommand)); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java index a063a1de638..5f6fe9e8616 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SingleCompositionTestBase.java @@ -18,37 +18,34 @@ public abstract class SingleCompositionTestBase extends Comma @EnumSource(Command.InterruptionBehavior.class) @ParameterizedTest void interruptible(Command.InterruptionBehavior interruptionBehavior) { - var command = - composeSingle( - new WaitUntilCommand(() -> false).withInterruptBehavior(interruptionBehavior)); + var command = composeSingle(Commands.idle().withInterruptBehavior(interruptionBehavior)); assertEquals(interruptionBehavior, command.getInterruptionBehavior()); } @ValueSource(booleans = {true, false}) @ParameterizedTest void runWhenDisabled(boolean runsWhenDisabled) { - var command = - composeSingle(new WaitUntilCommand(() -> false).ignoringDisable(runsWhenDisabled)); + var command = composeSingle(Commands.idle().ignoringDisable(runsWhenDisabled)); assertEquals(runsWhenDisabled, command.runsWhenDisabled()); } @Test void commandInOtherCompositionTest() { - var command = new InstantCommand(); + var command = Commands.none(); new WrapperCommand(command) {}; assertThrows(IllegalArgumentException.class, () -> composeSingle(command)); } @Test void commandInMultipleCompositionsTest() { - var command = new InstantCommand(); + var command = Commands.none(); composeSingle(command); assertThrows(IllegalArgumentException.class, () -> composeSingle(command)); } @Test void composeThenScheduleTest() { - var command = new InstantCommand(); + var command = Commands.none(); composeSingle(command); assertThrows( IllegalArgumentException.class, () -> CommandScheduler.getInstance().schedule(command)); @@ -56,7 +53,7 @@ void composeThenScheduleTest() { @Test void scheduleThenComposeTest() { - var command = new RunCommand(() -> {}); + var command = Commands.idle(); CommandScheduler.getInstance().schedule(command); assertThrows(IllegalArgumentException.class, () -> composeSingle(command)); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp index a0b7726f5d6..a8e057761fe 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp @@ -8,6 +8,7 @@ #include #include "CommandTestBase.h" +#include "frc2/command/Commands.h" #include "frc2/command/FunctionalCommand.h" #include "frc2/command/InstantCommand.h" #include "frc2/command/RunCommand.h" @@ -21,7 +22,7 @@ TEST_F(CommandDecoratorTest, WithTimeout) { frc::sim::PauseTiming(); - auto command = RunCommand([] {}, {}).WithTimeout(100_ms); + auto command = cmd::Idle().WithTimeout(100_ms); scheduler.Schedule(command); scheduler.Run(); @@ -42,7 +43,7 @@ TEST_F(CommandDecoratorTest, Until) { bool finish = false; - auto command = RunCommand([] {}, {}).Until([&finish] { return finish; }); + auto command = cmd::Idle().Until([&finish] { return finish; }); scheduler.Schedule(command); scheduler.Run(); @@ -85,7 +86,7 @@ TEST_F(CommandDecoratorTest, OnlyWhile) { bool run = true; - auto command = RunCommand([] {}, {}).OnlyWhile([&run] { return run; }); + auto command = cmd::Idle().OnlyWhile([&run] { return run; }); scheduler.Schedule(command); scheduler.Run(); @@ -126,7 +127,7 @@ TEST_F(CommandDecoratorTest, OnlyWhileOrder) { TEST_F(CommandDecoratorTest, IgnoringDisable) { CommandScheduler scheduler = GetScheduler(); - auto command = RunCommand([] {}, {}).IgnoringDisable(true); + auto command = cmd::Idle().IgnoringDisable(true); SetDSEnabled(false); @@ -141,8 +142,7 @@ TEST_F(CommandDecoratorTest, BeforeStarting) { bool finished = false; - auto command = InstantCommand([] {}, {}).BeforeStarting( - [&finished] { finished = true; }); + auto command = cmd::None().BeforeStarting([&finished] { finished = true; }); scheduler.Schedule(command); @@ -162,8 +162,7 @@ TEST_F(CommandDecoratorTest, AndThenLambda) { bool finished = false; - auto command = - InstantCommand([] {}, {}).AndThen([&finished] { finished = true; }); + auto command = cmd::None().AndThen([&finished] { finished = true; }); scheduler.Schedule(command); @@ -183,9 +182,9 @@ TEST_F(CommandDecoratorTest, AndThen) { bool finished = false; - auto command1 = InstantCommand(); - auto command2 = InstantCommand([&finished] { finished = true; }); - auto group = std::move(command1).AndThen(std::move(command2).ToPtr()); + auto command1 = cmd::None(); + auto command2 = cmd::RunOnce([&finished] { finished = true; }); + auto group = std::move(command1).AndThen(std::move(command2)); scheduler.Schedule(group); @@ -205,10 +204,10 @@ TEST_F(CommandDecoratorTest, DeadlineFor) { bool finish = false; - auto dictator = WaitUntilCommand([&finish] { return finish; }); - auto endsAfter = WaitUntilCommand([] { return false; }); + auto dictator = cmd::WaitUntil([&finish] { return finish; }); + auto endsAfter = cmd::Idle(); - auto group = std::move(dictator).DeadlineFor(std::move(endsAfter).ToPtr()); + auto group = std::move(dictator).DeadlineFor(std::move(endsAfter)); scheduler.Schedule(group); scheduler.Run(); @@ -247,10 +246,10 @@ TEST_F(CommandDecoratorTest, AlongWith) { bool finish = false; - auto command1 = WaitUntilCommand([&finish] { return finish; }); - auto command2 = InstantCommand(); + auto command1 = cmd::WaitUntil([&finish] { return finish; }); + auto command2 = cmd::None(); - auto group = std::move(command1).AlongWith(std::move(command2).ToPtr()); + auto group = std::move(command1).AlongWith(std::move(command2)); scheduler.Schedule(group); scheduler.Run(); @@ -266,10 +265,10 @@ TEST_F(CommandDecoratorTest, AlongWith) { TEST_F(CommandDecoratorTest, RaceWith) { CommandScheduler scheduler = GetScheduler(); - auto command1 = WaitUntilCommand([] { return false; }); - auto command2 = InstantCommand(); + auto command1 = cmd::Idle(); + auto command2 = cmd::None(); - auto group = std::move(command1).RaceWith(std::move(command2).ToPtr()); + auto group = std::move(command1).RaceWith(std::move(command2)); scheduler.Schedule(group); scheduler.Run(); @@ -290,12 +289,12 @@ TEST_F(CommandDecoratorTest, DeadlineForOrder) { dictatorWasPolled = true; return true; }); - auto other = RunCommand([&dictatorHasRun, &dictatorWasPolled] { + auto other = cmd::Run([&dictatorHasRun, &dictatorWasPolled] { EXPECT_TRUE(dictatorHasRun); EXPECT_TRUE(dictatorWasPolled); }); - auto group = std::move(dictator).DeadlineFor(std::move(other).ToPtr()); + auto group = std::move(dictator).DeadlineFor(std::move(other)); scheduler.Schedule(group); scheduler.Run(); @@ -343,12 +342,12 @@ TEST_F(CommandDecoratorTest, AlongWithOrder) { firstWasPolled = true; return true; }); - auto command2 = RunCommand([&firstHasRun, &firstWasPolled] { + auto command2 = cmd::Run([&firstHasRun, &firstWasPolled] { EXPECT_TRUE(firstHasRun); EXPECT_TRUE(firstWasPolled); }); - auto group = std::move(command1).AlongWith(std::move(command2).ToPtr()); + auto group = std::move(command1).AlongWith(std::move(command2)); scheduler.Schedule(group); scheduler.Run(); @@ -369,12 +368,12 @@ TEST_F(CommandDecoratorTest, RaceWithOrder) { firstWasPolled = true; return true; }); - auto command2 = RunCommand([&firstHasRun, &firstWasPolled] { + auto command2 = cmd::Run([&firstHasRun, &firstWasPolled] { EXPECT_TRUE(firstHasRun); EXPECT_TRUE(firstWasPolled); }); - auto group = std::move(command1).RaceWith(std::move(command2).ToPtr()); + auto group = std::move(command1).RaceWith(std::move(command2)); scheduler.Schedule(group); scheduler.Run(); @@ -389,8 +388,10 @@ TEST_F(CommandDecoratorTest, Unless) { bool hasRun = false; bool unlessCondition = true; - auto command = InstantCommand([&hasRun] { hasRun = true; }, {}) - .Unless([&unlessCondition] { return unlessCondition; }); + auto command = + cmd::RunOnce([&hasRun] { hasRun = true; }, {}).Unless([&unlessCondition] { + return unlessCondition; + }); scheduler.Schedule(command); scheduler.Run(); @@ -408,8 +409,10 @@ TEST_F(CommandDecoratorTest, OnlyIf) { bool hasRun = false; bool onlyIfCondition = false; - auto command = InstantCommand([&hasRun] { hasRun = true; }, {}) - .OnlyIf([&onlyIfCondition] { return onlyIfCondition; }); + auto command = + cmd::RunOnce([&hasRun] { hasRun = true; }, {}).OnlyIf([&onlyIfCondition] { + return onlyIfCondition; + }); scheduler.Schedule(command); scheduler.Run(); @@ -481,8 +484,8 @@ TEST_F(CommandDecoratorTest, HandleInterrupt) { } TEST_F(CommandDecoratorTest, WithName) { - InstantCommand command; + auto command = cmd::None(); std::string name{"Named"}; - CommandPtr named = std::move(command).WithName(name); + auto named = std::move(command).WithName(name); EXPECT_EQ(name, named.get()->GetName()); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h b/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h index 58fbcc393b3..4a641180fb9 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CompositionTestBase.h @@ -23,15 +23,13 @@ TYPED_TEST_SUITE_P(SingleCompositionRunsWhenDisabledTest); TYPED_TEST_P(SingleCompositionRunsWhenDisabledTest, True) { auto param = true; - TypeParam command = TypeParam( - cmd::WaitUntil([] { return false; }).IgnoringDisable(param).Unwrap()); + TypeParam command = TypeParam(cmd::Idle().IgnoringDisable(param).Unwrap()); EXPECT_EQ(param, command.RunsWhenDisabled()); } TYPED_TEST_P(SingleCompositionRunsWhenDisabledTest, False) { auto param = false; - TypeParam command = TypeParam( - cmd::WaitUntil([] { return false; }).IgnoringDisable(param).Unwrap()); + TypeParam command = TypeParam(cmd::Idle().IgnoringDisable(param).Unwrap()); EXPECT_EQ(param, command.RunsWhenDisabled()); } @@ -44,17 +42,15 @@ TYPED_TEST_SUITE_P(SingleCompositionInterruptibilityTest); TYPED_TEST_P(SingleCompositionInterruptibilityTest, CancelSelf) { auto param = Command::InterruptionBehavior::kCancelSelf; - TypeParam command = TypeParam(cmd::WaitUntil([] { return false; }) - .WithInterruptBehavior(param) - .Unwrap()); + TypeParam command = + TypeParam(cmd::Idle().WithInterruptBehavior(param).Unwrap()); EXPECT_EQ(param, command.GetInterruptionBehavior()); } TYPED_TEST_P(SingleCompositionInterruptibilityTest, CancelIncoming) { auto param = Command::InterruptionBehavior::kCancelIncoming; - TypeParam command = TypeParam(cmd::WaitUntil([] { return false; }) - .WithInterruptBehavior(param) - .Unwrap()); + TypeParam command = + TypeParam(cmd::Idle().WithInterruptBehavior(param).Unwrap()); EXPECT_EQ(param, command.GetInterruptionBehavior()); } @@ -77,47 +73,43 @@ TYPED_TEST_SUITE_P(MultiCompositionRunsWhenDisabledTest); TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, OneTrue) { auto param = true; - TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(param)))); + TypeParam command = TypeParam(CommandPtr::UnwrapVector( + cmd::impl::MakeVector(cmd::Idle().IgnoringDisable(param)))); EXPECT_EQ(param, command.RunsWhenDisabled()); } TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, OneFalse) { auto param = false; - TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(param)))); + TypeParam command = TypeParam(CommandPtr::UnwrapVector( + cmd::impl::MakeVector(cmd::Idle().IgnoringDisable(param)))); EXPECT_EQ(param, command.RunsWhenDisabled()); } TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, AllTrue) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true)))); + cmd::Idle().IgnoringDisable(true), cmd::Idle().IgnoringDisable(true), + cmd::Idle().IgnoringDisable(true)))); EXPECT_EQ(true, command.RunsWhenDisabled()); } TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, AllFalse) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false)))); + cmd::Idle().IgnoringDisable(false), cmd::Idle().IgnoringDisable(false), + cmd::Idle().IgnoringDisable(false)))); EXPECT_EQ(false, command.RunsWhenDisabled()); } TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, TwoTrueOneFalse) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false)))); + cmd::Idle().IgnoringDisable(true), cmd::Idle().IgnoringDisable(true), + cmd::Idle().IgnoringDisable(false)))); EXPECT_EQ(false, command.RunsWhenDisabled()); } TYPED_TEST_P(MultiCompositionRunsWhenDisabledTest, TwoFalseOneTrue) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true)))); + cmd::Idle().IgnoringDisable(false), cmd::Idle().IgnoringDisable(false), + cmd::Idle().IgnoringDisable(true)))); EXPECT_EQ(false, command.RunsWhenDisabled()); } @@ -132,61 +124,49 @@ class MultiCompositionInterruptibilityTest TYPED_TEST_SUITE_P(MultiCompositionInterruptibilityTest); TYPED_TEST_P(MultiCompositionInterruptibilityTest, AllCancelSelf) { - TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf)))); + TypeParam command = TypeParam(CommandPtr::UnwrapVector( + cmd::impl::MakeVector(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf)))); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.GetInterruptionBehavior()); } TYPED_TEST_P(MultiCompositionInterruptibilityTest, AllCancelIncoming) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { return false; }) - .WithInterruptBehavior( - Command::InterruptionBehavior::kCancelIncoming)))); + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming)))); EXPECT_EQ(Command::InterruptionBehavior::kCancelIncoming, command.GetInterruptionBehavior()); } TYPED_TEST_P(MultiCompositionInterruptibilityTest, TwoCancelSelfOneIncoming) { TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { return false; }) - .WithInterruptBehavior( - Command::InterruptionBehavior::kCancelIncoming)))); + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming)))); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.GetInterruptionBehavior()); } TYPED_TEST_P(MultiCompositionInterruptibilityTest, TwoCancelIncomingOneSelf) { - TypeParam command = TypeParam(CommandPtr::UnwrapVector(cmd::impl::MakeVector( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf)))); + TypeParam command = TypeParam(CommandPtr::UnwrapVector( + cmd::impl::MakeVector(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf)))); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.GetInterruptionBehavior()); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp index 7896a1aa326..fefb75d0e70 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp @@ -56,85 +56,72 @@ TEST_F(ConditionalCommandTest, ConditionalCommandRequirement) { } TEST_F(ConditionalCommandTest, AllTrue) { - CommandPtr command = - cmd::Either(cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - [] { return true; }); + auto command = + cmd::Either(cmd::Idle().IgnoringDisable(true), + cmd::Idle().IgnoringDisable(true), [] { return true; }); EXPECT_EQ(true, command.get()->RunsWhenDisabled()); } TEST_F(ConditionalCommandTest, AllFalse) { - CommandPtr command = - cmd::Either(cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - [] { return true; }); + auto command = + cmd::Either(cmd::Idle().IgnoringDisable(false), + cmd::Idle().IgnoringDisable(false), [] { return true; }); EXPECT_EQ(false, command.get()->RunsWhenDisabled()); } TEST_F(ConditionalCommandTest, OneTrueOneFalse) { - CommandPtr command = - cmd::Either(cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - [] { return true; }); + auto command = + cmd::Either(cmd::Idle().IgnoringDisable(true), + cmd::Idle().IgnoringDisable(false), [] { return true; }); EXPECT_EQ(false, command.get()->RunsWhenDisabled()); } TEST_F(ConditionalCommandTest, TwoFalseOneTrue) { - CommandPtr command = - cmd::Either(cmd::WaitUntil([] { return false; }).IgnoringDisable(false), - cmd::WaitUntil([] { return false; }).IgnoringDisable(true), - [] { return true; }); + auto command = + cmd::Either(cmd::Idle().IgnoringDisable(false), + cmd::Idle().IgnoringDisable(true), [] { return true; }); EXPECT_EQ(false, command.get()->RunsWhenDisabled()); } TEST_F(ConditionalCommandTest, AllCancelSelf) { - CommandPtr command = cmd::Either( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - [] { return true; }); + auto command = cmd::Either(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + [] { return true; }); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.get()->GetInterruptionBehavior()); } TEST_F(ConditionalCommandTest, AllCancelIncoming) { - CommandPtr command = cmd::Either( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - [] { return false; }); + auto command = + cmd::Either(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + [] { return false; }); EXPECT_EQ(Command::InterruptionBehavior::kCancelIncoming, command.get()->GetInterruptionBehavior()); } TEST_F(ConditionalCommandTest, OneCancelSelfOneIncoming) { - CommandPtr command = cmd::Either( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - [] { return false; }); + auto command = + cmd::Either(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + [] { return false; }); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.get()->GetInterruptionBehavior()); } TEST_F(ConditionalCommandTest, OneCancelIncomingOneSelf) { - CommandPtr command = cmd::Either( - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelIncoming), - cmd::WaitUntil([] { - return false; - }).WithInterruptBehavior(Command::InterruptionBehavior::kCancelSelf), - [] { return false; }); + auto command = + cmd::Either(cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelIncoming), + cmd::Idle().WithInterruptBehavior( + Command::InterruptionBehavior::kCancelSelf), + [] { return false; }); EXPECT_EQ(Command::InterruptionBehavior::kCancelSelf, command.get()->GetInterruptionBehavior()); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp index a024a2f1955..25acb7f979f 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp @@ -5,6 +5,7 @@ #include #include "CommandTestBase.h" +#include "frc2/command/Commands.h" #include "frc2/command/RunCommand.h" using namespace frc2; @@ -15,9 +16,9 @@ TEST_F(DefaultCommandTest, DefaultCommandSchedule) { TestSubsystem subsystem; - RunCommand command1([] {}, {&subsystem}); + auto command = cmd::Idle({&subsystem}); - scheduler.SetDefaultCommand(&subsystem, std::move(command1)); + scheduler.SetDefaultCommand(&subsystem, std::move(command)); auto handle = scheduler.GetDefaultCommand(&subsystem); scheduler.Run(); @@ -29,18 +30,18 @@ TEST_F(DefaultCommandTest, DefaultCommandInterruptResume) { TestSubsystem subsystem; - RunCommand command1([] {}, {&subsystem}); - RunCommand command2([] {}, {&subsystem}); + auto command1 = cmd::Idle({&subsystem}); + auto command2 = cmd::Idle({&subsystem}); scheduler.SetDefaultCommand(&subsystem, std::move(command1)); auto handle = scheduler.GetDefaultCommand(&subsystem); scheduler.Run(); - scheduler.Schedule(&command2); + scheduler.Schedule(command2); - EXPECT_TRUE(scheduler.IsScheduled(&command2)); + EXPECT_TRUE(scheduler.IsScheduled(command2)); EXPECT_FALSE(scheduler.IsScheduled(handle)); - scheduler.Cancel(&command2); + scheduler.Cancel(command2); scheduler.Run(); EXPECT_TRUE(scheduler.IsScheduled(handle)); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp index 90eab852231..9b01721e45a 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp @@ -3,6 +3,7 @@ // the WPILib BSD license file in the root directory of this project. #include "CommandTestBase.h" +#include "frc2/command/Commands.h" #include "frc2/command/InstantCommand.h" using namespace frc2; @@ -13,10 +14,10 @@ TEST_F(InstantCommandTest, InstantCommandSchedule) { int counter = 0; - InstantCommand command([&counter] { counter++; }, {}); + auto command = cmd::RunOnce([&counter] { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&command)); + EXPECT_FALSE(scheduler.IsScheduled(command)); EXPECT_EQ(counter, 1); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp index 21457d024cd..2f22a30a1e4 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp @@ -78,9 +78,9 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupInterrupt) { TEST_F(ParallelCommandGroupTest, ParallelGroupNotScheduledCancel) { CommandScheduler scheduler = GetScheduler(); - ParallelCommandGroup group((InstantCommand(), InstantCommand())); + auto group = cmd::Parallel(cmd::None(), cmd::None()); - EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); + EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(group)); } TEST_F(ParallelCommandGroupTest, ParallelGroupCopy) { @@ -88,15 +88,15 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupCopy) { bool finished = false; - WaitUntilCommand command([&finished] { return finished; }); + auto command = cmd::WaitUntil([&finished] { return finished; }); - ParallelCommandGroup group(command); - scheduler.Schedule(&group); + auto group = cmd::Parallel(std::move(command)); + scheduler.Schedule(group); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(group)); finished = true; scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } TEST_F(ParallelCommandGroupTest, ParallelGroupRequirement) { @@ -107,17 +107,17 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupRequirement) { TestSubsystem requirement3; TestSubsystem requirement4; - InstantCommand command1([] {}, {&requirement1, &requirement2}); - InstantCommand command2([] {}, {&requirement3}); - InstantCommand command3([] {}, {&requirement3, &requirement4}); + auto command1 = cmd::RunOnce([] {}, {&requirement1, &requirement2}); + auto command2 = cmd::RunOnce([] {}, {&requirement3}); + auto command3 = cmd::RunOnce([] {}, {&requirement3, &requirement4}); - ParallelCommandGroup group(std::move(command1), std::move(command2)); + auto group = cmd::Parallel(std::move(command1), std::move(command2)); - scheduler.Schedule(&group); - scheduler.Schedule(&command3); + scheduler.Schedule(group); + scheduler.Schedule(command3); - EXPECT_TRUE(scheduler.IsScheduled(&command3)); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(command3)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(ParallelCommandGroupTest, diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp index d36b97ad6c6..9da797ccadf 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp @@ -95,9 +95,9 @@ TEST_F(ParallelDeadlineGroupTest, SequentialGroupInterrupt) { TEST_F(ParallelDeadlineGroupTest, DeadlineGroupNotScheduledCancel) { CommandScheduler scheduler = GetScheduler(); - ParallelDeadlineGroup group{InstantCommand(), InstantCommand()}; + auto group = cmd::Deadline(cmd::None(), cmd::None()); - EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); + EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(group)); } TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineCopy) { @@ -105,15 +105,15 @@ TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineCopy) { bool finished = false; - WaitUntilCommand command([&finished] { return finished; }); + auto command = cmd::WaitUntil([&finished] { return finished; }); - ParallelDeadlineGroup group(command); - scheduler.Schedule(&group); + auto group = cmd::Deadline(std::move(command)); + scheduler.Schedule(group); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(group)); finished = true; scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineRequirement) { @@ -124,17 +124,17 @@ TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineRequirement) { TestSubsystem requirement3; TestSubsystem requirement4; - InstantCommand command1([] {}, {&requirement1, &requirement2}); - InstantCommand command2([] {}, {&requirement3}); - InstantCommand command3([] {}, {&requirement3, &requirement4}); + auto command1 = cmd::RunOnce([] {}, {&requirement1, &requirement2}); + auto command2 = cmd::RunOnce([] {}, {&requirement3}); + auto command3 = cmd::RunOnce([] {}, {&requirement3, &requirement4}); - ParallelDeadlineGroup group(std::move(command1), std::move(command2)); + auto group = cmd::Deadline(std::move(command1), std::move(command2)); - scheduler.Schedule(&group); - scheduler.Schedule(&command3); + scheduler.Schedule(group); + scheduler.Schedule(command3); - EXPECT_TRUE(scheduler.IsScheduled(&command3)); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(command3)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } class TestableDeadlineCommand : public ParallelDeadlineGroup { diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp index 032c3c1dd33..491ba75acb9 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp @@ -90,9 +90,9 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceInterrupt) { TEST_F(ParallelRaceGroupTest, ParallelRaceNotScheduledCancel) { CommandScheduler scheduler = GetScheduler(); - ParallelRaceGroup group{InstantCommand(), InstantCommand()}; + auto group = cmd::Race(cmd::None(), cmd::None()); - EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); + EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(group)); } TEST_F(ParallelRaceGroupTest, ParallelRaceCopy) { @@ -100,15 +100,15 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceCopy) { bool finished = false; - WaitUntilCommand command([&finished] { return finished; }); + auto command = cmd::WaitUntil([&finished] { return finished; }); - ParallelRaceGroup group(command); - scheduler.Schedule(&group); + auto group = cmd::Race(std::move(command)); + scheduler.Schedule(group); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(group)); finished = true; scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } TEST_F(ParallelRaceGroupTest, RaceGroupRequirement) { @@ -119,17 +119,17 @@ TEST_F(ParallelRaceGroupTest, RaceGroupRequirement) { TestSubsystem requirement3; TestSubsystem requirement4; - InstantCommand command1([] {}, {&requirement1, &requirement2}); - InstantCommand command2([] {}, {&requirement3}); - InstantCommand command3([] {}, {&requirement3, &requirement4}); + auto command1 = cmd::RunOnce([] {}, {&requirement1, &requirement2}); + auto command2 = cmd::RunOnce([] {}, {&requirement3}); + auto command3 = cmd::RunOnce([] {}, {&requirement3, &requirement4}); - ParallelRaceGroup group(std::move(command1), std::move(command2)); + auto group = cmd::Race(std::move(command1), std::move(command2)); - scheduler.Schedule(&group); - scheduler.Schedule(&command3); + scheduler.Schedule(group); + scheduler.Schedule(command3); - EXPECT_TRUE(scheduler.IsScheduled(&command3)); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(command3)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } TEST_F(ParallelRaceGroupTest, ParallelRaceOnlyCallsEndOnce) { @@ -139,21 +139,21 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceOnlyCallsEndOnce) { bool finished2 = false; bool finished3 = false; - WaitUntilCommand command1([&finished1] { return finished1; }); - WaitUntilCommand command2([&finished2] { return finished2; }); - WaitUntilCommand command3([&finished3] { return finished3; }); + auto command1 = cmd::WaitUntil([&finished1] { return finished1; }); + auto command2 = cmd::WaitUntil([&finished2] { return finished2; }); + auto command3 = cmd::WaitUntil([&finished3] { return finished3; }); - SequentialCommandGroup group1(command1, command2); - ParallelRaceGroup group2(std::move(group1), command3); + auto group1 = cmd::Sequence(std::move(command1), std::move(command2)); + auto group2 = cmd::Race(std::move(group1), std::move(command3)); - scheduler.Schedule(&group2); + scheduler.Schedule(group2); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&group2)); + EXPECT_TRUE(scheduler.IsScheduled(group2)); finished1 = true; scheduler.Run(); finished2 = true; EXPECT_NO_FATAL_FAILURE(scheduler.Run()); - EXPECT_FALSE(scheduler.IsScheduled(&group2)); + EXPECT_FALSE(scheduler.IsScheduled(group2)); } TEST_F(ParallelRaceGroupTest, ParallelRaceScheduleTwice) { diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp index 02575a30ccc..77906f1e611 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include #include "CommandTestBase.h" @@ -13,15 +15,15 @@ class PrintCommandTest : public CommandTestBase {}; TEST_F(PrintCommandTest, PrintCommandSchedule) { CommandScheduler scheduler = GetScheduler(); - PrintCommand command("Test!"); + auto command = cmd::Print("Test!"); testing::internal::CaptureStdout(); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); EXPECT_TRUE(std::regex_search(testing::internal::GetCapturedStdout(), std::regex("Test!"))); - EXPECT_FALSE(scheduler.IsScheduled(&command)); + EXPECT_FALSE(scheduler.IsScheduled(command)); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp index 81ec9d14326..7abc56fa11e 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include #include "CommandTestBase.h" @@ -52,8 +54,7 @@ TEST_F(ProxyCommandTest, OwningCommandSchedule) { bool scheduled = false; - CommandPtr command = - InstantCommand([&scheduled] { scheduled = true; }).AsProxy(); + auto command = cmd::RunOnce([&scheduled] { scheduled = true; }).AsProxy(); scheduler.Schedule(command); scheduler.Run(); @@ -66,8 +67,7 @@ TEST_F(ProxyCommandTest, OwningCommandEnd) { bool finished = false; - CommandPtr command = - WaitUntilCommand([&finished] { return finished; }).AsProxy(); + auto command = cmd::WaitUntil([&finished] { return finished; }).AsProxy(); scheduler.Schedule(command); scheduler.Run(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp index 11d4adac76b..07eaaf54c51 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include "CommandTestBase.h" #include "frc2/command/RunCommand.h" @@ -13,9 +15,9 @@ TEST_F(RunCommandTest, RunCommandSchedule) { int counter = 0; - RunCommand command([&counter] { counter++; }, {}); + auto command = cmd::Run([&counter] { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); scheduler.Run(); scheduler.Run(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp index bc4756cccc3..24ca0ecd5e1 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include #include "CommandTestBase.h" @@ -15,7 +17,7 @@ class SchedulerTest : public CommandTestBase {}; TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { CommandScheduler scheduler = GetScheduler(); - InstantCommand command; + auto command = cmd::None(); int counter = 0; @@ -23,7 +25,7 @@ TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { scheduler.OnCommandExecute([&counter](const Command&) { counter++; }); scheduler.OnCommandFinish([&counter](const Command&) { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); EXPECT_EQ(counter, 3); @@ -32,15 +34,15 @@ TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { TEST_F(SchedulerTest, SchedulerLambdaInterrupt) { CommandScheduler scheduler = GetScheduler(); - RunCommand command([] {}, {}); + auto command = cmd::Idle(); int counter = 0; scheduler.OnCommandInterrupt([&counter](const Command&) { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); - scheduler.Cancel(&command); + scheduler.Cancel(command); EXPECT_EQ(counter, 1); } @@ -56,10 +58,10 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptNoCause) { counter++; }); - RunCommand command([] {}); + auto command = cmd::Idle(); - scheduler.Schedule(&command); - scheduler.Cancel(&command); + scheduler.Schedule(command); + scheduler.Cancel(command); EXPECT_EQ(1, counter); } @@ -70,7 +72,7 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCause) { int counter = 0; TestSubsystem subsystem{}; - RunCommand command([] {}, {&subsystem}); + auto command = cmd::Idle({&subsystem}); InstantCommand interruptor([] {}, {&subsystem}); scheduler.OnCommandInterrupt( @@ -80,7 +82,7 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCause) { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Schedule(&interruptor); EXPECT_EQ(1, counter); @@ -92,11 +94,11 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCauseInRunLoop) { int counter = 0; TestSubsystem subsystem{}; - RunCommand command([] {}, {&subsystem}); + auto command = cmd::Idle({&subsystem}); InstantCommand interruptor([] {}, {&subsystem}); // This command will schedule interruptor in execute() inside the run loop - InstantCommand interruptorScheduler( - [&] { scheduler.Schedule(&interruptor); }); + auto interruptorScheduler = + cmd::RunOnce([&] { scheduler.Schedule(&interruptor); }); scheduler.OnCommandInterrupt( [&](const Command&, const std::optional& cause) { @@ -105,8 +107,8 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCauseInRunLoop) { counter++; }); - scheduler.Schedule(&command); - scheduler.Schedule(&interruptorScheduler); + scheduler.Schedule(command); + scheduler.Schedule(interruptorScheduler); scheduler.Run(); @@ -142,8 +144,8 @@ TEST_F(SchedulerTest, UnregisterSubsystem) { TEST_F(SchedulerTest, SchedulerCancelAll) { CommandScheduler scheduler = GetScheduler(); - RunCommand command([] {}, {}); - RunCommand command2([] {}, {}); + auto command1 = cmd::Idle(); + auto command2 = cmd::Idle(); int counter = 0; @@ -153,8 +155,8 @@ TEST_F(SchedulerTest, SchedulerCancelAll) { EXPECT_FALSE(interruptor); }); - scheduler.Schedule(&command); - scheduler.Schedule(&command2); + scheduler.Schedule(command1); + scheduler.Schedule(command2); scheduler.Run(); scheduler.CancelAll(); @@ -166,10 +168,10 @@ TEST_F(SchedulerTest, ScheduleScheduledNoOp) { int counter = 0; - StartEndCommand command([&counter] { counter++; }, [] {}); + auto command = cmd::StartEnd([&counter] { counter++; }, [] {}); - scheduler.Schedule(&command); - scheduler.Schedule(&command); + scheduler.Schedule(command); + scheduler.Schedule(command); EXPECT_EQ(counter, 1); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp index 0b54c589515..650319d8cfc 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include #include @@ -55,14 +57,14 @@ TEST_P(SchedulingRecursionTest, CancelFromInitialize) { TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, GetParam()}; - RunCommand other{[&hasOtherRun] { hasOtherRun = true; }, {&requirement}}; + auto other = cmd::Run([&hasOtherRun] { hasOtherRun = true; }, {&requirement}); scheduler.Schedule(&selfCancels); scheduler.Run(); - scheduler.Schedule(&other); + scheduler.Schedule(other); EXPECT_FALSE(scheduler.IsScheduled(&selfCancels)); - EXPECT_TRUE(scheduler.IsScheduled(&other)); + EXPECT_TRUE(scheduler.IsScheduled(other)); EXPECT_EQ(1, counter); scheduler.Run(); EXPECT_TRUE(hasOtherRun); @@ -78,16 +80,16 @@ TEST_F(SchedulingRecursionTest, CancelFromInitializeAction) { [&counter](bool) { counter++; }, [] { return false; }, {&requirement}}; - RunCommand other{[&hasOtherRun] { hasOtherRun = true; }, {&requirement}}; + auto other = cmd::Run([&hasOtherRun] { hasOtherRun = true; }, {&requirement}); scheduler.OnCommandInitialize([&scheduler, &selfCancels](const Command&) { scheduler.Cancel(&selfCancels); }); scheduler.Schedule(&selfCancels); scheduler.Run(); - scheduler.Schedule(&other); + scheduler.Schedule(other); EXPECT_FALSE(scheduler.IsScheduled(&selfCancels)); - EXPECT_TRUE(scheduler.IsScheduled(&other)); + EXPECT_TRUE(scheduler.IsScheduled(other)); EXPECT_EQ(1, counter); scheduler.Run(); EXPECT_TRUE(hasOtherRun); @@ -101,7 +103,7 @@ TEST_P(SchedulingRecursionTest, TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, GetParam()}; - RunCommand other{[&hasOtherRun] { hasOtherRun = true; }, {&requirement}}; + auto other = cmd::Run([&hasOtherRun] { hasOtherRun = true; }, {&requirement}); scheduler.SetDefaultCommand(&requirement, std::move(other)); scheduler.Schedule(&selfCancels); @@ -202,6 +204,7 @@ TEST_F(SchedulingRecursionTest, CancelFromEndLoop) { TEST_F(SchedulingRecursionTest, CancelFromEndLoopWhileInRunLoop) { CommandScheduler scheduler = GetScheduler(); int counter = 0; + EndCommand dCancelsAll([&](bool) { counter++; scheduler.CancelAll(); @@ -270,7 +273,6 @@ TEST_P(SchedulingRecursionTest, ScheduleFromEndCancel) { TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, GetParam()}; - RunCommand other{[] {}, {&requirement}}; scheduler.Schedule(&selfCancels); EXPECT_NO_THROW({ scheduler.Cancel(&selfCancels); }); @@ -284,30 +286,30 @@ TEST_P(SchedulingRecursionTest, ScheduleFromEndInterrupt) { TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, GetParam()}; - RunCommand other{[] {}, {&requirement}}; + auto other = cmd::Idle({&requirement}); scheduler.Schedule(&selfCancels); - EXPECT_NO_THROW({ scheduler.Schedule(&other); }); + EXPECT_NO_THROW({ scheduler.Schedule(other); }); EXPECT_EQ(1, counter); EXPECT_FALSE(scheduler.IsScheduled(&selfCancels)); - EXPECT_TRUE(scheduler.IsScheduled(&other)); + EXPECT_TRUE(scheduler.IsScheduled(other)); } TEST_F(SchedulingRecursionTest, ScheduleFromEndInterruptAction) { CommandScheduler scheduler = GetScheduler(); int counter = 0; TestSubsystem requirement; - RunCommand selfCancels{[] {}, {&requirement}}; - RunCommand other{[] {}, {&requirement}}; + auto selfCancels = cmd::Idle({&requirement}); + auto other = cmd::Idle({&requirement}); scheduler.OnCommandInterrupt([&](const Command&) { counter++; - scheduler.Schedule(&other); + scheduler.Schedule(other); }); - scheduler.Schedule(&selfCancels); - EXPECT_NO_THROW({ scheduler.Schedule(&other); }); + scheduler.Schedule(selfCancels); + EXPECT_NO_THROW({ scheduler.Schedule(other); }); EXPECT_EQ(1, counter); - EXPECT_FALSE(scheduler.IsScheduled(&selfCancels)); - EXPECT_TRUE(scheduler.IsScheduled(&other)); + EXPECT_FALSE(scheduler.IsScheduled(selfCancels)); + EXPECT_TRUE(scheduler.IsScheduled(other)); } TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { @@ -319,11 +321,11 @@ TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { [&counter](bool) { counter++; }, [] { return false; }, {&requirement}}; - RunCommand other{[] {}, {&requirement}}; + auto other = cmd::Idle({&requirement}); FunctionalCommand cancelDefaultCommand{[] {}, [] {}, [&](bool) { counter++; - scheduler.Schedule(&other); + scheduler.Schedule(other); }, [] { return false; }}; @@ -336,7 +338,7 @@ TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { }); EXPECT_EQ(2, counter); EXPECT_FALSE(scheduler.IsScheduled(&defaultCommand)); - EXPECT_TRUE(scheduler.IsScheduled(&other)); + EXPECT_TRUE(scheduler.IsScheduled(other)); } TEST_F(SchedulingRecursionTest, CancelNextCommandFromCommand) { diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp index dc882a0ed17..76d9e88c2c5 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp @@ -48,18 +48,19 @@ TEST_F(SelectCommandTest, SelectCommandRequirement) { TestSubsystem requirement3; TestSubsystem requirement4; - InstantCommand command1([] {}, {&requirement1, &requirement2}); - InstantCommand command2([] {}, {&requirement3}); - InstantCommand command3([] {}, {&requirement3, &requirement4}); + auto command1 = cmd::RunOnce([] {}, {&requirement1, &requirement2}); + auto command2 = cmd::RunOnce([] {}, {&requirement3}); + auto command3 = cmd::RunOnce([] {}, {&requirement3, &requirement4}); - SelectCommand select([] { return 1; }, std::pair(1, std::move(command1)), - std::pair(2, std::move(command2))); + auto select = + cmd::Select([] { return 1; }, std::pair(1, std::move(command1)), + std::pair(2, std::move(command2))); - scheduler.Schedule(&select); - scheduler.Schedule(&command3); + scheduler.Schedule(select); + scheduler.Schedule(command3); - EXPECT_TRUE(scheduler.IsScheduled(&command3)); - EXPECT_FALSE(scheduler.IsScheduled(&select)); + EXPECT_TRUE(scheduler.IsScheduled(command3)); + EXPECT_FALSE(scheduler.IsScheduled(select)); } class TestableSelectCommand : public SelectCommand { diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp index b8920c733f9..3781928ea64 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp @@ -105,15 +105,15 @@ TEST_F(SequentialCommandGroupTest, SequentialGroupCopy) { bool finished = false; - WaitUntilCommand command([&finished] { return finished; }); + auto command = cmd::WaitUntil([&finished] { return finished; }); - SequentialCommandGroup group(command); - scheduler.Schedule(&group); + auto group = cmd::Sequence(std::move(command)); + scheduler.Schedule(group); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(group)); finished = true; scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } TEST_F(SequentialCommandGroupTest, SequentialGroupRequirement) { @@ -124,17 +124,17 @@ TEST_F(SequentialCommandGroupTest, SequentialGroupRequirement) { TestSubsystem requirement3; TestSubsystem requirement4; - InstantCommand command1([] {}, {&requirement1, &requirement2}); - InstantCommand command2([] {}, {&requirement3}); - InstantCommand command3([] {}, {&requirement3, &requirement4}); + auto command1 = cmd::RunOnce([] {}, {&requirement1, &requirement2}); + auto command2 = cmd::RunOnce([] {}, {&requirement3}); + auto command3 = cmd::RunOnce([] {}, {&requirement3, &requirement4}); - SequentialCommandGroup group(std::move(command1), std::move(command2)); + auto group = cmd::Sequence(std::move(command1), std::move(command2)); - scheduler.Schedule(&group); - scheduler.Schedule(&command3); + scheduler.Schedule(group); + scheduler.Schedule(command3); - EXPECT_TRUE(scheduler.IsScheduled(&command3)); - EXPECT_FALSE(scheduler.IsScheduled(&group)); + EXPECT_TRUE(scheduler.IsScheduled(command3)); + EXPECT_FALSE(scheduler.IsScheduled(group)); } INSTANTIATE_MULTI_COMMAND_COMPOSITION_TEST_SUITE(SequentialCommandGroupTest, diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp index 53a2df2a2ce..744646d3719 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include "CommandTestBase.h" #include "frc2/command/StartEndCommand.h" @@ -13,13 +15,13 @@ TEST_F(StartEndCommandTest, StartEndCommandSchedule) { int counter = 0; - StartEndCommand command([&counter] { counter++; }, [&counter] { counter++; }, - {}); + auto command = + cmd::StartEnd([&counter] { counter++; }, [&counter] { counter++; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); scheduler.Run(); - scheduler.Cancel(&command); + scheduler.Cancel(command); EXPECT_EQ(2, counter); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp index 30eea6b4331..a575e656130 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include #include "CommandTestBase.h" @@ -16,14 +18,14 @@ TEST_F(WaitCommandTest, WaitCommandSchedule) { CommandScheduler scheduler = GetScheduler(); - WaitCommand command(100_ms); + auto command = cmd::Wait(100_ms); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&command)); + EXPECT_TRUE(scheduler.IsScheduled(command)); frc::sim::StepTiming(110_ms); scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&command)); + EXPECT_FALSE(scheduler.IsScheduled(command)); frc::sim::ResumeTiming(); } diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp index 01acc390e17..10b36fe5010 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp @@ -2,6 +2,8 @@ // 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. +#include + #include "CommandTestBase.h" #include "frc2/command/WaitUntilCommand.h" @@ -13,12 +15,12 @@ TEST_F(WaitUntilCommandTest, WaitUntilCommandSchedule) { bool finished = false; - WaitUntilCommand command([&finished] { return finished; }); + auto command = cmd::WaitUntil([&finished] { return finished; }); - scheduler.Schedule(&command); + scheduler.Schedule(command); scheduler.Run(); - EXPECT_TRUE(scheduler.IsScheduled(&command)); + EXPECT_TRUE(scheduler.IsScheduled(command)); finished = true; scheduler.Run(); - EXPECT_FALSE(scheduler.IsScheduled(&command)); + EXPECT_FALSE(scheduler.IsScheduled(command)); }