From 4c568c9b89c91500bd7e9568e55ab6b7687e72d2 Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Mon, 23 Dec 2024 09:53:45 -0800 Subject: [PATCH 1/3] Add and use CommandScheduler.resetInstance() --- .../wpilibj2/command/CommandScheduler.java | 13 +- .../cpp/frc2/command/CommandScheduler.cpp | 4 + .../include/frc2/command/CommandScheduler.h | 9 +- .../command/CommandDecoratorTest.java | 666 ++++++++-------- .../command/CommandRequirementsTest.java | 68 +- .../wpilibj2/command/CommandScheduleTest.java | 131 ++- .../command/CommandSendableButtonTest.java | 16 +- .../wpilibj2/command/CommandTestBase.java | 10 +- .../command/ConditionalCommandTest.java | 62 +- .../wpilibj2/command/DefaultCommandTest.java | 72 +- .../wpilibj2/command/DeferredCommandTest.java | 20 +- .../command/FunctionalCommandTest.java | 40 +- .../wpilibj2/command/InstantCommandTest.java | 14 +- .../wpilibj2/command/NotifierCommandTest.java | 18 +- .../command/ParallelCommandGroupTest.java | 110 ++- .../command/ParallelDeadlineGroupTest.java | 130 ++- .../command/ParallelRaceGroupTest.java | 188 +++-- .../wpilibj2/command/PrintCommandTest.java | 24 +- .../wpilibj2/command/ProxyCommandTest.java | 34 +- .../wpilibj2/command/RepeatCommandTest.java | 108 ++- .../command/RobotDisabledCommandTest.java | 134 ++-- .../wpilibj2/command/RunCommandTest.java | 16 +- .../wpilibj2/command/ScheduleCommandTest.java | 38 +- .../first/wpilibj2/command/SchedulerTest.java | 206 +++-- .../command/SchedulingRecursionTest.java | 744 +++++++++--------- .../wpilibj2/command/SelectCommandTest.java | 146 ++-- .../command/SequentialCommandGroupTest.java | 142 ++-- .../wpilibj2/command/StartEndCommandTest.java | 22 +- .../wpilibj2/command/WaitCommandTest.java | 54 +- .../command/WaitUntilCommandTest.java | 18 +- .../command/button/NetworkButtonTest.java | 2 - .../wpilibj2/command/button/TriggerTest.java | 10 - .../cpp/frc2/command/CommandDecoratorTest.cpp | 40 - .../cpp/frc2/command/CommandPtrTest.cpp | 2 - .../frc2/command/CommandRequirementsTest.cpp | 8 +- .../cpp/frc2/command/CommandScheduleTest.cpp | 21 +- .../command/CommandSendableButtonTest.cpp | 16 +- .../cpp/frc2/command/CommandTestBase.cpp | 10 +- .../native/cpp/frc2/command/CommandTestBase.h | 12 +- .../frc2/command/ConditionalCommandTest.cpp | 4 - .../cpp/frc2/command/DefaultCommandTest.cpp | 4 - .../frc2/command/FunctionalCommandTest.cpp | 2 - .../cpp/frc2/command/InstantCommandTest.cpp | 2 - .../cpp/frc2/command/NotifierCommandTest.cpp | 2 - .../frc2/command/ParallelCommandGroupTest.cpp | 10 - .../command/ParallelDeadlineGroupTest.cpp | 10 - .../frc2/command/ParallelRaceGroupTest.cpp | 14 - .../cpp/frc2/command/PrintCommandTest.cpp | 2 - .../cpp/frc2/command/ProxyCommandTest.cpp | 4 - .../cpp/frc2/command/RepeatCommandTest.cpp | 2 - .../frc2/command/RobotDisabledCommandTest.cpp | 16 - .../cpp/frc2/command/RunCommandTest.cpp | 2 - .../cpp/frc2/command/ScheduleCommandTest.cpp | 2 - .../native/cpp/frc2/command/SchedulerTest.cpp | 43 +- .../frc2/command/SchedulingRecursionTest.cpp | 23 +- .../cpp/frc2/command/SelectCommandTest.cpp | 4 - .../command/SequentialCommandGroupTest.cpp | 10 - .../cpp/frc2/command/StartEndCommandTest.cpp | 2 - .../cpp/frc2/command/WaitCommandTest.cpp | 2 - .../cpp/frc2/command/WaitUntilCommandTest.cpp | 2 - 60 files changed, 1579 insertions(+), 1961 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index 0e80a74c613..b3707643cee 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -62,6 +62,17 @@ public static synchronized CommandScheduler getInstance() { return instance; } + /** + * Resets the Scheduler instance, which is useful for testing purposes. This should not be called + * from user code. + */ + public static synchronized void resetInstance() { + if (instance != null) { + instance.close(); + } + instance = null; + } + private static final Optional kNoInterruptor = Optional.empty(); private final Map m_composedCommands = new WeakHashMap<>(); @@ -99,7 +110,7 @@ public static synchronized CommandScheduler getInstance() { private final Watchdog m_watchdog = new Watchdog(TimedRobot.kDefaultPeriod, () -> {}); - CommandScheduler() { + private CommandScheduler() { HAL.report(tResourceType.kResourceType_Command, tInstances.kCommand2_Scheduler); SendableRegistry.addLW(this, "Scheduler"); LiveWindow.setEnabledListener( diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 369e14367bc..002a67fa6f0 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -93,6 +93,10 @@ CommandScheduler& CommandScheduler::GetInstance() { return scheduler; } +void CommandScheduler::ResetInstance() { + std::make_unique().swap(GetInstance().m_impl); +} + void CommandScheduler::SetPeriod(units::second_t period) { m_watchdog.SetTimeout(period); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h index 2f43ff7bc2e..c1676e8aa4f 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h @@ -44,6 +44,10 @@ class CommandScheduler final : public wpi::Sendable, */ static CommandScheduler& GetInstance(); + /** Resets the Scheduler instance, which is useful for testing purposes. This + * should not be called from user code. */ + static void ResetInstance(); + ~CommandScheduler() override; CommandScheduler(const CommandScheduler&) = delete; CommandScheduler& operator=(const CommandScheduler&) = delete; @@ -466,10 +470,5 @@ class CommandScheduler final : public wpi::Sendable, std::unique_ptr m_impl; frc::Watchdog m_watchdog; - - friend class CommandTestBase; - - template - friend class CommandTestBaseWithParam; }; } // namespace frc2 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..c320e655b8d 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 @@ -22,7 +22,7 @@ class CommandDecoratorTest extends CommandTestBase { void withTimeoutTest() { HAL.initialize(500, 0); SimHooks.pauseTiming(); - try (CommandScheduler scheduler = new CommandScheduler()) { + try { Command timeout = new RunCommand(() -> {}).withTimeout(0.1); scheduler.schedule(timeout); @@ -41,492 +41,452 @@ void withTimeoutTest() { @Test void untilTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finish = new AtomicBoolean(); + AtomicBoolean finish = new AtomicBoolean(); - Command command = new RunCommand(() -> {}).until(finish::get); + Command command = new RunCommand(() -> {}).until(finish::get); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertTrue(scheduler.isScheduled(command)); + assertTrue(scheduler.isScheduled(command)); - finish.set(true); - scheduler.run(); + finish.set(true); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - } + assertFalse(scheduler.isScheduled(command)); } @Test void untilOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean firstHasRun = new AtomicBoolean(false); - AtomicBoolean firstWasPolled = new AtomicBoolean(false); - - Command first = - new FunctionalCommand( - () -> {}, - () -> firstHasRun.set(true), - interrupted -> {}, - () -> { - firstWasPolled.set(true); - return true; - }); - Command command = - first.until( - () -> { - assertAll( - () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - return true; - }); - - scheduler.schedule(command); - scheduler.run(); - - assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - } + AtomicBoolean firstHasRun = new AtomicBoolean(false); + AtomicBoolean firstWasPolled = new AtomicBoolean(false); + + Command first = + new FunctionalCommand( + () -> {}, + () -> firstHasRun.set(true), + interrupted -> {}, + () -> { + firstWasPolled.set(true); + return true; + }); + Command command = + first.until( + () -> { + assertAll( + () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); + return true; + }); + + scheduler.schedule(command); + scheduler.run(); + + assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); } @Test void onlyWhileTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean run = new AtomicBoolean(true); + AtomicBoolean run = new AtomicBoolean(true); - Command command = new RunCommand(() -> {}).onlyWhile(run::get); + Command command = new RunCommand(() -> {}).onlyWhile(run::get); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertTrue(scheduler.isScheduled(command)); + assertTrue(scheduler.isScheduled(command)); - run.set(false); - scheduler.run(); + run.set(false); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - } + assertFalse(scheduler.isScheduled(command)); } @Test void onlyWhileOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean firstHasRun = new AtomicBoolean(false); - AtomicBoolean firstWasPolled = new AtomicBoolean(false); - - Command first = - new FunctionalCommand( - () -> {}, - () -> firstHasRun.set(true), - interrupted -> {}, - () -> { - firstWasPolled.set(true); - return true; - }); - Command command = - first.onlyWhile( - () -> { - assertAll( - () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - return false; - }); - - scheduler.schedule(command); - scheduler.run(); - - assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - } + AtomicBoolean firstHasRun = new AtomicBoolean(false); + AtomicBoolean firstWasPolled = new AtomicBoolean(false); + + Command first = + new FunctionalCommand( + () -> {}, + () -> firstHasRun.set(true), + interrupted -> {}, + () -> { + firstWasPolled.set(true); + return true; + }); + Command command = + first.onlyWhile( + () -> { + assertAll( + () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); + return false; + }); + + scheduler.schedule(command); + scheduler.run(); + + assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); } @Test void ignoringDisableTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - var command = new RunCommand(() -> {}).ignoringDisable(true); + var command = new RunCommand(() -> {}).ignoringDisable(true); - setDSEnabled(false); + setDSEnabled(false); - scheduler.schedule(command); + scheduler.schedule(command); - scheduler.run(); - assertTrue(scheduler.isScheduled(command)); - } + scheduler.run(); + assertTrue(scheduler.isScheduled(command)); } @Test void beforeStartingTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finished = new AtomicBoolean(); - finished.set(false); + AtomicBoolean finished = new AtomicBoolean(); + finished.set(false); - Command command = new InstantCommand().beforeStarting(() -> finished.set(true)); + Command command = new InstantCommand().beforeStarting(() -> finished.set(true)); - scheduler.schedule(command); + scheduler.schedule(command); - assertTrue(finished.get()); + assertTrue(finished.get()); - scheduler.run(); + scheduler.run(); - assertTrue(scheduler.isScheduled(command)); + assertTrue(scheduler.isScheduled(command)); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - } + assertFalse(scheduler.isScheduled(command)); } @Test void andThenLambdaTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finished = new AtomicBoolean(false); + AtomicBoolean finished = new AtomicBoolean(false); - Command command = new InstantCommand().andThen(() -> finished.set(true)); + Command command = new InstantCommand().andThen(() -> finished.set(true)); - scheduler.schedule(command); + scheduler.schedule(command); - assertFalse(finished.get()); + assertFalse(finished.get()); - scheduler.run(); + scheduler.run(); - assertTrue(finished.get()); + assertTrue(finished.get()); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - } + assertFalse(scheduler.isScheduled(command)); } @Test void andThenTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean condition = new AtomicBoolean(false); + AtomicBoolean condition = new AtomicBoolean(false); - Command command1 = new InstantCommand(); - Command command2 = new InstantCommand(() -> condition.set(true)); - Command group = command1.andThen(command2); + Command command1 = new InstantCommand(); + Command command2 = new InstantCommand(() -> condition.set(true)); + Command group = command1.andThen(command2); - scheduler.schedule(group); + scheduler.schedule(group); - assertFalse(condition.get()); + assertFalse(condition.get()); - scheduler.run(); + scheduler.run(); - assertTrue(condition.get()); + assertTrue(condition.get()); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void deadlineForTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finish = new AtomicBoolean(false); + AtomicBoolean finish = new AtomicBoolean(false); - Command dictator = new WaitUntilCommand(finish::get); - Command endsBefore = new InstantCommand(); - Command endsAfter = new WaitUntilCommand(() -> false); + Command dictator = new WaitUntilCommand(finish::get); + Command endsBefore = new InstantCommand(); + Command endsAfter = new WaitUntilCommand(() -> false); - Command group = dictator.deadlineFor(endsBefore, endsAfter); + Command group = dictator.deadlineFor(endsBefore, endsAfter); - scheduler.schedule(group); - scheduler.run(); + scheduler.schedule(group); + scheduler.run(); - assertTrue(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(group)); - finish.set(true); - scheduler.run(); + finish.set(true); + scheduler.run(); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void deadlineForOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean dictatorHasRun = new AtomicBoolean(false); - AtomicBoolean dictatorWasPolled = new AtomicBoolean(false); - - Command dictator = - new FunctionalCommand( - () -> {}, - () -> dictatorHasRun.set(true), - interrupted -> {}, - () -> { - dictatorWasPolled.set(true); - return true; - }); - Command other = - new RunCommand( - () -> - assertAll( - () -> assertTrue(dictatorHasRun.get()), - () -> assertTrue(dictatorWasPolled.get()))); - - Command group = dictator.deadlineFor(other); - - scheduler.schedule(group); - scheduler.run(); + AtomicBoolean dictatorHasRun = new AtomicBoolean(false); + AtomicBoolean dictatorWasPolled = new AtomicBoolean(false); + + Command dictator = + new FunctionalCommand( + () -> {}, + () -> dictatorHasRun.set(true), + interrupted -> {}, + () -> { + dictatorWasPolled.set(true); + return true; + }); + Command other = + new RunCommand( + () -> + assertAll( + () -> assertTrue(dictatorHasRun.get()), + () -> assertTrue(dictatorWasPolled.get()))); - assertAll(() -> assertTrue(dictatorHasRun.get()), () -> assertTrue(dictatorWasPolled.get())); - } + Command group = dictator.deadlineFor(other); + + scheduler.schedule(group); + scheduler.run(); + + assertAll(() -> assertTrue(dictatorHasRun.get()), () -> assertTrue(dictatorWasPolled.get())); } @Test void withDeadlineTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finish = new AtomicBoolean(false); - - Command endsBeforeGroup = Commands.none().withDeadline(Commands.waitUntil(finish::get)); - scheduler.schedule(endsBeforeGroup); - scheduler.run(); - assertTrue(scheduler.isScheduled(endsBeforeGroup)); - finish.set(true); - scheduler.run(); - assertFalse(scheduler.isScheduled(endsBeforeGroup)); - finish.set(false); - - Command endsAfterGroup = Commands.idle().withDeadline(Commands.waitUntil(finish::get)); - scheduler.schedule(endsAfterGroup); - scheduler.run(); - assertTrue(scheduler.isScheduled(endsAfterGroup)); - finish.set(true); - scheduler.run(); - assertFalse(scheduler.isScheduled(endsAfterGroup)); - } + AtomicBoolean finish = new AtomicBoolean(false); + + Command endsBeforeGroup = Commands.none().withDeadline(Commands.waitUntil(finish::get)); + scheduler.schedule(endsBeforeGroup); + scheduler.run(); + assertTrue(scheduler.isScheduled(endsBeforeGroup)); + finish.set(true); + scheduler.run(); + assertFalse(scheduler.isScheduled(endsBeforeGroup)); + finish.set(false); + + Command endsAfterGroup = Commands.idle().withDeadline(Commands.waitUntil(finish::get)); + scheduler.schedule(endsAfterGroup); + scheduler.run(); + assertTrue(scheduler.isScheduled(endsAfterGroup)); + finish.set(true); + scheduler.run(); + assertFalse(scheduler.isScheduled(endsAfterGroup)); } @Test void withDeadlineOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean dictatorHasRun = new AtomicBoolean(false); - AtomicBoolean dictatorWasPolled = new AtomicBoolean(false); - Command dictator = - new FunctionalCommand( - () -> {}, - () -> dictatorHasRun.set(true), - interrupted -> {}, - () -> { - dictatorWasPolled.set(true); - return true; - }); - Command other = - Commands.run( - () -> - assertAll( - () -> assertTrue(dictatorHasRun.get()), - () -> assertTrue(dictatorWasPolled.get()))); - Command group = other.withDeadline(dictator); - scheduler.schedule(group); - scheduler.run(); - assertAll(() -> assertTrue(dictatorHasRun.get()), () -> assertTrue(dictatorWasPolled.get())); - } + AtomicBoolean dictatorHasRun = new AtomicBoolean(false); + AtomicBoolean dictatorWasPolled = new AtomicBoolean(false); + Command dictator = + new FunctionalCommand( + () -> {}, + () -> dictatorHasRun.set(true), + interrupted -> {}, + () -> { + dictatorWasPolled.set(true); + return true; + }); + Command other = + Commands.run( + () -> + assertAll( + () -> assertTrue(dictatorHasRun.get()), + () -> assertTrue(dictatorWasPolled.get()))); + Command group = other.withDeadline(dictator); + scheduler.schedule(group); + scheduler.run(); + assertAll(() -> assertTrue(dictatorHasRun.get()), () -> assertTrue(dictatorWasPolled.get())); } @Test void alongWithTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean finish = new AtomicBoolean(false); + AtomicBoolean finish = new AtomicBoolean(false); - Command command1 = new WaitUntilCommand(finish::get); - Command command2 = new InstantCommand(); + Command command1 = new WaitUntilCommand(finish::get); + Command command2 = new InstantCommand(); - Command group = command1.alongWith(command2); + Command group = command1.alongWith(command2); - scheduler.schedule(group); - scheduler.run(); + scheduler.schedule(group); + scheduler.run(); - assertTrue(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(group)); - finish.set(true); - scheduler.run(); + finish.set(true); + scheduler.run(); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void alongWithOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean firstHasRun = new AtomicBoolean(false); - AtomicBoolean firstWasPolled = new AtomicBoolean(false); - - Command command1 = - new FunctionalCommand( - () -> {}, - () -> firstHasRun.set(true), - interrupted -> {}, - () -> { - firstWasPolled.set(true); - return true; - }); - Command command2 = - new RunCommand( - () -> - assertAll( - () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get()))); - - Command group = command1.alongWith(command2); - - scheduler.schedule(group); - scheduler.run(); + AtomicBoolean firstHasRun = new AtomicBoolean(false); + AtomicBoolean firstWasPolled = new AtomicBoolean(false); + + Command command1 = + new FunctionalCommand( + () -> {}, + () -> firstHasRun.set(true), + interrupted -> {}, + () -> { + firstWasPolled.set(true); + return true; + }); + Command command2 = + new RunCommand( + () -> + assertAll( + () -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get()))); - assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - } + Command group = command1.alongWith(command2); + + scheduler.schedule(group); + scheduler.run(); + + assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); } @Test void raceWithTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Command command1 = new WaitUntilCommand(() -> false); - Command command2 = new InstantCommand(); + Command command1 = new WaitUntilCommand(() -> false); + Command command2 = new InstantCommand(); - Command group = command1.raceWith(command2); + Command group = command1.raceWith(command2); - scheduler.schedule(group); - scheduler.run(); + scheduler.schedule(group); + scheduler.run(); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void raceWithOrderTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean firstHasRun = new AtomicBoolean(false); - AtomicBoolean firstWasPolled = new AtomicBoolean(false); - - Command command1 = - new FunctionalCommand( - () -> {}, - () -> firstHasRun.set(true), - interrupted -> {}, - () -> { - firstWasPolled.set(true); - return true; - }); - Command command2 = - new RunCommand( - () -> { - assertTrue(firstHasRun.get()); - assertTrue(firstWasPolled.get()); - }); - - Command group = command1.raceWith(command2); - - scheduler.schedule(group); - scheduler.run(); - - assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); - } + AtomicBoolean firstHasRun = new AtomicBoolean(false); + AtomicBoolean firstWasPolled = new AtomicBoolean(false); + + Command command1 = + new FunctionalCommand( + () -> {}, + () -> firstHasRun.set(true), + interrupted -> {}, + () -> { + firstWasPolled.set(true); + return true; + }); + Command command2 = + new RunCommand( + () -> { + assertTrue(firstHasRun.get()); + assertTrue(firstWasPolled.get()); + }); + + Command group = command1.raceWith(command2); + + scheduler.schedule(group); + scheduler.run(); + + assertAll(() -> assertTrue(firstHasRun.get()), () -> assertTrue(firstWasPolled.get())); } @Test void unlessTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean hasRun = new AtomicBoolean(false); - AtomicBoolean unlessCondition = new AtomicBoolean(true); + AtomicBoolean hasRun = new AtomicBoolean(false); + AtomicBoolean unlessCondition = new AtomicBoolean(true); - Command command = new InstantCommand(() -> hasRun.set(true)).unless(unlessCondition::get); + Command command = new InstantCommand(() -> hasRun.set(true)).unless(unlessCondition::get); - scheduler.schedule(command); - scheduler.run(); - assertFalse(hasRun.get()); + scheduler.schedule(command); + scheduler.run(); + assertFalse(hasRun.get()); - unlessCondition.set(false); - scheduler.schedule(command); - scheduler.run(); - assertTrue(hasRun.get()); - } + unlessCondition.set(false); + scheduler.schedule(command); + scheduler.run(); + assertTrue(hasRun.get()); } @Test void onlyIfTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean hasRun = new AtomicBoolean(false); - AtomicBoolean onlyIfCondition = new AtomicBoolean(false); + AtomicBoolean hasRun = new AtomicBoolean(false); + AtomicBoolean onlyIfCondition = new AtomicBoolean(false); - Command command = new InstantCommand(() -> hasRun.set(true)).onlyIf(onlyIfCondition::get); + Command command = new InstantCommand(() -> hasRun.set(true)).onlyIf(onlyIfCondition::get); - scheduler.schedule(command); - scheduler.run(); - assertFalse(hasRun.get()); + scheduler.schedule(command); + scheduler.run(); + assertFalse(hasRun.get()); - onlyIfCondition.set(true); - scheduler.schedule(command); - scheduler.run(); - assertTrue(hasRun.get()); - } + onlyIfCondition.set(true); + scheduler.schedule(command); + scheduler.run(); + assertTrue(hasRun.get()); } @Test void finallyDoTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger first = new AtomicInteger(0); - AtomicInteger second = new AtomicInteger(0); - - Command command = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - if (!interrupted) { - first.incrementAndGet(); - } - }, - () -> true) - .finallyDo( - interrupted -> { - if (!interrupted) { - // to differentiate between "didn't run" and "ran before command's `end()` - second.addAndGet(1 + first.get()); - } - }); - - scheduler.schedule(command); - assertEquals(0, first.get()); - assertEquals(0, second.get()); - scheduler.run(); - assertEquals(1, first.get()); - // if `second == 0`, neither of the lambdas ran. - // if `second == 1`, the second lambda ran before the first one - assertEquals(2, second.get()); - } + AtomicInteger first = new AtomicInteger(0); + AtomicInteger second = new AtomicInteger(0); + + Command command = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + if (!interrupted) { + first.incrementAndGet(); + } + }, + () -> true) + .finallyDo( + interrupted -> { + if (!interrupted) { + // to differentiate between "didn't run" and "ran before command's `end()` + second.addAndGet(1 + first.get()); + } + }); + + scheduler.schedule(command); + assertEquals(0, first.get()); + assertEquals(0, second.get()); + scheduler.run(); + assertEquals(1, first.get()); + // if `second == 0`, neither of the lambdas ran. + // if `second == 1`, the second lambda ran before the first one + assertEquals(2, second.get()); } // handleInterruptTest() implicitly tests the interrupt=true branch of finallyDo() @Test void handleInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger first = new AtomicInteger(0); - AtomicInteger second = new AtomicInteger(0); - - Command command = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - if (interrupted) { - first.incrementAndGet(); - } - }, - () -> false) - .handleInterrupt( - () -> { - // to differentiate between "didn't run" and "ran before command's `end()` - second.addAndGet(1 + first.get()); - }); - - scheduler.schedule(command); - scheduler.run(); - assertEquals(0, first.get()); - assertEquals(0, second.get()); - - scheduler.cancel(command); - assertEquals(1, first.get()); - // if `second == 0`, neither of the lambdas ran. - // if `second == 1`, the second lambda ran before the first one - assertEquals(2, second.get()); - } + AtomicInteger first = new AtomicInteger(0); + AtomicInteger second = new AtomicInteger(0); + + Command command = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + if (interrupted) { + first.incrementAndGet(); + } + }, + () -> false) + .handleInterrupt( + () -> { + // to differentiate between "didn't run" and "ran before command's `end()` + second.addAndGet(1 + first.get()); + }); + + scheduler.schedule(command); + scheduler.run(); + assertEquals(0, first.get()); + assertEquals(0, second.get()); + + scheduler.cancel(command); + assertEquals(1, first.get()); + // if `second == 0`, neither of the lambdas ran. + // if `second == 1`, the second lambda ran before the first one + assertEquals(2, second.get()); } @Test 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..c001e32c37d 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 @@ -14,60 +14,54 @@ class CommandRequirementsTest extends CommandTestBase { @Test void requirementInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new SubsystemBase() {}; - MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement); - Command interrupted = interruptedHolder.getMock(); - MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement); - Command interrupter = interrupterHolder.getMock(); + MockCommandHolder interruptedHolder = new MockCommandHolder(true, requirement); + Command interrupted = interruptedHolder.getMock(); + MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement); + Command interrupter = interrupterHolder.getMock(); - scheduler.schedule(interrupted); - scheduler.run(); - scheduler.schedule(interrupter); - scheduler.run(); + scheduler.schedule(interrupted); + scheduler.run(); + scheduler.schedule(interrupter); + scheduler.run(); - verify(interrupted).initialize(); - verify(interrupted).execute(); - verify(interrupted).end(true); + verify(interrupted).initialize(); + verify(interrupted).execute(); + verify(interrupted).end(true); - verify(interrupter).initialize(); - verify(interrupter).execute(); + verify(interrupter).initialize(); + verify(interrupter).execute(); - assertFalse(scheduler.isScheduled(interrupted)); - assertTrue(scheduler.isScheduled(interrupter)); - } + assertFalse(scheduler.isScheduled(interrupted)); + assertTrue(scheduler.isScheduled(interrupter)); } @Test void requirementUninterruptibleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem requirement = new SubsystemBase() {}; + Subsystem requirement = new SubsystemBase() {}; - Command notInterrupted = - new RunCommand(() -> {}, requirement) - .withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming); - MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement); - Command interrupter = interrupterHolder.getMock(); + Command notInterrupted = + new RunCommand(() -> {}, requirement) + .withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming); + MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement); + Command interrupter = interrupterHolder.getMock(); - scheduler.schedule(notInterrupted); - scheduler.schedule(interrupter); + scheduler.schedule(notInterrupted); + scheduler.schedule(interrupter); - assertTrue(scheduler.isScheduled(notInterrupted)); - assertFalse(scheduler.isScheduled(interrupter)); - } + assertTrue(scheduler.isScheduled(notInterrupted)); + assertFalse(scheduler.isScheduled(interrupter)); } @Test void defaultCommandRequirementErrorTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem system = new SubsystemBase() {}; + Subsystem system = new SubsystemBase() {}; - Command missingRequirement = new WaitUntilCommand(() -> false); + Command missingRequirement = new WaitUntilCommand(() -> false); - assertThrows( - IllegalArgumentException.class, - () -> scheduler.setDefaultCommand(system, missingRequirement)); - } + assertThrows( + IllegalArgumentException.class, + () -> scheduler.setDefaultCommand(system, missingRequirement)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java index 793ad95f1e1..3b567cf7c1c 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandScheduleTest.java @@ -18,111 +18,100 @@ class CommandScheduleTest extends CommandTestBase { @Test void instantScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(true); - holder.setFinished(true); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(true); + holder.setFinished(true); + Command mockCommand = holder.getMock(); - scheduler.schedule(mockCommand); - assertTrue(scheduler.isScheduled(mockCommand)); - verify(mockCommand).initialize(); + scheduler.schedule(mockCommand); + assertTrue(scheduler.isScheduled(mockCommand)); + verify(mockCommand).initialize(); - scheduler.run(); + scheduler.run(); - verify(mockCommand).execute(); - verify(mockCommand).end(false); + verify(mockCommand).execute(); + verify(mockCommand).end(false); - assertFalse(scheduler.isScheduled(mockCommand)); - } + assertFalse(scheduler.isScheduled(mockCommand)); } @Test void singleIterationScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(true); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(true); + Command mockCommand = holder.getMock(); - scheduler.schedule(mockCommand); + scheduler.schedule(mockCommand); - assertTrue(scheduler.isScheduled(mockCommand)); + assertTrue(scheduler.isScheduled(mockCommand)); - scheduler.run(); - holder.setFinished(true); - scheduler.run(); + scheduler.run(); + holder.setFinished(true); + scheduler.run(); - verify(mockCommand).initialize(); - verify(mockCommand, times(2)).execute(); - verify(mockCommand).end(false); + verify(mockCommand).initialize(); + verify(mockCommand, times(2)).execute(); + verify(mockCommand).end(false); - assertFalse(scheduler.isScheduled(mockCommand)); - } + assertFalse(scheduler.isScheduled(mockCommand)); } @Test void multiScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - - scheduler.schedule(command1, command2, command3); - assertTrue(scheduler.isScheduled(command1, command2, command3)); - scheduler.run(); - assertTrue(scheduler.isScheduled(command1, command2, command3)); - - command1Holder.setFinished(true); - scheduler.run(); - assertTrue(scheduler.isScheduled(command2, command3)); - assertFalse(scheduler.isScheduled(command1)); - - command2Holder.setFinished(true); - scheduler.run(); - assertTrue(scheduler.isScheduled(command3)); - assertFalse(scheduler.isScheduled(command1, command2)); - - command3Holder.setFinished(true); - scheduler.run(); - assertFalse(scheduler.isScheduled(command1, command2, command3)); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + + scheduler.schedule(command1, command2, command3); + assertTrue(scheduler.isScheduled(command1, command2, command3)); + scheduler.run(); + assertTrue(scheduler.isScheduled(command1, command2, command3)); + + command1Holder.setFinished(true); + scheduler.run(); + assertTrue(scheduler.isScheduled(command2, command3)); + assertFalse(scheduler.isScheduled(command1)); + + command2Holder.setFinished(true); + scheduler.run(); + assertTrue(scheduler.isScheduled(command3)); + assertFalse(scheduler.isScheduled(command1, command2)); + + command3Holder.setFinished(true); + scheduler.run(); + assertFalse(scheduler.isScheduled(command1, command2, command3)); } @Test void schedulerCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(true); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(true); + Command mockCommand = holder.getMock(); - scheduler.schedule(mockCommand); + scheduler.schedule(mockCommand); - scheduler.run(); - scheduler.cancel(mockCommand); - scheduler.run(); + scheduler.run(); + scheduler.cancel(mockCommand); + scheduler.run(); - verify(mockCommand).execute(); - verify(mockCommand).end(true); - verify(mockCommand, never()).end(false); + verify(mockCommand).execute(); + verify(mockCommand).end(true); + verify(mockCommand, never()).end(false); - assertFalse(scheduler.isScheduled(mockCommand)); - } + assertFalse(scheduler.isScheduled(mockCommand)); } @Test void notScheduledCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(true); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(true); + Command mockCommand = holder.getMock(); - assertDoesNotThrow(() -> scheduler.cancel(mockCommand)); - } + assertDoesNotThrow(() -> scheduler.cancel(mockCommand)); } @Test void smartDashboardCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler(); - var inst = NetworkTableInstance.create()) { + try (var inst = NetworkTableInstance.create()) { SmartDashboard.setNetworkTableInstance(inst); SmartDashboard.putData("Scheduler", scheduler); SmartDashboard.updateValues(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java index c89ed7f7f3e..f99825dc838 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandSendableButtonTest.java @@ -38,7 +38,7 @@ void setUp() { @Test void trueAndNotScheduledSchedules() { // Not scheduled and true -> scheduled - CommandScheduler.getInstance().run(); + scheduler.run(); SmartDashboard.updateValues(); assertFalse(m_command.isScheduled()); assertEquals(0, m_schedule.get()); @@ -46,7 +46,7 @@ void trueAndNotScheduledSchedules() { m_publish.set(true); SmartDashboard.updateValues(); - CommandScheduler.getInstance().run(); + scheduler.run(); assertTrue(m_command.isScheduled()); assertEquals(1, m_schedule.get()); assertEquals(0, m_cancel.get()); @@ -56,7 +56,7 @@ void trueAndNotScheduledSchedules() { void trueAndScheduledNoOp() { // Scheduled and true -> no-op m_command.schedule(); - CommandScheduler.getInstance().run(); + scheduler.run(); SmartDashboard.updateValues(); assertTrue(m_command.isScheduled()); assertEquals(1, m_schedule.get()); @@ -64,7 +64,7 @@ void trueAndScheduledNoOp() { m_publish.set(true); SmartDashboard.updateValues(); - CommandScheduler.getInstance().run(); + scheduler.run(); assertTrue(m_command.isScheduled()); assertEquals(1, m_schedule.get()); assertEquals(0, m_cancel.get()); @@ -73,7 +73,7 @@ void trueAndScheduledNoOp() { @Test void falseAndNotScheduledNoOp() { // Not scheduled and false -> no-op - CommandScheduler.getInstance().run(); + scheduler.run(); SmartDashboard.updateValues(); assertFalse(m_command.isScheduled()); assertEquals(0, m_schedule.get()); @@ -81,7 +81,7 @@ void falseAndNotScheduledNoOp() { m_publish.set(false); SmartDashboard.updateValues(); - CommandScheduler.getInstance().run(); + scheduler.run(); assertFalse(m_command.isScheduled()); assertEquals(0, m_schedule.get()); assertEquals(0, m_cancel.get()); @@ -91,7 +91,7 @@ void falseAndNotScheduledNoOp() { void falseAndScheduledCancel() { // Scheduled and false -> cancel m_command.schedule(); - CommandScheduler.getInstance().run(); + scheduler.run(); SmartDashboard.updateValues(); assertTrue(m_command.isScheduled()); assertEquals(1, m_schedule.get()); @@ -99,7 +99,7 @@ void falseAndScheduledCancel() { m_publish.set(false); SmartDashboard.updateValues(); - CommandScheduler.getInstance().run(); + scheduler.run(); assertFalse(m_command.isScheduled()); assertEquals(1, m_schedule.get()); assertEquals(1, m_cancel.get()); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java index 13f65977385..a6db3fd180b 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/CommandTestBase.java @@ -17,13 +17,13 @@ public class CommandTestBase { protected CommandTestBase() {} + @SuppressWarnings("PMD.MemberName") + protected CommandScheduler scheduler; + @BeforeEach void commandSetup() { - CommandScheduler.getInstance().cancelAll(); - CommandScheduler.getInstance().enable(); - CommandScheduler.getInstance().getActiveButtonLoop().clear(); - CommandScheduler.getInstance().clearComposedCommands(); - CommandScheduler.getInstance().unregisterAllSubsystems(); + CommandScheduler.resetInstance(); + scheduler = CommandScheduler.getInstance(); setDSEnabled(true); } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ConditionalCommandTest.java index 4659f0ec3d4..2b5b3d38a5c 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 @@ -21,27 +21,24 @@ class ConditionalCommandTest extends CommandTestBase { @Test void conditionalCommandTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - command1Holder.setFinished(true); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - - ConditionalCommand conditionalCommand = - new ConditionalCommand(command1, command2, () -> true); - - scheduler.schedule(conditionalCommand); - scheduler.run(); - - verify(command1).initialize(); - verify(command1).execute(); - verify(command1).end(false); - - verify(command2, never()).initialize(); - verify(command2, never()).execute(); - verify(command2, never()).end(false); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + command1Holder.setFinished(true); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + + ConditionalCommand conditionalCommand = new ConditionalCommand(command1, command2, () -> true); + + scheduler.schedule(conditionalCommand); + scheduler.run(); + + verify(command1).initialize(); + verify(command1).execute(); + verify(command1).end(false); + + verify(command2, never()).initialize(); + verify(command2, never()).execute(); + verify(command2, never()).end(false); } @Test @@ -50,23 +47,20 @@ void conditionalCommandRequirementTest() { Subsystem system2 = new SubsystemBase() {}; Subsystem system3 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); - ConditionalCommand conditionalCommand = - new ConditionalCommand(command1, command2, () -> true); + ConditionalCommand conditionalCommand = new ConditionalCommand(command1, command2, () -> true); - scheduler.schedule(conditionalCommand); - scheduler.schedule(new InstantCommand(() -> {}, system3)); + scheduler.schedule(conditionalCommand); + scheduler.schedule(new InstantCommand(() -> {}, system3)); - assertFalse(scheduler.isScheduled(conditionalCommand)); + assertFalse(scheduler.isScheduled(conditionalCommand)); - verify(command1).end(true); - verify(command2, never()).end(true); - } + verify(command1).end(true); + verify(command2, never()).end(true); } static Stream interruptible() { diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java index 23ae47d6489..fc4ce0a5064 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DefaultCommandTest.java @@ -13,68 +13,62 @@ class DefaultCommandTest extends CommandTestBase { @Test void defaultCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new SubsystemBase() {}; - MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); - Command defaultCommand = defaultHolder.getMock(); + MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); + Command defaultCommand = defaultHolder.getMock(); - scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); - scheduler.run(); + scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); + scheduler.run(); - assertTrue(scheduler.isScheduled(defaultCommand)); - } + assertTrue(scheduler.isScheduled(defaultCommand)); } @Test void defaultCommandInterruptResumeTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new SubsystemBase() {}; - MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); - Command defaultCommand = defaultHolder.getMock(); - MockCommandHolder interrupterHolder = new MockCommandHolder(true, hasDefaultCommand); - Command interrupter = interrupterHolder.getMock(); + MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand); + Command defaultCommand = defaultHolder.getMock(); + MockCommandHolder interrupterHolder = new MockCommandHolder(true, hasDefaultCommand); + Command interrupter = interrupterHolder.getMock(); - scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); - scheduler.run(); - scheduler.schedule(interrupter); + scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); + scheduler.run(); + scheduler.schedule(interrupter); - assertFalse(scheduler.isScheduled(defaultCommand)); - assertTrue(scheduler.isScheduled(interrupter)); + assertFalse(scheduler.isScheduled(defaultCommand)); + assertTrue(scheduler.isScheduled(interrupter)); - scheduler.cancel(interrupter); - scheduler.run(); + scheduler.cancel(interrupter); + scheduler.run(); - assertTrue(scheduler.isScheduled(defaultCommand)); - assertFalse(scheduler.isScheduled(interrupter)); - } + assertTrue(scheduler.isScheduled(defaultCommand)); + assertFalse(scheduler.isScheduled(interrupter)); } @Test void defaultCommandDisableResumeTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Subsystem hasDefaultCommand = new SubsystemBase() {}; + Subsystem hasDefaultCommand = new SubsystemBase() {}; - MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand); - Command defaultCommand = defaultHolder.getMock(); + MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand); + Command defaultCommand = defaultHolder.getMock(); - scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); - scheduler.run(); + scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand); + scheduler.run(); - assertTrue(scheduler.isScheduled(defaultCommand)); + assertTrue(scheduler.isScheduled(defaultCommand)); - setDSEnabled(false); - scheduler.run(); + setDSEnabled(false); + scheduler.run(); - assertFalse(scheduler.isScheduled(defaultCommand)); + assertFalse(scheduler.isScheduled(defaultCommand)); - setDSEnabled(true); - scheduler.run(); + setDSEnabled(true); + scheduler.run(); - assertTrue(scheduler.isScheduled(defaultCommand)); + assertTrue(scheduler.isScheduled(defaultCommand)); - verify(defaultCommand).end(true); - } + verify(defaultCommand).end(true); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java index 259ba0fdcef..3e3a99bc027 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/DeferredCommandTest.java @@ -47,20 +47,18 @@ void deferredFunctionsTest(boolean interrupted) { @SuppressWarnings("unchecked") @Test void deferredSupplierOnlyCalledDuringInit() { - try (CommandScheduler scheduler = new CommandScheduler()) { - Supplier supplier = (Supplier) mock(Supplier.class); - when(supplier.get()).thenReturn(Commands.none(), Commands.none()); + Supplier supplier = (Supplier) mock(Supplier.class); + when(supplier.get()).thenReturn(Commands.none(), Commands.none()); - DeferredCommand command = new DeferredCommand(supplier, Set.of()); - verify(supplier, never()).get(); + DeferredCommand command = new DeferredCommand(supplier, Set.of()); + verify(supplier, never()).get(); - scheduler.schedule(command); - verify(supplier, only()).get(); - scheduler.run(); + scheduler.schedule(command); + verify(supplier, only()).get(); + scheduler.run(); - scheduler.schedule(command); - verify(supplier, times(2)).get(); - } + scheduler.schedule(command); + verify(supplier, times(2)).get(); } @Test diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java index f983e8a667d..8e90080c79b 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/FunctionalCommandTest.java @@ -13,32 +13,30 @@ class FunctionalCommandTest extends CommandTestBase { @Test void functionalCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean cond1 = new AtomicBoolean(); - AtomicBoolean cond2 = new AtomicBoolean(); - AtomicBoolean cond3 = new AtomicBoolean(); - AtomicBoolean cond4 = new AtomicBoolean(); + AtomicBoolean cond1 = new AtomicBoolean(); + AtomicBoolean cond2 = new AtomicBoolean(); + AtomicBoolean cond3 = new AtomicBoolean(); + AtomicBoolean cond4 = new AtomicBoolean(); - FunctionalCommand command = - new FunctionalCommand( - () -> cond1.set(true), - () -> cond2.set(true), - interrupted -> cond3.set(true), - cond4::get); + FunctionalCommand command = + new FunctionalCommand( + () -> cond1.set(true), + () -> cond2.set(true), + interrupted -> cond3.set(true), + cond4::get); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertTrue(scheduler.isScheduled(command)); + assertTrue(scheduler.isScheduled(command)); - cond4.set(true); + cond4.set(true); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - assertTrue(cond1.get()); - assertTrue(cond2.get()); - assertTrue(cond3.get()); - } + assertFalse(scheduler.isScheduled(command)); + assertTrue(cond1.get()); + assertTrue(cond2.get()); + assertTrue(cond3.get()); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java index 813a44adf5f..79ab5e3b0bb 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/InstantCommandTest.java @@ -13,16 +13,14 @@ class InstantCommandTest extends CommandTestBase { @Test void instantCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean cond = new AtomicBoolean(); + AtomicBoolean cond = new AtomicBoolean(); - InstantCommand command = new InstantCommand(() -> cond.set(true)); + InstantCommand command = new InstantCommand(() -> cond.set(true)); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertTrue(cond.get()); - assertFalse(scheduler.isScheduled(command)); - } + assertTrue(cond.get()); + assertFalse(scheduler.isScheduled(command)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java index 4928cb10149..65faf9ff490 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/NotifierCommandTest.java @@ -29,18 +29,16 @@ void cleanup() { @Test @ResourceLock("timing") void notifierCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(0); + AtomicInteger counter = new AtomicInteger(0); - NotifierCommand command = new NotifierCommand(counter::incrementAndGet, 0.01); + NotifierCommand command = new NotifierCommand(counter::incrementAndGet, 0.01); - scheduler.schedule(command); - for (int i = 0; i < 5; ++i) { - SimHooks.stepTiming(0.005); - } - scheduler.cancel(command); - - assertEquals(2, counter.get()); + scheduler.schedule(command); + for (int i = 0; i < 5; ++i) { + SimHooks.stepTiming(0.005); } + scheduler.cancel(command); + + assertEquals(2, counter.get()); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java index a837baac8aa..31431ed6ca3 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/ParallelCommandGroupTest.java @@ -17,74 +17,68 @@ class ParallelCommandGroupTest extends MultiCompositionTestBase { @Test void parallelGroupScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelCommandGroup(command1, command2); + Command group = new ParallelCommandGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - verify(command1).initialize(); - verify(command2).initialize(); + verify(command1).initialize(); + verify(command2).initialize(); - command1Holder.setFinished(true); - scheduler.run(); - command2Holder.setFinished(true); - scheduler.run(); + command1Holder.setFinished(true); + scheduler.run(); + command2Holder.setFinished(true); + scheduler.run(); - verify(command1).execute(); - verify(command1).end(false); - verify(command2, times(2)).execute(); - verify(command2).end(false); + verify(command1).execute(); + verify(command1).end(false); + verify(command2, times(2)).execute(); + verify(command2).end(false); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void parallelGroupInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelCommandGroup(command1, command2); + Command group = new ParallelCommandGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - command1Holder.setFinished(true); - scheduler.run(); - scheduler.run(); - scheduler.cancel(group); + command1Holder.setFinished(true); + scheduler.run(); + scheduler.run(); + scheduler.cancel(group); - verify(command1).execute(); - verify(command1).end(false); - verify(command1, never()).end(true); + verify(command1).execute(); + verify(command1).end(false); + verify(command1, never()).end(true); - verify(command2, times(2)).execute(); - verify(command2, never()).end(false); - verify(command2).end(true); + verify(command2, times(2)).execute(); + verify(command2, never()).end(false); + verify(command2).end(true); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void notScheduledCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelCommandGroup(command1, command2); + Command group = new ParallelCommandGroup(command1, command2); - assertDoesNotThrow(() -> scheduler.cancel(group)); - } + assertDoesNotThrow(() -> scheduler.cancel(group)); } @Test @@ -94,22 +88,20 @@ void parallelGroupRequirementTest() { Subsystem system3 = new SubsystemBase() {}; Subsystem system4 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); - Command command3 = command3Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); + Command command3 = command3Holder.getMock(); - Command group = new ParallelCommandGroup(command1, command2); + Command group = new ParallelCommandGroup(command1, command2); - scheduler.schedule(group); - scheduler.schedule(command3); + scheduler.schedule(group); + scheduler.schedule(command3); - assertFalse(scheduler.isScheduled(group)); - assertTrue(scheduler.isScheduled(command3)); - } + assertFalse(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(command3)); } @Test 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..952dcbc6ae4 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 @@ -18,71 +18,67 @@ class ParallelDeadlineGroupTest extends MultiCompositionTestBase { @Test void parallelDeadlineScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - command2Holder.setFinished(true); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - - Command group = new ParallelDeadlineGroup(command1, command2, command3); - - scheduler.schedule(group); - scheduler.run(); - - assertTrue(scheduler.isScheduled(group)); - - command1Holder.setFinished(true); - scheduler.run(); - - assertFalse(scheduler.isScheduled(group)); - - verify(command2).initialize(); - verify(command2).execute(); - verify(command2).end(false); - verify(command2, never()).end(true); - - verify(command1).initialize(); - verify(command1, times(2)).execute(); - verify(command1).end(false); - verify(command1, never()).end(true); - - verify(command3).initialize(); - verify(command3, times(2)).execute(); - verify(command3, never()).end(false); - verify(command3).end(true); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + command2Holder.setFinished(true); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + + Command group = new ParallelDeadlineGroup(command1, command2, command3); + + scheduler.schedule(group); + scheduler.run(); + + assertTrue(scheduler.isScheduled(group)); + + command1Holder.setFinished(true); + scheduler.run(); + + assertFalse(scheduler.isScheduled(group)); + + verify(command2).initialize(); + verify(command2).execute(); + verify(command2).end(false); + verify(command2, never()).end(true); + + verify(command1).initialize(); + verify(command1, times(2)).execute(); + verify(command1).end(false); + verify(command1, never()).end(true); + + verify(command3).initialize(); + verify(command3, times(2)).execute(); + verify(command3, never()).end(false); + verify(command3).end(true); } @Test void parallelDeadlineInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - command2Holder.setFinished(true); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + command2Holder.setFinished(true); - Command group = new ParallelDeadlineGroup(command1, command2); + Command group = new ParallelDeadlineGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - scheduler.run(); - scheduler.run(); - scheduler.cancel(group); + scheduler.run(); + scheduler.run(); + scheduler.cancel(group); - verify(command1, times(2)).execute(); - verify(command1, never()).end(false); - verify(command1).end(true); + verify(command1, times(2)).execute(); + verify(command1, never()).end(false); + verify(command1).end(true); - verify(command2).execute(); - verify(command2).end(false); - verify(command2, never()).end(true); + verify(command2).execute(); + verify(command2).end(false); + verify(command2, never()).end(true); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test @@ -92,22 +88,20 @@ void parallelDeadlineRequirementTest() { Subsystem system3 = new SubsystemBase() {}; Subsystem system4 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); - Command command3 = command3Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); + Command command3 = command3Holder.getMock(); - Command group = new ParallelDeadlineGroup(command1, command2); + Command group = new ParallelDeadlineGroup(command1, command2); - scheduler.schedule(group); - scheduler.schedule(command3); + scheduler.schedule(group); + scheduler.schedule(command3); - assertFalse(scheduler.isScheduled(group)); - assertTrue(scheduler.isScheduled(command3)); - } + assertFalse(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(command3)); } @Test 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..62969e55548 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 @@ -19,74 +19,68 @@ class ParallelRaceGroupTest extends MultiCompositionTestBase { @Test void parallelRaceScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelRaceGroup(command1, command2); + Command group = new ParallelRaceGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - verify(command1).initialize(); - verify(command2).initialize(); + verify(command1).initialize(); + verify(command2).initialize(); - command1Holder.setFinished(true); - scheduler.run(); - command2Holder.setFinished(true); - scheduler.run(); + command1Holder.setFinished(true); + scheduler.run(); + command2Holder.setFinished(true); + scheduler.run(); - verify(command1).execute(); - verify(command1).end(false); - verify(command2).execute(); - verify(command2).end(true); - verify(command2, never()).end(false); + verify(command1).execute(); + verify(command1).end(false); + verify(command2).execute(); + verify(command2).end(true); + verify(command2, never()).end(false); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void parallelRaceInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelRaceGroup(command1, command2); + Command group = new ParallelRaceGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - scheduler.run(); - scheduler.run(); - scheduler.cancel(group); + scheduler.run(); + scheduler.run(); + scheduler.cancel(group); - verify(command1, times(2)).execute(); - verify(command1, never()).end(false); - verify(command1).end(true); + verify(command1, times(2)).execute(); + verify(command1, never()).end(false); + verify(command1).end(true); - verify(command2, times(2)).execute(); - verify(command2, never()).end(false); - verify(command2).end(true); + verify(command2, times(2)).execute(); + verify(command2, never()).end(false); + verify(command2).end(true); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void notScheduledCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelRaceGroup(command1, command2); + Command group = new ParallelRaceGroup(command1, command2); - assertDoesNotThrow(() -> scheduler.cancel(group)); - } + assertDoesNotThrow(() -> scheduler.cancel(group)); } @Test @@ -96,22 +90,20 @@ void parallelRaceRequirementTest() { Subsystem system3 = new SubsystemBase() {}; Subsystem system4 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); - Command command3 = command3Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); + Command command3 = command3Holder.getMock(); - Command group = new ParallelRaceGroup(command1, command2); + Command group = new ParallelRaceGroup(command1, command2); - scheduler.schedule(group); - scheduler.schedule(command3); + scheduler.schedule(group); + scheduler.schedule(command3); - assertFalse(scheduler.isScheduled(group)); - assertTrue(scheduler.isScheduled(command3)); - } + assertFalse(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(command3)); } @Test @@ -145,62 +137,58 @@ void parallelRaceOnlyCallsEndOnceTest() { assertNotNull(command3); Command group2 = new ParallelRaceGroup(group1, command3); - try (CommandScheduler scheduler = new CommandScheduler()) { - scheduler.schedule(group2); - scheduler.run(); - command1Holder.setFinished(true); - scheduler.run(); - command2Holder.setFinished(true); - // at this point the sequential group should be done - assertDoesNotThrow(scheduler::run); - assertFalse(scheduler.isScheduled(group2)); - } + scheduler.schedule(group2); + scheduler.run(); + command1Holder.setFinished(true); + scheduler.run(); + command2Holder.setFinished(true); + // at this point the sequential group should be done + assertDoesNotThrow(scheduler::run); + assertFalse(scheduler.isScheduled(group2)); } @Test void parallelRaceScheduleTwiceTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new ParallelRaceGroup(command1, command2); + Command group = new ParallelRaceGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - verify(command1).initialize(); - verify(command2).initialize(); + verify(command1).initialize(); + verify(command2).initialize(); - command1Holder.setFinished(true); - scheduler.run(); - command2Holder.setFinished(true); - scheduler.run(); + command1Holder.setFinished(true); + scheduler.run(); + command2Holder.setFinished(true); + scheduler.run(); - verify(command1).execute(); - verify(command1).end(false); - verify(command2).execute(); - verify(command2).end(true); - verify(command2, never()).end(false); + verify(command1).execute(); + verify(command1).end(false); + verify(command2).execute(); + verify(command2).end(true); + verify(command2, never()).end(false); - assertFalse(scheduler.isScheduled(group)); + assertFalse(scheduler.isScheduled(group)); - reset(command1); - reset(command2); + reset(command1); + reset(command2); - scheduler.schedule(group); + scheduler.schedule(group); - verify(command1).initialize(); - verify(command2).initialize(); + verify(command1).initialize(); + verify(command2).initialize(); - scheduler.run(); - scheduler.run(); - assertTrue(scheduler.isScheduled(group)); - command2Holder.setFinished(true); - scheduler.run(); + scheduler.run(); + scheduler.run(); + assertTrue(scheduler.isScheduled(group)); + command2Holder.setFinished(true); + scheduler.run(); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Override diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java index 6abd94b9872..b18c3e4c79a 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/PrintCommandTest.java @@ -14,21 +14,19 @@ class PrintCommandTest extends CommandTestBase { @Test void printCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - final PrintStream originalOut = System.out; - ByteArrayOutputStream testOut = new ByteArrayOutputStream(); - System.setOut(new PrintStream(testOut)); - try { - PrintCommand command = new PrintCommand("Test!"); + final PrintStream originalOut = System.out; + ByteArrayOutputStream testOut = new ByteArrayOutputStream(); + System.setOut(new PrintStream(testOut)); + try { + PrintCommand command = new PrintCommand("Test!"); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - assertEquals(testOut.toString(), "Test!" + System.lineSeparator()); - } finally { - System.setOut(originalOut); - } + assertFalse(scheduler.isScheduled(command)); + assertEquals(testOut.toString(), "Test!" + System.lineSeparator()); + } finally { + System.setOut(originalOut); } } } 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..3308a0da3c9 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 @@ -14,36 +14,32 @@ class ProxyCommandTest extends CommandTestBase { @Test void proxyCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); - ProxyCommand scheduleCommand = new ProxyCommand(command1); + ProxyCommand scheduleCommand = new ProxyCommand(command1); - scheduler.schedule(scheduleCommand); + scheduler.schedule(scheduleCommand); - verify(command1).schedule(); - } + verify(command1).schedule(); } @Test void proxyCommandEndTest() { - try (CommandScheduler scheduler = CommandScheduler.getInstance()) { - AtomicBoolean cond = new AtomicBoolean(); + AtomicBoolean cond = new AtomicBoolean(); - WaitUntilCommand command = new WaitUntilCommand(cond::get); + WaitUntilCommand command = new WaitUntilCommand(cond::get); - ProxyCommand scheduleCommand = new ProxyCommand(command); + ProxyCommand scheduleCommand = new ProxyCommand(command); - scheduler.schedule(scheduleCommand); + scheduler.schedule(scheduleCommand); - scheduler.run(); - assertTrue(scheduler.isScheduled(scheduleCommand)); + scheduler.run(); + assertTrue(scheduler.isScheduled(scheduleCommand)); - cond.set(true); - scheduler.run(); - scheduler.run(); - assertFalse(scheduler.isScheduled(scheduleCommand)); - } + cond.set(true); + scheduler.run(); + scheduler.run(); + assertFalse(scheduler.isScheduled(scheduleCommand)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java index 2aaecc6d933..2b5aafb734b 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RepeatCommandTest.java @@ -13,69 +13,67 @@ class RepeatCommandTest extends SingleCompositionTestBase { @Test void callsMethodsCorrectly() { - try (CommandScheduler scheduler = new CommandScheduler()) { - var initCounter = new AtomicInteger(0); - var exeCounter = new AtomicInteger(0); - var isFinishedCounter = new AtomicInteger(0); - var endCounter = new AtomicInteger(0); - var isFinishedHook = new AtomicBoolean(false); + var initCounter = new AtomicInteger(0); + var exeCounter = new AtomicInteger(0); + var isFinishedCounter = new AtomicInteger(0); + var endCounter = new AtomicInteger(0); + var isFinishedHook = new AtomicBoolean(false); - final var command = - new FunctionalCommand( - initCounter::incrementAndGet, - exeCounter::incrementAndGet, - interrupted -> endCounter.incrementAndGet(), - () -> { - isFinishedCounter.incrementAndGet(); - return isFinishedHook.get(); - }) - .repeatedly(); + final var command = + new FunctionalCommand( + initCounter::incrementAndGet, + exeCounter::incrementAndGet, + interrupted -> endCounter.incrementAndGet(), + () -> { + isFinishedCounter.incrementAndGet(); + return isFinishedHook.get(); + }) + .repeatedly(); - assertEquals(0, initCounter.get()); - assertEquals(0, exeCounter.get()); - assertEquals(0, isFinishedCounter.get()); - assertEquals(0, endCounter.get()); + assertEquals(0, initCounter.get()); + assertEquals(0, exeCounter.get()); + assertEquals(0, isFinishedCounter.get()); + assertEquals(0, endCounter.get()); - scheduler.schedule(command); - assertEquals(1, initCounter.get()); - assertEquals(0, exeCounter.get()); - assertEquals(0, isFinishedCounter.get()); - assertEquals(0, endCounter.get()); + scheduler.schedule(command); + assertEquals(1, initCounter.get()); + assertEquals(0, exeCounter.get()); + assertEquals(0, isFinishedCounter.get()); + assertEquals(0, endCounter.get()); - isFinishedHook.set(false); - scheduler.run(); - assertEquals(1, initCounter.get()); - assertEquals(1, exeCounter.get()); - assertEquals(1, isFinishedCounter.get()); - assertEquals(0, endCounter.get()); + isFinishedHook.set(false); + scheduler.run(); + assertEquals(1, initCounter.get()); + assertEquals(1, exeCounter.get()); + assertEquals(1, isFinishedCounter.get()); + assertEquals(0, endCounter.get()); - isFinishedHook.set(true); - scheduler.run(); - assertEquals(1, initCounter.get()); - assertEquals(2, exeCounter.get()); - assertEquals(2, isFinishedCounter.get()); - assertEquals(1, endCounter.get()); + isFinishedHook.set(true); + scheduler.run(); + assertEquals(1, initCounter.get()); + assertEquals(2, exeCounter.get()); + assertEquals(2, isFinishedCounter.get()); + assertEquals(1, endCounter.get()); - isFinishedHook.set(false); - scheduler.run(); - assertEquals(2, initCounter.get()); - assertEquals(3, exeCounter.get()); - assertEquals(3, isFinishedCounter.get()); - assertEquals(1, endCounter.get()); + isFinishedHook.set(false); + scheduler.run(); + assertEquals(2, initCounter.get()); + assertEquals(3, exeCounter.get()); + assertEquals(3, isFinishedCounter.get()); + assertEquals(1, endCounter.get()); - isFinishedHook.set(true); - scheduler.run(); - assertEquals(2, initCounter.get()); - assertEquals(4, exeCounter.get()); - assertEquals(4, isFinishedCounter.get()); - assertEquals(2, endCounter.get()); + isFinishedHook.set(true); + scheduler.run(); + assertEquals(2, initCounter.get()); + assertEquals(4, exeCounter.get()); + assertEquals(4, isFinishedCounter.get()); + assertEquals(2, endCounter.get()); - scheduler.cancel(command); - assertEquals(2, initCounter.get()); - assertEquals(4, exeCounter.get()); - assertEquals(4, isFinishedCounter.get()); - assertEquals(2, endCounter.get()); - } + scheduler.cancel(command); + assertEquals(2, initCounter.get()); + assertEquals(4, exeCounter.get()); + assertEquals(4, isFinishedCounter.get()); + assertEquals(2, endCounter.get()); } @Override diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java index a248810e330..90be5c60d67 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RobotDisabledCommandTest.java @@ -14,94 +14,86 @@ class RobotDisabledCommandTest extends CommandTestBase { @Test void robotDisabledCommandCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(false); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(false); + Command mockCommand = holder.getMock(); - scheduler.schedule(mockCommand); + scheduler.schedule(mockCommand); - assertTrue(scheduler.isScheduled(mockCommand)); + assertTrue(scheduler.isScheduled(mockCommand)); - setDSEnabled(false); + setDSEnabled(false); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(mockCommand)); + assertFalse(scheduler.isScheduled(mockCommand)); - setDSEnabled(true); - } + setDSEnabled(true); } @Test void runWhenDisabledTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder holder = new MockCommandHolder(true); - Command mockCommand = holder.getMock(); + MockCommandHolder holder = new MockCommandHolder(true); + Command mockCommand = holder.getMock(); - scheduler.schedule(mockCommand); + scheduler.schedule(mockCommand); - assertTrue(scheduler.isScheduled(mockCommand)); + assertTrue(scheduler.isScheduled(mockCommand)); - setDSEnabled(false); + setDSEnabled(false); - scheduler.run(); + scheduler.run(); - assertTrue(scheduler.isScheduled(mockCommand)); - } + assertTrue(scheduler.isScheduled(mockCommand)); } @Test void sequentialGroupRunWhenDisabledTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - MockCommandHolder command4Holder = new MockCommandHolder(false); - Command command4 = command4Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + MockCommandHolder command4Holder = new MockCommandHolder(false); + Command command4 = command4Holder.getMock(); - Command runWhenDisabled = new SequentialCommandGroup(command1, command2); - Command dontRunWhenDisabled = new SequentialCommandGroup(command3, command4); + Command runWhenDisabled = new SequentialCommandGroup(command1, command2); + Command dontRunWhenDisabled = new SequentialCommandGroup(command3, command4); - scheduler.schedule(runWhenDisabled); - scheduler.schedule(dontRunWhenDisabled); + scheduler.schedule(runWhenDisabled); + scheduler.schedule(dontRunWhenDisabled); - setDSEnabled(false); + setDSEnabled(false); - scheduler.run(); + scheduler.run(); - assertTrue(scheduler.isScheduled(runWhenDisabled)); - assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - } + assertTrue(scheduler.isScheduled(runWhenDisabled)); + assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); } @Test void parallelGroupRunWhenDisabledTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - MockCommandHolder command4Holder = new MockCommandHolder(false); - Command command4 = command4Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + MockCommandHolder command4Holder = new MockCommandHolder(false); + Command command4 = command4Holder.getMock(); - Command runWhenDisabled = new ParallelCommandGroup(command1, command2); - Command dontRunWhenDisabled = new ParallelCommandGroup(command3, command4); + Command runWhenDisabled = new ParallelCommandGroup(command1, command2); + Command dontRunWhenDisabled = new ParallelCommandGroup(command3, command4); - scheduler.schedule(runWhenDisabled); - scheduler.schedule(dontRunWhenDisabled); + scheduler.schedule(runWhenDisabled); + scheduler.schedule(dontRunWhenDisabled); - setDSEnabled(false); + setDSEnabled(false); - scheduler.run(); + scheduler.run(); - assertTrue(scheduler.isScheduled(runWhenDisabled)); - assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - } + assertTrue(scheduler.isScheduled(runWhenDisabled)); + assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); } @Test @@ -117,15 +109,13 @@ void conditionalRunWhenDisabledTest() { MockCommandHolder command4Holder = new MockCommandHolder(false); Command command4 = command4Holder.getMock(); - try (CommandScheduler scheduler = new CommandScheduler()) { - Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true); - Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true); + Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true); + Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true); - scheduler.schedule(runWhenDisabled, dontRunWhenDisabled); + scheduler.schedule(runWhenDisabled, dontRunWhenDisabled); - assertTrue(scheduler.isScheduled(runWhenDisabled)); - assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - } + assertTrue(scheduler.isScheduled(runWhenDisabled)); + assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); } @Test @@ -144,12 +134,10 @@ void selectRunWhenDisabledTest() { Command runWhenDisabled = new SelectCommand<>(Map.of(1, command1, 2, command2), () -> 1); Command dontRunWhenDisabled = new SelectCommand<>(Map.of(1, command3, 2, command4), () -> 1); - try (CommandScheduler scheduler = new CommandScheduler()) { - scheduler.schedule(runWhenDisabled, dontRunWhenDisabled); + scheduler.schedule(runWhenDisabled, dontRunWhenDisabled); - assertTrue(scheduler.isScheduled(runWhenDisabled)); - assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); - } + assertTrue(scheduler.isScheduled(runWhenDisabled)); + assertFalse(scheduler.isScheduled(dontRunWhenDisabled)); } @Test @@ -165,15 +153,13 @@ void parallelConditionalRunWhenDisabledTest() { MockCommandHolder command4Holder = new MockCommandHolder(false); Command command4 = command4Holder.getMock(); - try (CommandScheduler scheduler = new CommandScheduler()) { - Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true); - Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true); + Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true); + Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true); - Command parallel = parallel(runWhenDisabled, dontRunWhenDisabled); + Command parallel = parallel(runWhenDisabled, dontRunWhenDisabled); - scheduler.schedule(parallel); + scheduler.schedule(parallel); - assertFalse(scheduler.isScheduled(runWhenDisabled)); - } + assertFalse(scheduler.isScheduled(runWhenDisabled)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java index 1f63487f34d..020c2a222c2 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/RunCommandTest.java @@ -12,17 +12,15 @@ class RunCommandTest extends CommandTestBase { @Test void runCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(0); + AtomicInteger counter = new AtomicInteger(0); - RunCommand command = new RunCommand(counter::incrementAndGet); + RunCommand command = new RunCommand(counter::incrementAndGet); - scheduler.schedule(command); - scheduler.run(); - scheduler.run(); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); + scheduler.run(); + scheduler.run(); - assertEquals(3, counter.get()); - } + assertEquals(3, counter.get()); } } 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..0c8d2063bce 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 @@ -12,33 +12,29 @@ class ScheduleCommandTest extends CommandTestBase { @Test void scheduleCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - ScheduleCommand scheduleCommand = new ScheduleCommand(command1, command2); + ScheduleCommand scheduleCommand = new ScheduleCommand(command1, command2); - scheduler.schedule(scheduleCommand); + scheduler.schedule(scheduleCommand); - verify(command1).schedule(); - verify(command2).schedule(); - } + verify(command1).schedule(); + verify(command2).schedule(); } @Test void scheduleCommandDuringRunTest() { - try (CommandScheduler scheduler = CommandScheduler.getInstance()) { - InstantCommand toSchedule = new InstantCommand(); - ScheduleCommand scheduleCommand = new ScheduleCommand(toSchedule); - SequentialCommandGroup group = - new SequentialCommandGroup(new InstantCommand(), scheduleCommand); - - scheduler.schedule(group); - scheduler.schedule(new RunCommand(() -> {})); - scheduler.run(); - assertDoesNotThrow(scheduler::run); - } + InstantCommand toSchedule = new InstantCommand(); + ScheduleCommand scheduleCommand = new ScheduleCommand(toSchedule); + SequentialCommandGroup group = + new SequentialCommandGroup(new InstantCommand(), scheduleCommand); + + scheduler.schedule(group); + scheduler.schedule(new RunCommand(() -> {})); + 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..ed5fe7058ef 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 @@ -16,174 +16,156 @@ class SchedulerTest extends CommandTestBase { @Test void schedulerLambdaTestNoInterrupt() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - scheduler.onCommandInitialize(command -> counter.incrementAndGet()); - scheduler.onCommandExecute(command -> counter.incrementAndGet()); - scheduler.onCommandFinish(command -> counter.incrementAndGet()); + scheduler.onCommandInitialize(command -> counter.incrementAndGet()); + scheduler.onCommandExecute(command -> counter.incrementAndGet()); + scheduler.onCommandFinish(command -> counter.incrementAndGet()); - scheduler.schedule(new InstantCommand()); - scheduler.run(); + scheduler.schedule(new InstantCommand()); + scheduler.run(); - assertEquals(counter.get(), 3); - } + assertEquals(counter.get(), 3); } @Test void schedulerInterruptLambdaTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); + scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); - Command command = new WaitCommand(10); + Command command = new WaitCommand(10); - scheduler.schedule(command); - scheduler.cancel(command); + scheduler.schedule(command); + scheduler.cancel(command); - assertEquals(counter.get(), 1); - } + assertEquals(counter.get(), 1); } @Test void schedulerInterruptNoCauseLambdaTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - scheduler.onCommandInterrupt( - (interrupted, cause) -> { - assertFalse(cause.isPresent()); - counter.incrementAndGet(); - }); + scheduler.onCommandInterrupt( + (interrupted, cause) -> { + assertFalse(cause.isPresent()); + counter.incrementAndGet(); + }); - Command command = Commands.run(() -> {}); + Command command = Commands.run(() -> {}); - scheduler.schedule(command); - scheduler.cancel(command); + scheduler.schedule(command); + scheduler.cancel(command); - assertEquals(1, counter.get()); - } + assertEquals(1, counter.get()); } @Test void schedulerInterruptCauseLambdaTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - Subsystem subsystem = new Subsystem() {}; - Command command = subsystem.run(() -> {}); - Command interruptor = subsystem.runOnce(() -> {}); + Subsystem subsystem = new Subsystem() {}; + Command command = subsystem.run(() -> {}); + Command interruptor = subsystem.runOnce(() -> {}); - scheduler.onCommandInterrupt( - (interrupted, cause) -> { - assertTrue(cause.isPresent()); - assertSame(interruptor, cause.get()); - counter.incrementAndGet(); - }); + scheduler.onCommandInterrupt( + (interrupted, cause) -> { + assertTrue(cause.isPresent()); + assertSame(interruptor, cause.get()); + counter.incrementAndGet(); + }); - scheduler.schedule(command); - scheduler.schedule(interruptor); + scheduler.schedule(command); + scheduler.schedule(interruptor); - assertEquals(1, counter.get()); - } + assertEquals(1, counter.get()); } @Test void schedulerInterruptCauseLambdaInRunLoopTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - - Subsystem subsystem = new Subsystem() {}; - Command command = subsystem.run(() -> {}); - Command interruptor = subsystem.runOnce(() -> {}); - // This command will schedule interruptor in execute() inside the run loop - Command interruptorScheduler = Commands.runOnce(() -> scheduler.schedule(interruptor)); - - scheduler.onCommandInterrupt( - (interrupted, cause) -> { - assertTrue(cause.isPresent()); - assertSame(interruptor, cause.get()); - counter.incrementAndGet(); - }); + AtomicInteger counter = new AtomicInteger(); + + Subsystem subsystem = new Subsystem() {}; + Command command = subsystem.run(() -> {}); + Command interruptor = subsystem.runOnce(() -> {}); + // This command will schedule interruptor in execute() inside the run loop + Command interruptorScheduler = Commands.runOnce(() -> scheduler.schedule(interruptor)); + + scheduler.onCommandInterrupt( + (interrupted, cause) -> { + assertTrue(cause.isPresent()); + assertSame(interruptor, cause.get()); + counter.incrementAndGet(); + }); - scheduler.schedule(command); - scheduler.schedule(interruptorScheduler); + scheduler.schedule(command); + scheduler.schedule(interruptorScheduler); - scheduler.run(); + scheduler.run(); - assertEquals(1, counter.get()); - } + assertEquals(1, counter.get()); } @Test void registerSubsystemTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(0); - Subsystem system = - new SubsystemBase() { - @Override - public void periodic() { - counter.incrementAndGet(); - } - }; - - assertDoesNotThrow(() -> scheduler.registerSubsystem(system)); - - scheduler.run(); - assertEquals(1, counter.get()); - } + AtomicInteger counter = new AtomicInteger(0); + Subsystem system = + new Subsystem() { + @Override + public void periodic() { + counter.incrementAndGet(); + } + }; + + assertDoesNotThrow(() -> scheduler.registerSubsystem(system)); + + scheduler.run(); + assertEquals(1, counter.get()); } @Test void unregisterSubsystemTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(0); - Subsystem system = - new SubsystemBase() { - @Override - public void periodic() { - counter.incrementAndGet(); - } - }; - scheduler.registerSubsystem(system); - assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system)); - - scheduler.run(); - assertEquals(0, counter.get()); - } + AtomicInteger counter = new AtomicInteger(0); + Subsystem system = + new Subsystem() { + @Override + public void periodic() { + counter.incrementAndGet(); + } + }; + scheduler.registerSubsystem(system); + assertDoesNotThrow(() -> scheduler.unregisterSubsystem(system)); + + scheduler.run(); + assertEquals(0, counter.get()); } @Test void schedulerCancelAllTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); - scheduler.onCommandInterrupt((command, interruptor) -> assertFalse(interruptor.isPresent())); + scheduler.onCommandInterrupt(command -> counter.incrementAndGet()); + scheduler.onCommandInterrupt((command, interruptor) -> assertFalse(interruptor.isPresent())); - Command command = new WaitCommand(10); - Command command2 = new WaitCommand(10); + Command command = new WaitCommand(10); + Command command2 = new WaitCommand(10); - scheduler.schedule(command); - scheduler.schedule(command2); - scheduler.cancelAll(); + scheduler.schedule(command); + scheduler.schedule(command2); + scheduler.cancelAll(); - assertEquals(counter.get(), 2); - } + assertEquals(counter.get(), 2); } @Test void scheduleScheduledNoOp() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); + AtomicInteger counter = new AtomicInteger(); - Command command = Commands.startEnd(counter::incrementAndGet, () -> {}); + Command command = Commands.startEnd(counter::incrementAndGet, () -> {}); - scheduler.schedule(command); - scheduler.schedule(command); + scheduler.schedule(command); + scheduler.schedule(command); - assertEquals(counter.get(), 1); - } + assertEquals(counter.get(), 1); } } 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..3824f8647b5 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 @@ -23,443 +23,413 @@ class SchedulingRecursionTest extends CommandTestBase { @EnumSource(InterruptionBehavior.class) @ParameterizedTest void cancelFromInitialize(InterruptionBehavior interruptionBehavior) { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean hasOtherRun = new AtomicBoolean(); - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; - Command selfCancels = - new Command() { - { - addRequirements(requirement); - } - - @Override - public void initialize() { - scheduler.cancel(this); - } - - @Override - public void end(boolean interrupted) { - counter.incrementAndGet(); - } - - @Override - public InterruptionBehavior getInterruptionBehavior() { - return interruptionBehavior; - } - }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); - - assertDoesNotThrow( - () -> { - scheduler.schedule(selfCancels); - scheduler.run(); - scheduler.schedule(other); - }); - assertFalse(scheduler.isScheduled(selfCancels)); - assertTrue(scheduler.isScheduled(other)); - assertEquals(1, counter.get()); - scheduler.run(); - assertTrue(hasOtherRun.get()); - } + AtomicBoolean hasOtherRun = new AtomicBoolean(); + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new SubsystemBase() {}; + Command selfCancels = + new Command() { + { + addRequirements(requirement); + } + + @Override + public void initialize() { + scheduler.cancel(this); + } + + @Override + public void end(boolean interrupted) { + counter.incrementAndGet(); + } + + @Override + public InterruptionBehavior getInterruptionBehavior() { + return interruptionBehavior; + } + }; + Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + + assertDoesNotThrow( + () -> { + scheduler.schedule(selfCancels); + scheduler.run(); + scheduler.schedule(other); + }); + assertFalse(scheduler.isScheduled(selfCancels)); + assertTrue(scheduler.isScheduled(other)); + assertEquals(1, counter.get()); + scheduler.run(); + assertTrue(hasOtherRun.get()); } @EnumSource(InterruptionBehavior.class) @ParameterizedTest void cancelFromInitializeAction(InterruptionBehavior interruptionBehavior) { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean hasOtherRun = new AtomicBoolean(); - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new Subsystem() {}; - Command selfCancels = - new Command() { - { - addRequirements(requirement); - } - - @Override - public void end(boolean interrupted) { - counter.incrementAndGet(); - } - - @Override - public InterruptionBehavior getInterruptionBehavior() { - return interruptionBehavior; - } - }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); - - assertDoesNotThrow( - () -> { - scheduler.onCommandInitialize(cmd -> scheduler.cancel(selfCancels)); - scheduler.schedule(selfCancels); - scheduler.run(); - scheduler.schedule(other); - }); - assertFalse(scheduler.isScheduled(selfCancels)); - assertTrue(scheduler.isScheduled(other)); - assertEquals(1, counter.get()); - scheduler.run(); - assertTrue(hasOtherRun.get()); - } + AtomicBoolean hasOtherRun = new AtomicBoolean(); + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new Subsystem() {}; + Command selfCancels = + new Command() { + { + addRequirements(requirement); + } + + @Override + public void end(boolean interrupted) { + counter.incrementAndGet(); + } + + @Override + public InterruptionBehavior getInterruptionBehavior() { + return interruptionBehavior; + } + }; + Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + + assertDoesNotThrow( + () -> { + scheduler.onCommandInitialize(cmd -> scheduler.cancel(selfCancels)); + scheduler.schedule(selfCancels); + scheduler.run(); + scheduler.schedule(other); + }); + assertFalse(scheduler.isScheduled(selfCancels)); + assertTrue(scheduler.isScheduled(other)); + assertEquals(1, counter.get()); + scheduler.run(); + assertTrue(hasOtherRun.get()); } @EnumSource(InterruptionBehavior.class) @ParameterizedTest void defaultCommandGetsRescheduledAfterSelfCanceling(InterruptionBehavior interruptionBehavior) { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean hasOtherRun = new AtomicBoolean(); - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; - Command selfCancels = - new Command() { - { - addRequirements(requirement); - } - - @Override - public void initialize() { - scheduler.cancel(this); - } - - @Override - public void end(boolean interrupted) { - counter.incrementAndGet(); - } - - @Override - public InterruptionBehavior getInterruptionBehavior() { - return interruptionBehavior; - } - }; - Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); - scheduler.setDefaultCommand(requirement, other); - - assertDoesNotThrow( - () -> { - scheduler.schedule(selfCancels); - scheduler.run(); - }); - scheduler.run(); - assertFalse(scheduler.isScheduled(selfCancels)); - assertTrue(scheduler.isScheduled(other)); - assertEquals(1, counter.get()); - scheduler.run(); - assertTrue(hasOtherRun.get()); - } + AtomicBoolean hasOtherRun = new AtomicBoolean(); + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new SubsystemBase() {}; + Command selfCancels = + new Command() { + { + addRequirements(requirement); + } + + @Override + public void initialize() { + scheduler.cancel(this); + } + + @Override + public void end(boolean interrupted) { + counter.incrementAndGet(); + } + + @Override + public InterruptionBehavior getInterruptionBehavior() { + return interruptionBehavior; + } + }; + Command other = new RunCommand(() -> hasOtherRun.set(true), requirement); + scheduler.setDefaultCommand(requirement, other); + + assertDoesNotThrow( + () -> { + scheduler.schedule(selfCancels); + scheduler.run(); + }); + scheduler.run(); + assertFalse(scheduler.isScheduled(selfCancels)); + assertTrue(scheduler.isScheduled(other)); + assertEquals(1, counter.get()); + scheduler.run(); + assertTrue(hasOtherRun.get()); } @Test void cancelFromEnd() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Command selfCancels = - new Command() { - @Override - public void end(boolean interrupted) { - counter.incrementAndGet(); - scheduler.cancel(this); - } - }; - scheduler.schedule(selfCancels); - - assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); - assertEquals(1, counter.get()); - assertFalse(scheduler.isScheduled(selfCancels)); - } + AtomicInteger counter = new AtomicInteger(); + Command selfCancels = + new Command() { + @Override + public void end(boolean interrupted) { + counter.incrementAndGet(); + scheduler.cancel(this); + } + }; + scheduler.schedule(selfCancels); + + assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); + assertEquals(1, counter.get()); + assertFalse(scheduler.isScheduled(selfCancels)); } @Test void cancelFromInterruptAction() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Command selfCancels = new RunCommand(() -> {}); - scheduler.onCommandInterrupt( - cmd -> { - counter.incrementAndGet(); - scheduler.cancel(selfCancels); - }); - scheduler.schedule(selfCancels); - - assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); - assertEquals(1, counter.get()); - assertFalse(scheduler.isScheduled(selfCancels)); - } + AtomicInteger counter = new AtomicInteger(); + Command selfCancels = new RunCommand(() -> {}); + scheduler.onCommandInterrupt( + cmd -> { + counter.incrementAndGet(); + scheduler.cancel(selfCancels); + }); + scheduler.schedule(selfCancels); + + assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); + assertEquals(1, counter.get()); + assertFalse(scheduler.isScheduled(selfCancels)); } @Test void cancelFromEndLoop() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - FunctionalCommand dCancelsAll = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancelAll(); - }, - () -> true); - FunctionalCommand cCancelsD = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(dCancelsAll); - }, - () -> true); - FunctionalCommand bCancelsC = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(cCancelsD); - }, - () -> true); - FunctionalCommand aCancelsB = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(bCancelsC); - }, - () -> true); - - scheduler.schedule(aCancelsB); - scheduler.schedule(bCancelsC); - scheduler.schedule(cCancelsD); - scheduler.schedule(dCancelsAll); - - assertDoesNotThrow(() -> scheduler.cancel(aCancelsB)); - assertEquals(4, counter.get()); - assertFalse(scheduler.isScheduled(aCancelsB)); - assertFalse(scheduler.isScheduled(bCancelsC)); - assertFalse(scheduler.isScheduled(cCancelsD)); - assertFalse(scheduler.isScheduled(dCancelsAll)); - } + AtomicInteger counter = new AtomicInteger(); + FunctionalCommand dCancelsAll = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancelAll(); + }, + () -> true); + FunctionalCommand cCancelsD = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(dCancelsAll); + }, + () -> true); + FunctionalCommand bCancelsC = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(cCancelsD); + }, + () -> true); + FunctionalCommand aCancelsB = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(bCancelsC); + }, + () -> true); + + scheduler.schedule(aCancelsB); + scheduler.schedule(bCancelsC); + scheduler.schedule(cCancelsD); + scheduler.schedule(dCancelsAll); + + assertDoesNotThrow(() -> scheduler.cancel(aCancelsB)); + assertEquals(4, counter.get()); + assertFalse(scheduler.isScheduled(aCancelsB)); + assertFalse(scheduler.isScheduled(bCancelsC)); + assertFalse(scheduler.isScheduled(cCancelsD)); + assertFalse(scheduler.isScheduled(dCancelsAll)); } @Test void cancelFromEndLoopWhileInRunLoop() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - FunctionalCommand dCancelsAll = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancelAll(); - }, - () -> true); - FunctionalCommand cCancelsD = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(dCancelsAll); - }, - () -> true); - FunctionalCommand bCancelsC = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(cCancelsD); - }, - () -> true); - FunctionalCommand aCancelsB = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.cancel(bCancelsC); - }, - () -> true); - - scheduler.schedule(aCancelsB); - scheduler.schedule(bCancelsC); - scheduler.schedule(cCancelsD); - scheduler.schedule(dCancelsAll); - - assertDoesNotThrow(scheduler::run); - assertEquals(4, counter.get()); - assertFalse(scheduler.isScheduled(aCancelsB)); - assertFalse(scheduler.isScheduled(bCancelsC)); - assertFalse(scheduler.isScheduled(cCancelsD)); - assertFalse(scheduler.isScheduled(dCancelsAll)); - } + AtomicInteger counter = new AtomicInteger(); + FunctionalCommand dCancelsAll = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancelAll(); + }, + () -> true); + FunctionalCommand cCancelsD = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(dCancelsAll); + }, + () -> true); + FunctionalCommand bCancelsC = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(cCancelsD); + }, + () -> true); + FunctionalCommand aCancelsB = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.cancel(bCancelsC); + }, + () -> true); + + scheduler.schedule(aCancelsB); + scheduler.schedule(bCancelsC); + scheduler.schedule(cCancelsD); + scheduler.schedule(dCancelsAll); + + assertDoesNotThrow(scheduler::run); + assertEquals(4, counter.get()); + assertFalse(scheduler.isScheduled(aCancelsB)); + assertFalse(scheduler.isScheduled(bCancelsC)); + assertFalse(scheduler.isScheduled(cCancelsD)); + assertFalse(scheduler.isScheduled(dCancelsAll)); } @Test void multiCancelFromEnd() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - FunctionalCommand bIncrementsCounter = - new FunctionalCommand( - () -> {}, () -> {}, interrupted -> counter.incrementAndGet(), () -> true); - Command aCancelsB = - new Command() { - @Override - public void end(boolean interrupted) { - counter.incrementAndGet(); - scheduler.cancel(bIncrementsCounter); - scheduler.cancel(this); - } - }; - - scheduler.schedule(aCancelsB); - scheduler.schedule(bIncrementsCounter); - - assertDoesNotThrow(() -> scheduler.cancel(aCancelsB)); - assertEquals(2, counter.get()); - assertFalse(scheduler.isScheduled(aCancelsB)); - assertFalse(scheduler.isScheduled(bIncrementsCounter)); - } + AtomicInteger counter = new AtomicInteger(); + FunctionalCommand bIncrementsCounter = + new FunctionalCommand( + () -> {}, () -> {}, interrupted -> counter.incrementAndGet(), () -> true); + Command aCancelsB = + new Command() { + @Override + public void end(boolean interrupted) { + counter.incrementAndGet(); + scheduler.cancel(bIncrementsCounter); + scheduler.cancel(this); + } + }; + + scheduler.schedule(aCancelsB); + scheduler.schedule(bIncrementsCounter); + + assertDoesNotThrow(() -> scheduler.cancel(aCancelsB)); + assertEquals(2, counter.get()); + assertFalse(scheduler.isScheduled(aCancelsB)); + assertFalse(scheduler.isScheduled(bIncrementsCounter)); } @Test void scheduleFromEndCancel() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; - InstantCommand other = new InstantCommand(() -> {}, requirement); - FunctionalCommand selfCancels = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.schedule(other); - }, - () -> false, - requirement); - - scheduler.schedule(selfCancels); - - assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); - assertEquals(1, counter.get()); - assertFalse(scheduler.isScheduled(selfCancels)); - } + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new SubsystemBase() {}; + InstantCommand other = new InstantCommand(() -> {}, requirement); + FunctionalCommand selfCancels = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.schedule(other); + }, + () -> false, + requirement); + + scheduler.schedule(selfCancels); + + assertDoesNotThrow(() -> scheduler.cancel(selfCancels)); + assertEquals(1, counter.get()); + assertFalse(scheduler.isScheduled(selfCancels)); } @Test void scheduleFromEndInterrupt() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; - InstantCommand other = new InstantCommand(() -> {}, requirement); - FunctionalCommand selfCancels = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.schedule(other); - }, - () -> false, - requirement); - - scheduler.schedule(selfCancels); - - assertDoesNotThrow(() -> scheduler.schedule(other)); - assertEquals(1, counter.get()); - assertFalse(scheduler.isScheduled(selfCancels)); - assertTrue(scheduler.isScheduled(other)); - } + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new SubsystemBase() {}; + InstantCommand other = new InstantCommand(() -> {}, requirement); + FunctionalCommand selfCancels = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.schedule(other); + }, + () -> false, + requirement); + + scheduler.schedule(selfCancels); + + assertDoesNotThrow(() -> scheduler.schedule(other)); + assertEquals(1, counter.get()); + assertFalse(scheduler.isScheduled(selfCancels)); + assertTrue(scheduler.isScheduled(other)); } @Test 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); - scheduler.onCommandInterrupt( - cmd -> { - counter.incrementAndGet(); - scheduler.schedule(other); - }); - scheduler.schedule(selfCancels); - - assertDoesNotThrow(() -> scheduler.schedule(other)); - assertEquals(1, counter.get()); - assertFalse(scheduler.isScheduled(selfCancels)); - assertTrue(scheduler.isScheduled(other)); - } + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new Subsystem() {}; + InstantCommand other = new InstantCommand(() -> {}, requirement); + InstantCommand selfCancels = new InstantCommand(() -> {}, requirement); + scheduler.onCommandInterrupt( + cmd -> { + counter.incrementAndGet(); + scheduler.schedule(other); + }); + scheduler.schedule(selfCancels); + + assertDoesNotThrow(() -> scheduler.schedule(other)); + assertEquals(1, counter.get()); + assertFalse(scheduler.isScheduled(selfCancels)); + assertTrue(scheduler.isScheduled(other)); } @ParameterizedTest @EnumSource(InterruptionBehavior.class) void scheduleInitializeFromDefaultCommand(InterruptionBehavior interruptionBehavior) { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new SubsystemBase() {}; - Command other = - new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior); - FunctionalCommand defaultCommand = - new FunctionalCommand( - () -> { - counter.incrementAndGet(); - scheduler.schedule(other); - }, - () -> {}, - interrupted -> {}, - () -> false, - requirement); - - scheduler.setDefaultCommand(requirement, defaultCommand); - - scheduler.run(); - scheduler.run(); - scheduler.run(); - assertEquals(3, counter.get()); - assertFalse(scheduler.isScheduled(defaultCommand)); - assertTrue(scheduler.isScheduled(other)); - } + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new SubsystemBase() {}; + Command other = + new InstantCommand(() -> {}, requirement).withInterruptBehavior(interruptionBehavior); + FunctionalCommand defaultCommand = + new FunctionalCommand( + () -> { + counter.incrementAndGet(); + scheduler.schedule(other); + }, + () -> {}, + interrupted -> {}, + () -> false, + requirement); + + scheduler.setDefaultCommand(requirement, defaultCommand); + + scheduler.run(); + scheduler.run(); + scheduler.run(); + assertEquals(3, counter.get()); + assertFalse(scheduler.isScheduled(defaultCommand)); + assertTrue(scheduler.isScheduled(other)); } @Test void cancelDefaultCommandFromEnd() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicInteger counter = new AtomicInteger(); - Subsystem requirement = new Subsystem() {}; - Command defaultCommand = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> counter.incrementAndGet(), - () -> false, - requirement); - Command other = new InstantCommand(() -> {}, requirement); - Command cancelDefaultCommand = - new FunctionalCommand( - () -> {}, - () -> {}, - interrupted -> { - counter.incrementAndGet(); - scheduler.schedule(other); - }, - () -> false); - - assertDoesNotThrow( - () -> { - scheduler.schedule(cancelDefaultCommand); - scheduler.setDefaultCommand(requirement, defaultCommand); - - scheduler.run(); - scheduler.cancel(cancelDefaultCommand); - }); - assertEquals(2, counter.get()); - assertFalse(scheduler.isScheduled(defaultCommand)); - assertTrue(scheduler.isScheduled(other)); - } + AtomicInteger counter = new AtomicInteger(); + Subsystem requirement = new Subsystem() {}; + Command defaultCommand = + new FunctionalCommand( + () -> {}, () -> {}, interrupted -> counter.incrementAndGet(), () -> false, requirement); + Command other = new InstantCommand(() -> {}, requirement); + Command cancelDefaultCommand = + new FunctionalCommand( + () -> {}, + () -> {}, + interrupted -> { + counter.incrementAndGet(); + scheduler.schedule(other); + }, + () -> false); + + assertDoesNotThrow( + () -> { + scheduler.schedule(cancelDefaultCommand); + scheduler.setDefaultCommand(requirement, defaultCommand); + + scheduler.run(); + scheduler.cancel(cancelDefaultCommand); + }); + assertEquals(2, counter.get()); + assertFalse(scheduler.isScheduled(defaultCommand)); + assertTrue(scheduler.isScheduled(other)); } } 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..97e4d9e9db8 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 @@ -16,61 +16,57 @@ class SelectCommandTest extends MultiCompositionTestBase> { @Test void selectCommandTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - command1Holder.setFinished(true); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - - SelectCommand selectCommand = - new SelectCommand<>( - Map.ofEntries( - Map.entry("one", command1), - Map.entry("two", command2), - Map.entry("three", command3)), - () -> "one"); - - scheduler.schedule(selectCommand); - scheduler.run(); - - verify(command1).initialize(); - verify(command1).execute(); - verify(command1).end(false); - - verify(command2, never()).initialize(); - verify(command2, never()).execute(); - verify(command2, never()).end(false); - - verify(command3, never()).initialize(); - verify(command3, never()).execute(); - verify(command3, never()).end(false); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + command1Holder.setFinished(true); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + + SelectCommand selectCommand = + new SelectCommand<>( + Map.ofEntries( + Map.entry("one", command1), + Map.entry("two", command2), + Map.entry("three", command3)), + () -> "one"); + + scheduler.schedule(selectCommand); + scheduler.run(); + + verify(command1).initialize(); + verify(command1).execute(); + verify(command1).end(false); + + verify(command2, never()).initialize(); + verify(command2, never()).execute(); + verify(command2, never()).end(false); + + verify(command3, never()).initialize(); + verify(command3, never()).execute(); + verify(command3, never()).end(false); } @Test void selectCommandInvalidKeyTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - command1Holder.setFinished(true); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - - SelectCommand selectCommand = - new SelectCommand<>( - Map.ofEntries( - Map.entry("one", command1), - Map.entry("two", command2), - Map.entry("three", command3)), - () -> "four"); - - assertDoesNotThrow(() -> scheduler.schedule(selectCommand)); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + command1Holder.setFinished(true); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + + SelectCommand selectCommand = + new SelectCommand<>( + Map.ofEntries( + Map.entry("one", command1), + Map.entry("two", command2), + Map.entry("three", command3)), + () -> "four"); + + assertDoesNotThrow(() -> scheduler.schedule(selectCommand)); } @Test @@ -80,31 +76,29 @@ void selectCommandRequirementTest() { Subsystem system3 = new SubsystemBase() {}; Subsystem system4 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); - Command command3 = command3Holder.getMock(); - - SelectCommand selectCommand = - new SelectCommand<>( - Map.ofEntries( - Map.entry("one", command1), - Map.entry("two", command2), - Map.entry("three", command3)), - () -> "one"); - - scheduler.schedule(selectCommand); - scheduler.schedule(new InstantCommand(() -> {}, system3)); - - assertFalse(scheduler.isScheduled(selectCommand)); - - verify(command1).end(true); - verify(command2, never()).end(true); - verify(command3, never()).end(true); - } + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); + Command command3 = command3Holder.getMock(); + + SelectCommand selectCommand = + new SelectCommand<>( + Map.ofEntries( + Map.entry("one", command1), + Map.entry("two", command2), + Map.entry("three", command3)), + () -> "one"); + + scheduler.schedule(selectCommand); + scheduler.schedule(new InstantCommand(() -> {}, system3)); + + assertFalse(scheduler.isScheduled(selectCommand)); + + verify(command1).end(true); + verify(command2, never()).end(true); + verify(command3, never()).end(true); } @Override diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java index abbc49062c7..75139c64e30 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/SequentialCommandGroupTest.java @@ -15,86 +15,80 @@ class SequentialCommandGroupTest extends MultiCompositionTestBase { @Test void sequentialGroupScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new SequentialCommandGroup(command1, command2); + Command group = new SequentialCommandGroup(command1, command2); - scheduler.schedule(group); + scheduler.schedule(group); - verify(command1).initialize(); - verify(command2, never()).initialize(); + verify(command1).initialize(); + verify(command2, never()).initialize(); - command1Holder.setFinished(true); - scheduler.run(); + command1Holder.setFinished(true); + scheduler.run(); - verify(command1).execute(); - verify(command1).end(false); - verify(command2).initialize(); - verify(command2, never()).execute(); - verify(command2, never()).end(false); + verify(command1).execute(); + verify(command1).end(false); + verify(command2).initialize(); + verify(command2, never()).execute(); + verify(command2, never()).end(false); - command2Holder.setFinished(true); - scheduler.run(); + command2Holder.setFinished(true); + scheduler.run(); - verify(command1).execute(); - verify(command1).end(false); - verify(command2).execute(); - verify(command2).end(false); + verify(command1).execute(); + verify(command1).end(false); + verify(command2).execute(); + verify(command2).end(false); - assertFalse(scheduler.isScheduled(group)); - } + assertFalse(scheduler.isScheduled(group)); } @Test void sequentialGroupInterruptTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true); - Command command3 = command3Holder.getMock(); - - Command group = new SequentialCommandGroup(command1, command2, command3); - - scheduler.schedule(group); - - command1Holder.setFinished(true); - scheduler.run(); - scheduler.cancel(group); - scheduler.run(); - - verify(command1).execute(); - verify(command1, never()).end(true); - verify(command1).end(false); - verify(command2, never()).execute(); - verify(command2).end(true); - verify(command2, never()).end(false); - verify(command3, never()).initialize(); - verify(command3, never()).execute(); - verify(command3, never()).end(true); - verify(command3, never()).end(false); - - assertFalse(scheduler.isScheduled(group)); - } + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true); + Command command3 = command3Holder.getMock(); + + Command group = new SequentialCommandGroup(command1, command2, command3); + + scheduler.schedule(group); + + command1Holder.setFinished(true); + scheduler.run(); + scheduler.cancel(group); + scheduler.run(); + + verify(command1).execute(); + verify(command1, never()).end(true); + verify(command1).end(false); + verify(command2, never()).execute(); + verify(command2).end(true); + verify(command2, never()).end(false); + verify(command3, never()).initialize(); + verify(command3, never()).execute(); + verify(command3, never()).end(true); + verify(command3, never()).end(false); + + assertFalse(scheduler.isScheduled(group)); } @Test void notScheduledCancelTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true); - Command command2 = command2Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true); + Command command2 = command2Holder.getMock(); - Command group = new SequentialCommandGroup(command1, command2); + Command group = new SequentialCommandGroup(command1, command2); - assertDoesNotThrow(() -> scheduler.cancel(group)); - } + assertDoesNotThrow(() -> scheduler.cancel(group)); } @Test @@ -104,22 +98,20 @@ void sequentialGroupRequirementTest() { Subsystem system3 = new SubsystemBase() {}; Subsystem system4 = new SubsystemBase() {}; - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); - Command command1 = command1Holder.getMock(); - MockCommandHolder command2Holder = new MockCommandHolder(true, system3); - Command command2 = command2Holder.getMock(); - MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); - Command command3 = command3Holder.getMock(); + MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2); + Command command1 = command1Holder.getMock(); + MockCommandHolder command2Holder = new MockCommandHolder(true, system3); + Command command2 = command2Holder.getMock(); + MockCommandHolder command3Holder = new MockCommandHolder(true, system3, system4); + Command command3 = command3Holder.getMock(); - Command group = new SequentialCommandGroup(command1, command2); + Command group = new SequentialCommandGroup(command1, command2); - scheduler.schedule(group); - scheduler.schedule(command3); + scheduler.schedule(group); + scheduler.schedule(command3); - assertFalse(scheduler.isScheduled(group)); - assertTrue(scheduler.isScheduled(command3)); - } + assertFalse(scheduler.isScheduled(group)); + assertTrue(scheduler.isScheduled(command3)); } @Override diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java index db0d7928188..9e12cb181ec 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/StartEndCommandTest.java @@ -13,22 +13,20 @@ class StartEndCommandTest extends CommandTestBase { @Test void startEndCommandScheduleTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean cond1 = new AtomicBoolean(); - AtomicBoolean cond2 = new AtomicBoolean(); + AtomicBoolean cond1 = new AtomicBoolean(); + AtomicBoolean cond2 = new AtomicBoolean(); - StartEndCommand command = new StartEndCommand(() -> cond1.set(true), () -> cond2.set(true)); + StartEndCommand command = new StartEndCommand(() -> cond1.set(true), () -> cond2.set(true)); - scheduler.schedule(command); - scheduler.run(); + scheduler.schedule(command); + scheduler.run(); - assertTrue(scheduler.isScheduled(command)); + assertTrue(scheduler.isScheduled(command)); - scheduler.cancel(command); + scheduler.cancel(command); - assertFalse(scheduler.isScheduled(command)); - assertTrue(cond1.get()); - assertTrue(cond2.get()); - } + assertFalse(scheduler.isScheduled(command)); + assertTrue(cond1.get()); + assertTrue(cond2.get()); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java index 7cf1a285433..e7ded5e05e6 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitCommandTest.java @@ -34,49 +34,45 @@ void cleanup() { @Test @ResourceLock("timing") void waitCommandTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - WaitCommand waitCommand = new WaitCommand(2); + WaitCommand waitCommand = new WaitCommand(2); - scheduler.schedule(waitCommand); - scheduler.run(); - SimHooks.stepTiming(1); - scheduler.run(); + scheduler.schedule(waitCommand); + scheduler.run(); + SimHooks.stepTiming(1); + scheduler.run(); - assertTrue(scheduler.isScheduled(waitCommand)); + assertTrue(scheduler.isScheduled(waitCommand)); - SimHooks.stepTiming(2); + SimHooks.stepTiming(2); - scheduler.run(); + scheduler.run(); - assertFalse(scheduler.isScheduled(waitCommand)); - } + assertFalse(scheduler.isScheduled(waitCommand)); } @Test @ResourceLock("timing") void withTimeoutTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - MockCommandHolder command1Holder = new MockCommandHolder(true); - Command command1 = command1Holder.getMock(); - when(command1.withTimeout(anyDouble())).thenCallRealMethod(); - when(command1.raceWith(notNull())).thenCallRealMethod(); + MockCommandHolder command1Holder = new MockCommandHolder(true); + Command command1 = command1Holder.getMock(); + when(command1.withTimeout(anyDouble())).thenCallRealMethod(); + when(command1.raceWith(notNull())).thenCallRealMethod(); - Command timeout = command1.withTimeout(2); + Command timeout = command1.withTimeout(2); - scheduler.schedule(timeout); - scheduler.run(); + scheduler.schedule(timeout); + scheduler.run(); - verify(command1).initialize(); - verify(command1).execute(); - assertFalse(scheduler.isScheduled(command1)); - assertTrue(scheduler.isScheduled(timeout)); + verify(command1).initialize(); + verify(command1).execute(); + assertFalse(scheduler.isScheduled(command1)); + assertTrue(scheduler.isScheduled(timeout)); - SimHooks.stepTiming(3); - scheduler.run(); + SimHooks.stepTiming(3); + scheduler.run(); - verify(command1).end(true); - verify(command1, never()).end(false); - assertFalse(scheduler.isScheduled(timeout)); - } + verify(command1).end(true); + verify(command1, never()).end(false); + assertFalse(scheduler.isScheduled(timeout)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java index e91ae4e5631..532a5cf781c 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/WaitUntilCommandTest.java @@ -13,17 +13,15 @@ class WaitUntilCommandTest extends CommandTestBase { @Test void waitUntilTest() { - try (CommandScheduler scheduler = new CommandScheduler()) { - AtomicBoolean condition = new AtomicBoolean(); + AtomicBoolean condition = new AtomicBoolean(); - Command command = new WaitUntilCommand(condition::get); + Command command = new WaitUntilCommand(condition::get); - scheduler.schedule(command); - scheduler.run(); - assertTrue(scheduler.isScheduled(command)); - condition.set(true); - scheduler.run(); - assertFalse(scheduler.isScheduled(command)); - } + scheduler.schedule(command); + scheduler.run(); + assertTrue(scheduler.isScheduled(command)); + condition.set(true); + scheduler.run(); + assertFalse(scheduler.isScheduled(command)); } } diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java index b9adc1344c3..d8b45d8d123 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/NetworkButtonTest.java @@ -8,7 +8,6 @@ import static org.mockito.Mockito.verify; import edu.wpi.first.networktables.NetworkTableInstance; -import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.CommandTestBase; import org.junit.jupiter.api.AfterEach; import org.junit.jupiter.api.BeforeEach; @@ -30,7 +29,6 @@ void teardown() { @Test void setNetworkButtonTest() { - var scheduler = CommandScheduler.getInstance(); var commandHolder = new MockCommandHolder(true); var command = commandHolder.getMock(); var pub = m_inst.getTable("TestTable").getBooleanTopic("Test").publish(); diff --git a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java index 8cd5fdea2f1..af3760c164f 100644 --- a/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java +++ b/wpilibNewCommands/src/test/java/edu/wpi/first/wpilibj2/command/button/TriggerTest.java @@ -12,7 +12,6 @@ import edu.wpi.first.wpilibj.simulation.SimHooks; import edu.wpi.first.wpilibj2.command.Command; -import edu.wpi.first.wpilibj2.command.CommandScheduler; import edu.wpi.first.wpilibj2.command.CommandTestBase; import edu.wpi.first.wpilibj2.command.FunctionalCommand; import edu.wpi.first.wpilibj2.command.RunCommand; @@ -26,7 +25,6 @@ class TriggerTest extends CommandTestBase { @Test void onTrueTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicBoolean finished = new AtomicBoolean(false); Command command1 = new WaitUntilCommand(finished::get); @@ -45,7 +43,6 @@ void onTrueTest() { @Test void onFalseTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicBoolean finished = new AtomicBoolean(false); Command command1 = new WaitUntilCommand(finished::get); @@ -64,7 +61,6 @@ void onFalseTest() { @Test void onChangeTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicBoolean finished = new AtomicBoolean(false); Command command1 = new WaitUntilCommand(finished::get); @@ -90,7 +86,6 @@ void onChangeTest() { @Test void whileTrueRepeatedlyTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicInteger inits = new AtomicInteger(0); AtomicInteger counter = new AtomicInteger(0); // the repeatedly() here is the point! @@ -121,7 +116,6 @@ void whileTrueRepeatedlyTest() { @Test void whileTrueLambdaRunTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicInteger counter = new AtomicInteger(0); // the repeatedly() here is the point! Command command1 = new RunCommand(counter::incrementAndGet); @@ -143,7 +137,6 @@ void whileTrueLambdaRunTest() { @Test void whileTrueOnceTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicInteger startCounter = new AtomicInteger(0); AtomicInteger endCounter = new AtomicInteger(0); Command command1 = @@ -168,7 +161,6 @@ void whileTrueOnceTest() { @Test void toggleOnTrueTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicInteger startCounter = new AtomicInteger(0); AtomicInteger endCounter = new AtomicInteger(0); Command command1 = @@ -197,7 +189,6 @@ void toggleOnTrueTest() { @Test void cancelWhenActiveTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); AtomicInteger startCounter = new AtomicInteger(0); AtomicInteger endCounter = new AtomicInteger(0); @@ -247,7 +238,6 @@ void triggerCompositionSupplierTest() { @Test void debounceTest() { - CommandScheduler scheduler = CommandScheduler.getInstance(); MockCommandHolder commandHolder = new MockCommandHolder(true); Command command = commandHolder.getMock(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp index a0b7726f5d6..429bac50457 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandDecoratorTest.cpp @@ -17,8 +17,6 @@ using namespace frc2; class CommandDecoratorTest : public CommandTestBase {}; TEST_F(CommandDecoratorTest, WithTimeout) { - CommandScheduler scheduler = GetScheduler(); - frc::sim::PauseTiming(); auto command = RunCommand([] {}, {}).WithTimeout(100_ms); @@ -38,8 +36,6 @@ TEST_F(CommandDecoratorTest, WithTimeout) { } TEST_F(CommandDecoratorTest, Until) { - CommandScheduler scheduler = GetScheduler(); - bool finish = false; auto command = RunCommand([] {}, {}).Until([&finish] { return finish; }); @@ -56,8 +52,6 @@ TEST_F(CommandDecoratorTest, Until) { } TEST_F(CommandDecoratorTest, UntilOrder) { - CommandScheduler scheduler = GetScheduler(); - bool firstHasRun = false; bool firstWasPolled = false; @@ -81,8 +75,6 @@ TEST_F(CommandDecoratorTest, UntilOrder) { } TEST_F(CommandDecoratorTest, OnlyWhile) { - CommandScheduler scheduler = GetScheduler(); - bool run = true; auto command = RunCommand([] {}, {}).OnlyWhile([&run] { return run; }); @@ -99,8 +91,6 @@ TEST_F(CommandDecoratorTest, OnlyWhile) { } TEST_F(CommandDecoratorTest, OnlyWhileOrder) { - CommandScheduler scheduler = GetScheduler(); - bool firstHasRun = false; bool firstWasPolled = false; @@ -124,8 +114,6 @@ TEST_F(CommandDecoratorTest, OnlyWhileOrder) { } TEST_F(CommandDecoratorTest, IgnoringDisable) { - CommandScheduler scheduler = GetScheduler(); - auto command = RunCommand([] {}, {}).IgnoringDisable(true); SetDSEnabled(false); @@ -137,8 +125,6 @@ TEST_F(CommandDecoratorTest, IgnoringDisable) { } TEST_F(CommandDecoratorTest, BeforeStarting) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; auto command = InstantCommand([] {}, {}).BeforeStarting( @@ -158,8 +144,6 @@ TEST_F(CommandDecoratorTest, BeforeStarting) { } TEST_F(CommandDecoratorTest, AndThenLambda) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; auto command = @@ -179,8 +163,6 @@ TEST_F(CommandDecoratorTest, AndThenLambda) { } TEST_F(CommandDecoratorTest, AndThen) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; auto command1 = InstantCommand(); @@ -201,8 +183,6 @@ TEST_F(CommandDecoratorTest, AndThen) { } TEST_F(CommandDecoratorTest, DeadlineFor) { - CommandScheduler scheduler = GetScheduler(); - bool finish = false; auto dictator = WaitUntilCommand([&finish] { return finish; }); @@ -222,8 +202,6 @@ TEST_F(CommandDecoratorTest, DeadlineFor) { } TEST_F(CommandDecoratorTest, WithDeadline) { - CommandScheduler scheduler = GetScheduler(); - bool finish = false; auto dictator = WaitUntilCommand([&finish] { return finish; }); @@ -243,8 +221,6 @@ TEST_F(CommandDecoratorTest, WithDeadline) { } TEST_F(CommandDecoratorTest, AlongWith) { - CommandScheduler scheduler = GetScheduler(); - bool finish = false; auto command1 = WaitUntilCommand([&finish] { return finish; }); @@ -264,8 +240,6 @@ TEST_F(CommandDecoratorTest, AlongWith) { } TEST_F(CommandDecoratorTest, RaceWith) { - CommandScheduler scheduler = GetScheduler(); - auto command1 = WaitUntilCommand([] { return false; }); auto command2 = InstantCommand(); @@ -278,8 +252,6 @@ TEST_F(CommandDecoratorTest, RaceWith) { } TEST_F(CommandDecoratorTest, DeadlineForOrder) { - CommandScheduler scheduler = GetScheduler(); - bool dictatorHasRun = false; bool dictatorWasPolled = false; @@ -305,8 +277,6 @@ TEST_F(CommandDecoratorTest, DeadlineForOrder) { } TEST_F(CommandDecoratorTest, WithDeadlineOrder) { - CommandScheduler scheduler = GetScheduler(); - bool dictatorHasRun = false; bool dictatorWasPolled = false; @@ -332,8 +302,6 @@ TEST_F(CommandDecoratorTest, WithDeadlineOrder) { } TEST_F(CommandDecoratorTest, AlongWithOrder) { - CommandScheduler scheduler = GetScheduler(); - bool firstHasRun = false; bool firstWasPolled = false; @@ -358,8 +326,6 @@ TEST_F(CommandDecoratorTest, AlongWithOrder) { } TEST_F(CommandDecoratorTest, RaceWithOrder) { - CommandScheduler scheduler = GetScheduler(); - bool firstHasRun = false; bool firstWasPolled = false; @@ -384,8 +350,6 @@ TEST_F(CommandDecoratorTest, RaceWithOrder) { } TEST_F(CommandDecoratorTest, Unless) { - CommandScheduler scheduler = GetScheduler(); - bool hasRun = false; bool unlessCondition = true; @@ -403,8 +367,6 @@ TEST_F(CommandDecoratorTest, Unless) { } TEST_F(CommandDecoratorTest, OnlyIf) { - CommandScheduler scheduler = GetScheduler(); - bool hasRun = false; bool onlyIfCondition = false; @@ -422,7 +384,6 @@ TEST_F(CommandDecoratorTest, OnlyIf) { } TEST_F(CommandDecoratorTest, FinallyDo) { - CommandScheduler scheduler = GetScheduler(); int first = 0; int second = 0; CommandPtr command = FunctionalCommand([] {}, [] {}, @@ -453,7 +414,6 @@ TEST_F(CommandDecoratorTest, FinallyDo) { // handleInterruptTest() implicitly tests the interrupt=true branch of // finallyDo() TEST_F(CommandDecoratorTest, HandleInterrupt) { - CommandScheduler scheduler = GetScheduler(); int first = 0; int second = 0; CommandPtr command = FunctionalCommand([] {}, [] {}, diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp index 1dae951bea7..13508f91685 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandPtrTest.cpp @@ -15,8 +15,6 @@ using namespace frc2; class CommandPtrTest : public CommandTestBase {}; TEST_F(CommandPtrTest, MovedFrom) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; CommandPtr movedFrom = cmd::Run([&counter] { counter++; }); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp index e8d3c16ff4f..7a472c86d12 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandRequirementsTest.cpp @@ -14,8 +14,6 @@ using namespace frc2; class CommandRequirementsTest : public CommandTestBase {}; TEST_F(CommandRequirementsTest, RequirementInterrupt) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement; MockCommand command1({&requirement}); @@ -28,7 +26,9 @@ TEST_F(CommandRequirementsTest, RequirementInterrupt) { EXPECT_CALL(command2, Initialize()); EXPECT_CALL(command2, Execute()); - EXPECT_CALL(command2, End(true)).Times(0); + // Because we schedule command2 on the CommandScheduler singleton, the + // MockCommand deconstructor will cancel it at the end of the scope + EXPECT_CALL(command2, End(true)).Times(1); EXPECT_CALL(command2, End(false)).Times(0); scheduler.Schedule(&command1); @@ -41,8 +41,6 @@ TEST_F(CommandRequirementsTest, RequirementInterrupt) { } TEST_F(CommandRequirementsTest, RequirementUninterruptible) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement; int initCounter = 0; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandScheduleTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandScheduleTest.cpp index 840c05bb213..655d402c909 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandScheduleTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandScheduleTest.cpp @@ -14,7 +14,6 @@ using namespace frc2; class CommandScheduleTest : public CommandTestBase {}; TEST_F(CommandScheduleTest, InstantSchedule) { - CommandScheduler scheduler = GetScheduler(); MockCommand command; EXPECT_CALL(command, Initialize()); @@ -29,7 +28,6 @@ TEST_F(CommandScheduleTest, InstantSchedule) { } TEST_F(CommandScheduleTest, SingleIterationSchedule) { - CommandScheduler scheduler = GetScheduler(); MockCommand command; EXPECT_CALL(command, Initialize()); @@ -45,7 +43,6 @@ TEST_F(CommandScheduleTest, SingleIterationSchedule) { } TEST_F(CommandScheduleTest, MultiSchedule) { - CommandScheduler scheduler = GetScheduler(); MockCommand command1; MockCommand command2; MockCommand command3; @@ -82,7 +79,6 @@ TEST_F(CommandScheduleTest, MultiSchedule) { } TEST_F(CommandScheduleTest, SchedulerCancel) { - CommandScheduler scheduler = GetScheduler(); MockCommand command; EXPECT_CALL(command, Initialize()); @@ -99,8 +95,6 @@ TEST_F(CommandScheduleTest, SchedulerCancel) { } TEST_F(CommandScheduleTest, CommandKnowsWhenItEnded) { - CommandScheduler scheduler = GetScheduler(); - frc2::FunctionalCommand* commandPtr = nullptr; auto command = frc2::FunctionalCommand( [] {}, [] {}, @@ -119,17 +113,14 @@ TEST_F(CommandScheduleTest, CommandKnowsWhenItEnded) { } TEST_F(CommandScheduleTest, ScheduleCommandInCommand) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; frc2::InstantCommand commandToGetScheduled{[&counter] { counter++; }}; - auto command = - frc2::RunCommand([&counter, &scheduler, &commandToGetScheduled] { - scheduler.Schedule(&commandToGetScheduled); - EXPECT_EQ(counter, 1) - << "Scheduled command's init was not run immediately " - "after getting scheduled"; - }); + auto command = frc2::RunCommand([this, &counter, &commandToGetScheduled] { + scheduler.Schedule(&commandToGetScheduled); + EXPECT_EQ(counter, 1) << "Scheduled command's init was not run immediately " + "after getting scheduled"; + }); scheduler.Schedule(&command); scheduler.Run(); @@ -144,14 +135,12 @@ TEST_F(CommandScheduleTest, ScheduleCommandInCommand) { } TEST_F(CommandScheduleTest, NotScheduledCancel) { - CommandScheduler scheduler = GetScheduler(); MockCommand command; EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&command)); } TEST_F(CommandScheduleTest, SmartDashboardCancel) { - CommandScheduler scheduler = GetScheduler(); frc::SmartDashboard::PutData("Scheduler", &scheduler); frc::SmartDashboard::UpdateValues(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandSendableButtonTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandSendableButtonTest.cpp index 08caa5cddaf..730988bcf73 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandSendableButtonTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandSendableButtonTest.cpp @@ -33,7 +33,7 @@ class CommandSendableButtonTest : public CommandTestBase { TEST_F(CommandSendableButtonTest, trueAndNotScheduledSchedules) { // Not scheduled and true -> scheduled - GetScheduler().Run(); + scheduler.Run(); frc::SmartDashboard::UpdateValues(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); @@ -41,7 +41,7 @@ TEST_F(CommandSendableButtonTest, trueAndNotScheduledSchedules) { m_publish.Set(true); frc::SmartDashboard::UpdateValues(); - GetScheduler().Run(); + scheduler.Run(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); EXPECT_EQ(0, m_cancel); @@ -50,7 +50,7 @@ TEST_F(CommandSendableButtonTest, trueAndNotScheduledSchedules) { TEST_F(CommandSendableButtonTest, trueAndScheduledNoOp) { // Scheduled and true -> no-op m_command->Schedule(); - GetScheduler().Run(); + scheduler.Run(); frc::SmartDashboard::UpdateValues(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); @@ -58,7 +58,7 @@ TEST_F(CommandSendableButtonTest, trueAndScheduledNoOp) { m_publish.Set(true); frc::SmartDashboard::UpdateValues(); - GetScheduler().Run(); + scheduler.Run(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); EXPECT_EQ(0, m_cancel); @@ -66,7 +66,7 @@ TEST_F(CommandSendableButtonTest, trueAndScheduledNoOp) { TEST_F(CommandSendableButtonTest, falseAndNotScheduledNoOp) { // Not scheduled and false -> no-op - GetScheduler().Run(); + scheduler.Run(); frc::SmartDashboard::UpdateValues(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); @@ -74,7 +74,7 @@ TEST_F(CommandSendableButtonTest, falseAndNotScheduledNoOp) { m_publish.Set(false); frc::SmartDashboard::UpdateValues(); - GetScheduler().Run(); + scheduler.Run(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); EXPECT_EQ(0, m_cancel); @@ -83,7 +83,7 @@ TEST_F(CommandSendableButtonTest, falseAndNotScheduledNoOp) { TEST_F(CommandSendableButtonTest, falseAndScheduledCancel) { // Scheduled and false -> cancel m_command->Schedule(); - GetScheduler().Run(); + scheduler.Run(); frc::SmartDashboard::UpdateValues(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); @@ -91,7 +91,7 @@ TEST_F(CommandSendableButtonTest, falseAndScheduledCancel) { m_publish.Set(false); frc::SmartDashboard::UpdateValues(); - GetScheduler().Run(); + scheduler.Run(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); EXPECT_EQ(1, m_cancel); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp index 1bd180c8a5a..f998117dc28 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.cpp @@ -7,11 +7,7 @@ using namespace frc2; CommandTestBase::CommandTestBase() { - auto& scheduler = CommandScheduler::GetInstance(); - scheduler.CancelAll(); - scheduler.Enable(); - scheduler.GetActiveButtonLoop()->Clear(); - scheduler.UnregisterAllSubsystems(); + CommandScheduler::ResetInstance(); SetDSEnabled(true); } @@ -21,10 +17,6 @@ CommandTestBase::~CommandTestBase() { CommandScheduler::GetInstance().UnregisterAllSubsystems(); } -CommandScheduler CommandTestBase::GetScheduler() { - return CommandScheduler(); -} - void CommandTestBase::SetDSEnabled(bool enabled) { frc::sim::DriverStationSim::SetDsAttached(true); frc::sim::DriverStationSim::SetEnabled(enabled); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h index 16d0cdc8b2c..2ef6a2134b8 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/CommandTestBase.h @@ -93,7 +93,8 @@ class CommandTestBase : public ::testing::Test { ~CommandTestBase() override; protected: - CommandScheduler GetScheduler(); + // Reference is still valid after resetting the instance + CommandScheduler& scheduler = CommandScheduler::GetInstance(); void SetDSEnabled(bool enabled); }; @@ -102,11 +103,7 @@ template class CommandTestBaseWithParam : public ::testing::TestWithParam { public: CommandTestBaseWithParam() { - auto& scheduler = CommandScheduler::GetInstance(); - scheduler.CancelAll(); - scheduler.Enable(); - scheduler.GetActiveButtonLoop()->Clear(); - scheduler.UnregisterAllSubsystems(); + CommandScheduler::ResetInstance(); SetDSEnabled(true); } @@ -117,7 +114,8 @@ class CommandTestBaseWithParam : public ::testing::TestWithParam { } protected: - CommandScheduler GetScheduler() { return CommandScheduler(); } + // Reference is still valid after resetting the instance + CommandScheduler& scheduler = CommandScheduler::GetInstance(); void SetDSEnabled(bool enabled) { frc::sim::DriverStationSim::SetDsAttached(true); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp index 7896a1aa326..6aaddd11bbf 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ConditionalCommandTest.cpp @@ -14,8 +14,6 @@ using namespace frc2; class ConditionalCommandTest : public CommandTestBase {}; TEST_F(ConditionalCommandTest, ConditionalCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr mock = std::make_unique(); MockCommand* mockptr = mock.get(); @@ -35,8 +33,6 @@ TEST_F(ConditionalCommandTest, ConditionalCommandSchedule) { } TEST_F(ConditionalCommandTest, ConditionalCommandRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp index a024a2f1955..43ce258e1b1 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/DefaultCommandTest.cpp @@ -11,8 +11,6 @@ using namespace frc2; class DefaultCommandTest : public CommandTestBase {}; TEST_F(DefaultCommandTest, DefaultCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem subsystem; RunCommand command1([] {}, {&subsystem}); @@ -25,8 +23,6 @@ TEST_F(DefaultCommandTest, DefaultCommandSchedule) { } TEST_F(DefaultCommandTest, DefaultCommandInterruptResume) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem subsystem; RunCommand command1([] {}, {&subsystem}); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/FunctionalCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/FunctionalCommandTest.cpp index 0f0ebdabe73..7f95d00a837 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/FunctionalCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/FunctionalCommandTest.cpp @@ -9,8 +9,6 @@ using namespace frc2; class FunctionalCommandTest : public CommandTestBase {}; TEST_F(FunctionalCommandTest, FunctionalCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; bool finished = false; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp index 90eab852231..46a496b98a8 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/InstantCommandTest.cpp @@ -9,8 +9,6 @@ using namespace frc2; class InstantCommandTest : public CommandTestBase {}; TEST_F(InstantCommandTest, InstantCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; InstantCommand command([&counter] { counter++; }, {}); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/NotifierCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/NotifierCommandTest.cpp index 8b4f1cc909b..95c586c9411 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/NotifierCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/NotifierCommandTest.cpp @@ -13,8 +13,6 @@ using namespace std::chrono_literals; class NotifierCommandTest : public CommandTestBase {}; TEST_F(NotifierCommandTest, NotifierCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - frc::sim::PauseTiming(); int counter = 0; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp index 21457d024cd..c392f82d439 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelCommandGroupTest.cpp @@ -15,8 +15,6 @@ using namespace frc2; class ParallelCommandGroupTest : public CommandTestBase {}; TEST_F(ParallelCommandGroupTest, ParallelGroupSchedule) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); @@ -45,8 +43,6 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupSchedule) { } TEST_F(ParallelCommandGroupTest, ParallelGroupInterrupt) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); @@ -76,16 +72,12 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupInterrupt) { } TEST_F(ParallelCommandGroupTest, ParallelGroupNotScheduledCancel) { - CommandScheduler scheduler = GetScheduler(); - ParallelCommandGroup group((InstantCommand(), InstantCommand())); EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); } TEST_F(ParallelCommandGroupTest, ParallelGroupCopy) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; WaitUntilCommand command([&finished] { return finished; }); @@ -100,8 +92,6 @@ TEST_F(ParallelCommandGroupTest, ParallelGroupCopy) { } TEST_F(ParallelCommandGroupTest, ParallelGroupRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp index d36b97ad6c6..c66d307dc83 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelDeadlineGroupTest.cpp @@ -16,8 +16,6 @@ using namespace frc2; class ParallelDeadlineGroupTest : public CommandTestBase {}; TEST_F(ParallelDeadlineGroupTest, DeadlineGroupSchedule) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); @@ -54,8 +52,6 @@ TEST_F(ParallelDeadlineGroupTest, DeadlineGroupSchedule) { } TEST_F(ParallelDeadlineGroupTest, SequentialGroupInterrupt) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem subsystem; std::unique_ptr command1Holder = std::make_unique(); @@ -93,16 +89,12 @@ TEST_F(ParallelDeadlineGroupTest, SequentialGroupInterrupt) { } TEST_F(ParallelDeadlineGroupTest, DeadlineGroupNotScheduledCancel) { - CommandScheduler scheduler = GetScheduler(); - ParallelDeadlineGroup group{InstantCommand(), InstantCommand()}; EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); } TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineCopy) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; WaitUntilCommand command([&finished] { return finished; }); @@ -117,8 +109,6 @@ TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineCopy) { } TEST_F(ParallelDeadlineGroupTest, ParallelDeadlineRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp index 032c3c1dd33..2d2d44248b4 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ParallelRaceGroupTest.cpp @@ -16,8 +16,6 @@ using namespace frc2; class ParallelRaceGroupTest : public CommandTestBase {}; TEST_F(ParallelRaceGroupTest, ParallelRaceSchedule) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); @@ -52,8 +50,6 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceSchedule) { } TEST_F(ParallelRaceGroupTest, ParallelRaceInterrupt) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); @@ -88,16 +84,12 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceInterrupt) { } TEST_F(ParallelRaceGroupTest, ParallelRaceNotScheduledCancel) { - CommandScheduler scheduler = GetScheduler(); - ParallelRaceGroup group{InstantCommand(), InstantCommand()}; EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); } TEST_F(ParallelRaceGroupTest, ParallelRaceCopy) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; WaitUntilCommand command([&finished] { return finished; }); @@ -112,8 +104,6 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceCopy) { } TEST_F(ParallelRaceGroupTest, RaceGroupRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; @@ -133,8 +123,6 @@ TEST_F(ParallelRaceGroupTest, RaceGroupRequirement) { } TEST_F(ParallelRaceGroupTest, ParallelRaceOnlyCallsEndOnce) { - CommandScheduler scheduler = GetScheduler(); - bool finished1 = false; bool finished2 = false; bool finished3 = false; @@ -157,8 +145,6 @@ TEST_F(ParallelRaceGroupTest, ParallelRaceOnlyCallsEndOnce) { } TEST_F(ParallelRaceGroupTest, ParallelRaceScheduleTwice) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp index 02575a30ccc..571788e9475 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/PrintCommandTest.cpp @@ -11,8 +11,6 @@ using namespace frc2; class PrintCommandTest : public CommandTestBase {}; TEST_F(PrintCommandTest, PrintCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - PrintCommand command("Test!"); testing::internal::CaptureStdout(); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp index 81ec9d14326..de3bb645801 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ProxyCommandTest.cpp @@ -14,8 +14,6 @@ using namespace frc2; class ProxyCommandTest : public CommandTestBase {}; TEST_F(ProxyCommandTest, NonOwningCommandSchedule) { - CommandScheduler& scheduler = CommandScheduler::GetInstance(); - bool scheduled = false; InstantCommand toSchedule([&scheduled] { scheduled = true; }, {}); @@ -29,8 +27,6 @@ TEST_F(ProxyCommandTest, NonOwningCommandSchedule) { } TEST_F(ProxyCommandTest, NonOwningCommandEnd) { - CommandScheduler& scheduler = CommandScheduler::GetInstance(); - bool finished = false; WaitUntilCommand toSchedule([&finished] { return finished; }); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp index b5456fad335..e6f00e5c843 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/RepeatCommandTest.cpp @@ -11,8 +11,6 @@ using namespace frc2; class RepeatCommandTest : public CommandTestBase {}; TEST_F(RepeatCommandTest, CallsMethodsCorrectly) { - CommandScheduler scheduler = GetScheduler(); - int initCounter = 0; int exeCounter = 0; int isFinishedCounter = 0; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/RobotDisabledCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/RobotDisabledCommandTest.cpp index 1595a1e6d36..be24e7adc3c 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/RobotDisabledCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/RobotDisabledCommandTest.cpp @@ -14,8 +14,6 @@ using namespace frc2; class RobotDisabledCommandTest : public CommandTestBase {}; TEST_F(RobotDisabledCommandTest, RobotDisabledCommandCancel) { - CommandScheduler scheduler = GetScheduler(); - MockCommand command({}, false, false); EXPECT_CALL(command, End(true)); @@ -35,8 +33,6 @@ TEST_F(RobotDisabledCommandTest, RobotDisabledCommandCancel) { } TEST_F(RobotDisabledCommandTest, RunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - MockCommand command1; MockCommand command2; @@ -53,8 +49,6 @@ TEST_F(RobotDisabledCommandTest, RunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, SequentialGroupRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - SequentialCommandGroup runWhenDisabled{MockCommand(), MockCommand()}; SequentialCommandGroup dontRunWhenDisabled{MockCommand(), MockCommand({}, false, false)}; @@ -69,8 +63,6 @@ TEST_F(RobotDisabledCommandTest, SequentialGroupRunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, ParallelGroupRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - ParallelCommandGroup runWhenDisabled{MockCommand(), MockCommand()}; ParallelCommandGroup dontRunWhenDisabled{MockCommand(), MockCommand({}, false, false)}; @@ -85,8 +77,6 @@ TEST_F(RobotDisabledCommandTest, ParallelGroupRunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, ParallelRaceRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - ParallelRaceGroup runWhenDisabled{MockCommand(), MockCommand()}; ParallelRaceGroup dontRunWhenDisabled{MockCommand(), MockCommand({}, false, false)}; @@ -101,8 +91,6 @@ TEST_F(RobotDisabledCommandTest, ParallelRaceRunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, ParallelDeadlineRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - ParallelDeadlineGroup runWhenDisabled{MockCommand(), MockCommand()}; ParallelDeadlineGroup dontRunWhenDisabled{MockCommand(), MockCommand({}, false, false)}; @@ -117,8 +105,6 @@ TEST_F(RobotDisabledCommandTest, ParallelDeadlineRunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, ConditionalCommandRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - ConditionalCommand runWhenDisabled{MockCommand(), MockCommand(), [] { return true; }}; ConditionalCommand dontRunWhenDisabled{ @@ -134,8 +120,6 @@ TEST_F(RobotDisabledCommandTest, ConditionalCommandRunWhenDisabled) { } TEST_F(RobotDisabledCommandTest, SelectCommandRunWhenDisabled) { - CommandScheduler scheduler = GetScheduler(); - SelectCommand runWhenDisabled{[] { return 1; }, std::pair(1, MockCommand()), std::pair(1, MockCommand())}; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp index 11d4adac76b..a321e1411b8 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/RunCommandTest.cpp @@ -9,8 +9,6 @@ using namespace frc2; class RunCommandTest : public CommandTestBase {}; TEST_F(RunCommandTest, RunCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; RunCommand command([&counter] { counter++; }, {}); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/ScheduleCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/ScheduleCommandTest.cpp index 4003b4ab498..61a4d154b8b 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/ScheduleCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/ScheduleCommandTest.cpp @@ -13,8 +13,6 @@ using namespace frc2; class ScheduleCommandTest : public CommandTestBase {}; TEST_F(ScheduleCommandTest, ScheduleCommandSchedule) { - CommandScheduler& scheduler = CommandScheduler::GetInstance(); - bool scheduled = false; InstantCommand toSchedule([&scheduled] { scheduled = true; }, {}); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp index bc4756cccc3..8225fdbf04c 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulerTest.cpp @@ -13,8 +13,6 @@ using namespace frc2; class SchedulerTest : public CommandTestBase {}; TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { - CommandScheduler scheduler = GetScheduler(); - InstantCommand command; int counter = 0; @@ -30,8 +28,6 @@ TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { } TEST_F(SchedulerTest, SchedulerLambdaInterrupt) { - CommandScheduler scheduler = GetScheduler(); - RunCommand command([] {}, {}); int counter = 0; @@ -46,8 +42,6 @@ TEST_F(SchedulerTest, SchedulerLambdaInterrupt) { } TEST_F(SchedulerTest, SchedulerLambdaInterruptNoCause) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; scheduler.OnCommandInterrupt( @@ -65,8 +59,6 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptNoCause) { } TEST_F(SchedulerTest, SchedulerLambdaInterruptCause) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; TestSubsystem subsystem{}; @@ -74,10 +66,12 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCause) { InstantCommand interruptor([] {}, {&subsystem}); scheduler.OnCommandInterrupt( - [&](const Command&, const std::optional& cause) { - ASSERT_TRUE(cause); - EXPECT_EQ(&interruptor, *cause); - counter++; + [&](const Command& interrupted, const std::optional& cause) { + if (&interrupted == &command) { + ASSERT_TRUE(cause); + EXPECT_EQ(&interruptor, *cause); + counter++; + } }); scheduler.Schedule(&command); @@ -87,8 +81,6 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCause) { } TEST_F(SchedulerTest, SchedulerLambdaInterruptCauseInRunLoop) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; TestSubsystem subsystem{}; @@ -113,11 +105,19 @@ TEST_F(SchedulerTest, SchedulerLambdaInterruptCauseInRunLoop) { EXPECT_EQ(1, counter); } -TEST_F(SchedulerTest, RegisterSubsystem) { - CommandScheduler scheduler = GetScheduler(); +class UnregisteredSubsystem : public Subsystem { + public: + explicit UnregisteredSubsystem(int& runCount) : m_runCount{runCount} {} + + void Periodic() override { ++m_runCount; } + + private: + int& m_runCount; +}; +TEST_F(SchedulerTest, RegisterSubsystem) { int counter = 0; - TestSubsystem system{[&counter] { counter++; }}; + UnregisteredSubsystem system{counter}; EXPECT_NO_FATAL_FAILURE(scheduler.RegisterSubsystem(&system)); @@ -126,10 +126,8 @@ TEST_F(SchedulerTest, RegisterSubsystem) { } TEST_F(SchedulerTest, UnregisterSubsystem) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; - TestSubsystem system{[&counter] { counter++; }}; + UnregisteredSubsystem system{counter}; scheduler.RegisterSubsystem(&system); @@ -140,8 +138,6 @@ TEST_F(SchedulerTest, UnregisterSubsystem) { } TEST_F(SchedulerTest, SchedulerCancelAll) { - CommandScheduler scheduler = GetScheduler(); - RunCommand command([] {}, {}); RunCommand command2([] {}, {}); @@ -162,8 +158,6 @@ TEST_F(SchedulerTest, SchedulerCancelAll) { } TEST_F(SchedulerTest, ScheduleScheduledNoOp) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; StartEndCommand command([&counter] { counter++; }, [] {}); @@ -192,7 +186,6 @@ class TrackDestroyCommand }; TEST_F(SchedulerTest, ScheduleCommandPtr) { - CommandScheduler scheduler = GetScheduler(); int destructionCounter = 0; int runCounter = 0; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp index 0b54c589515..2eb413dc4a8 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SchedulingRecursionTest.cpp @@ -49,7 +49,6 @@ class SelfCancellingCommand * href="https://github.com/wpilibsuite/allwpilib/issues/4259">wpilibsuite/allwpilib#4259. */ TEST_P(SchedulingRecursionTest, CancelFromInitialize) { - CommandScheduler scheduler = GetScheduler(); bool hasOtherRun = false; int counter = 0; TestSubsystem requirement; @@ -69,7 +68,6 @@ TEST_P(SchedulingRecursionTest, CancelFromInitialize) { } TEST_F(SchedulingRecursionTest, CancelFromInitializeAction) { - CommandScheduler scheduler = GetScheduler(); bool hasOtherRun = false; int counter = 0; TestSubsystem requirement; @@ -79,9 +77,8 @@ TEST_F(SchedulingRecursionTest, CancelFromInitializeAction) { [] { return false; }, {&requirement}}; RunCommand other{[&hasOtherRun] { hasOtherRun = true; }, {&requirement}}; - scheduler.OnCommandInitialize([&scheduler, &selfCancels](const Command&) { - scheduler.Cancel(&selfCancels); - }); + scheduler.OnCommandInitialize( + [this, &selfCancels](const Command&) { scheduler.Cancel(&selfCancels); }); scheduler.Schedule(&selfCancels); scheduler.Run(); scheduler.Schedule(&other); @@ -95,7 +92,6 @@ TEST_F(SchedulingRecursionTest, CancelFromInitializeAction) { TEST_P(SchedulingRecursionTest, DefaultCommandGetsRescheduledAfterSelfCanceling) { - CommandScheduler scheduler = GetScheduler(); bool hasOtherRun = false; int counter = 0; TestSubsystem requirement; @@ -130,7 +126,6 @@ class CancelEndCommand : public CommandHelper { }; TEST_F(SchedulingRecursionTest, CancelFromEnd) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; CancelEndCommand selfCancels{&scheduler, counter}; @@ -142,7 +137,6 @@ TEST_F(SchedulingRecursionTest, CancelFromEnd) { } TEST_F(SchedulingRecursionTest, CancelFromInterruptAction) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; FunctionalCommand selfCancels{[] {}, [] {}, [](bool) {}, [] { return false; }}; @@ -168,7 +162,6 @@ class EndCommand : public CommandHelper { }; TEST_F(SchedulingRecursionTest, CancelFromEndLoop) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; EndCommand dCancelsAll([&](bool) { counter++; @@ -200,7 +193,6 @@ TEST_F(SchedulingRecursionTest, CancelFromEndLoop) { } TEST_F(SchedulingRecursionTest, CancelFromEndLoopWhileInRunLoop) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; EndCommand dCancelsAll([&](bool) { counter++; @@ -250,7 +242,6 @@ class MultiCancelCommand : public CommandHelper { }; TEST_F(SchedulingRecursionTest, MultiCancelFromEnd) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; EndCommand bIncrementsCounter([&counter](bool) { counter++; }); MultiCancelCommand aCancelsB{&scheduler, counter, &bIncrementsCounter}; @@ -265,7 +256,6 @@ TEST_F(SchedulingRecursionTest, MultiCancelFromEnd) { } TEST_P(SchedulingRecursionTest, ScheduleFromEndCancel) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, @@ -279,7 +269,6 @@ TEST_P(SchedulingRecursionTest, ScheduleFromEndCancel) { } TEST_P(SchedulingRecursionTest, ScheduleFromEndInterrupt) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; TestSubsystem requirement; SelfCancellingCommand selfCancels{&scheduler, counter, &requirement, @@ -294,7 +283,6 @@ TEST_P(SchedulingRecursionTest, ScheduleFromEndInterrupt) { } TEST_F(SchedulingRecursionTest, ScheduleFromEndInterruptAction) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; TestSubsystem requirement; RunCommand selfCancels{[] {}, {&requirement}}; @@ -311,7 +299,6 @@ TEST_F(SchedulingRecursionTest, ScheduleFromEndInterruptAction) { } TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { - CommandScheduler scheduler = GetScheduler(); int counter = 0; TestSubsystem requirement; FunctionalCommand defaultCommand{[] {}, @@ -340,17 +327,15 @@ TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { } TEST_F(SchedulingRecursionTest, CancelNextCommandFromCommand) { - CommandScheduler scheduler = GetScheduler(); - frc2::RunCommand* command1Ptr = nullptr; frc2::RunCommand* command2Ptr = nullptr; int counter = 0; - auto command1 = frc2::RunCommand([&counter, &command2Ptr, &scheduler] { + auto command1 = frc2::RunCommand([this, &counter, &command2Ptr] { scheduler.Cancel(command2Ptr); counter++; }); - auto command2 = frc2::RunCommand([&counter, &command1Ptr, &scheduler] { + auto command2 = frc2::RunCommand([this, &counter, &command1Ptr] { scheduler.Cancel(command1Ptr); counter++; }); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp index dc882a0ed17..2ab62b8e662 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SelectCommandTest.cpp @@ -15,8 +15,6 @@ using namespace frc2; class SelectCommandTest : public CommandTestBase {}; TEST_F(SelectCommandTest, SelectCommand) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr mock = std::make_unique(); MockCommand* mockptr = mock.get(); @@ -41,8 +39,6 @@ TEST_F(SelectCommandTest, SelectCommand) { } TEST_F(SelectCommandTest, SelectCommandRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp index b8920c733f9..ee5b23e9bfd 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/SequentialCommandGroupTest.cpp @@ -15,8 +15,6 @@ using namespace frc2; class SequentialCommandGroupTest : public CommandTestBase {}; TEST_F(SequentialCommandGroupTest, SequentialGroupSchedule) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); @@ -54,8 +52,6 @@ TEST_F(SequentialCommandGroupTest, SequentialGroupSchedule) { } TEST_F(SequentialCommandGroupTest, SequentialGroupInterrupt) { - CommandScheduler scheduler = GetScheduler(); - std::unique_ptr command1Holder = std::make_unique(); std::unique_ptr command2Holder = std::make_unique(); std::unique_ptr command3Holder = std::make_unique(); @@ -93,16 +89,12 @@ TEST_F(SequentialCommandGroupTest, SequentialGroupInterrupt) { } TEST_F(SequentialCommandGroupTest, SequentialGroupNotScheduledCancel) { - CommandScheduler scheduler = GetScheduler(); - SequentialCommandGroup group{InstantCommand(), InstantCommand()}; EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(&group)); } TEST_F(SequentialCommandGroupTest, SequentialGroupCopy) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; WaitUntilCommand command([&finished] { return finished; }); @@ -117,8 +109,6 @@ TEST_F(SequentialCommandGroupTest, SequentialGroupCopy) { } TEST_F(SequentialCommandGroupTest, SequentialGroupRequirement) { - CommandScheduler scheduler = GetScheduler(); - TestSubsystem requirement1; TestSubsystem requirement2; TestSubsystem requirement3; diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp index 53a2df2a2ce..f0e8c99eae7 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/StartEndCommandTest.cpp @@ -9,8 +9,6 @@ using namespace frc2; class StartEndCommandTest : public CommandTestBase {}; TEST_F(StartEndCommandTest, StartEndCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - int counter = 0; StartEndCommand command([&counter] { counter++; }, [&counter] { 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..15e4e518608 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitCommandTest.cpp @@ -14,8 +14,6 @@ class WaitCommandTest : public CommandTestBase {}; TEST_F(WaitCommandTest, WaitCommandSchedule) { frc::sim::PauseTiming(); - CommandScheduler scheduler = GetScheduler(); - WaitCommand command(100_ms); scheduler.Schedule(&command); diff --git a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp index 01acc390e17..91a8139d193 100644 --- a/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp +++ b/wpilibNewCommands/src/test/native/cpp/frc2/command/WaitUntilCommandTest.cpp @@ -9,8 +9,6 @@ using namespace frc2; class WaitUntilCommandTest : public CommandTestBase {}; TEST_F(WaitUntilCommandTest, WaitUntilCommandSchedule) { - CommandScheduler scheduler = GetScheduler(); - bool finished = false; WaitUntilCommand command([&finished] { return finished; }); From 6f3bcffe737169cee94e2667222b71d9464a662b Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Sat, 28 Dec 2024 15:41:17 -0800 Subject: [PATCH 2/3] Only enable resetInstance in simulation --- .../edu/wpi/first/wpilibj2/command/CommandScheduler.java | 9 ++++++++- .../main/native/cpp/frc2/command/CommandScheduler.cpp | 7 +++++++ .../main/native/include/frc2/command/CommandScheduler.h | 3 ++- 3 files changed, 17 insertions(+), 2 deletions(-) diff --git a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java index b3707643cee..3f7beebede2 100644 --- a/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java +++ b/wpilibNewCommands/src/main/java/edu/wpi/first/wpilibj2/command/CommandScheduler.java @@ -64,9 +64,16 @@ public static synchronized CommandScheduler getInstance() { /** * Resets the Scheduler instance, which is useful for testing purposes. This should not be called - * from user code. + * from user code and will only work when simulating code. */ public static synchronized void resetInstance() { + if (!RobotBase.isSimulation()) { + DriverStation.reportWarning( + "Ignored call to CommandScheduler.resetInstance() outside of simulation! " + + "CommandScheduler.resetInstance() should only be used for unit test setup.", + true); + return; + } if (instance != null) { instance.close(); } diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 002a67fa6f0..d7e1ad32dc4 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -10,6 +10,7 @@ #include #include +#include #include #include #include @@ -94,6 +95,12 @@ CommandScheduler& CommandScheduler::GetInstance() { } void CommandScheduler::ResetInstance() { + if (!frc::RobotBase::IsSimulation()) { + FRC_ReportWarning( + "Ignoring call to frc2::CommandScheduler::ResetInstance() outside of " + "simulation! frc2::CommandScheduler::ResetInstance() should only be " + "used for unit test setup."); + } std::make_unique().swap(GetInstance().m_impl); } diff --git a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h index c1676e8aa4f..5e5c234f9b7 100644 --- a/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h +++ b/wpilibNewCommands/src/main/native/include/frc2/command/CommandScheduler.h @@ -45,7 +45,8 @@ class CommandScheduler final : public wpi::Sendable, static CommandScheduler& GetInstance(); /** Resets the Scheduler instance, which is useful for testing purposes. This - * should not be called from user code. */ + * should not be called from user code and will only work when simulating + * code. */ static void ResetInstance(); ~CommandScheduler() override; From e72b6b0342727b235d46c97cb7d8efee667243b4 Mon Sep 17 00:00:00 2001 From: Joseph Eng Date: Wed, 8 Jan 2025 17:04:02 -0800 Subject: [PATCH 3/3] Add return to C++ CommandScheduler::ResetInstance() --- .../src/main/native/cpp/frc2/command/CommandScheduler.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp index d7e1ad32dc4..d8bb956440e 100644 --- a/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/wpilibNewCommands/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -100,6 +100,7 @@ void CommandScheduler::ResetInstance() { "Ignoring call to frc2::CommandScheduler::ResetInstance() outside of " "simulation! frc2::CommandScheduler::ResetInstance() should only be " "used for unit test setup."); + return; } std::make_unique().swap(GetInstance().m_impl); }