mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-21 01:01:43 +00:00
SCRIPT Move subprojects
This commit is contained in:
committed by
Peter Johnson
parent
8cfc158790
commit
a5492d30da
@@ -0,0 +1,39 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
|
||||
import org.junit.jupiter.api.extension.BeforeAllCallback;
|
||||
import org.junit.jupiter.api.extension.ExtensionContext;
|
||||
import org.junit.jupiter.api.extension.ExtensionContext.Namespace;
|
||||
|
||||
public final class MockHardwareExtension implements BeforeAllCallback {
|
||||
private static ExtensionContext getRoot(ExtensionContext context) {
|
||||
return context.getParent().map(MockHardwareExtension::getRoot).orElse(context);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void beforeAll(ExtensionContext context) {
|
||||
getRoot(context)
|
||||
.getStore(Namespace.GLOBAL)
|
||||
.getOrComputeIfAbsent(
|
||||
"HAL Initialized",
|
||||
key -> {
|
||||
initializeHardware();
|
||||
return true;
|
||||
},
|
||||
Boolean.class);
|
||||
}
|
||||
|
||||
private void initializeHardware() {
|
||||
HAL.initialize(500, 0);
|
||||
DriverStationSim.setDsAttached(true);
|
||||
DriverStationSim.setAutonomous(false);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.setTest(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,539 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertAll;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.api.parallel.ResourceLock;
|
||||
|
||||
class CommandDecoratorTest extends CommandTestBase {
|
||||
@Test
|
||||
@ResourceLock("timing")
|
||||
void withTimeoutTest() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Command timeout = Commands.idle().withTimeout(0.1);
|
||||
|
||||
scheduler.schedule(timeout);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(timeout));
|
||||
|
||||
SimHooks.stepTiming(0.15);
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(timeout));
|
||||
} finally {
|
||||
SimHooks.resumeTiming();
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void untilTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finish = new AtomicBoolean();
|
||||
|
||||
Command command = Commands.idle().until(finish::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
|
||||
finish.set(true);
|
||||
scheduler.run();
|
||||
|
||||
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()));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void onlyWhileTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean run = new AtomicBoolean(true);
|
||||
|
||||
Command command = Commands.idle().onlyWhile(run::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
|
||||
run.set(false);
|
||||
scheduler.run();
|
||||
|
||||
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()));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void ignoringDisableTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
var command = Commands.idle().ignoringDisable(true);
|
||||
|
||||
setDSEnabled(false);
|
||||
|
||||
scheduler.schedule(command);
|
||||
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void beforeStartingTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finished = new AtomicBoolean();
|
||||
finished.set(false);
|
||||
|
||||
Command command = Commands.none().beforeStarting(() -> finished.set(true));
|
||||
|
||||
scheduler.schedule(command);
|
||||
|
||||
assertTrue(finished.get());
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void andThenLambdaTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finished = new AtomicBoolean(false);
|
||||
|
||||
Command command = Commands.none().andThen(() -> finished.set(true));
|
||||
|
||||
scheduler.schedule(command);
|
||||
|
||||
assertFalse(finished.get());
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(finished.get());
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void andThenTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean condition = new AtomicBoolean(false);
|
||||
|
||||
Command command1 = Commands.none();
|
||||
Command command2 = Commands.runOnce(() -> condition.set(true));
|
||||
Command group = command1.andThen(command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
assertFalse(condition.get());
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(condition.get());
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void deadlineForTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finish = new AtomicBoolean(false);
|
||||
|
||||
Command dictator = Commands.waitUntil(finish::get);
|
||||
Command endsBefore = Commands.none();
|
||||
Command endsAfter = Commands.idle();
|
||||
|
||||
Command group = dictator.deadlineFor(endsBefore, endsAfter);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(group));
|
||||
|
||||
finish.set(true);
|
||||
scheduler.run();
|
||||
|
||||
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 =
|
||||
Commands.run(
|
||||
() ->
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@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()));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void alongWithTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean finish = new AtomicBoolean(false);
|
||||
|
||||
Command command1 = Commands.waitUntil(finish::get);
|
||||
Command command2 = Commands.none();
|
||||
|
||||
Command group = command1.alongWith(command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(group));
|
||||
|
||||
finish.set(true);
|
||||
scheduler.run();
|
||||
|
||||
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 =
|
||||
Commands.run(
|
||||
() ->
|
||||
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 = Commands.idle();
|
||||
Command command2 = Commands.none();
|
||||
|
||||
Command group = command1.raceWith(command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.run();
|
||||
|
||||
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 =
|
||||
Commands.run(
|
||||
() -> {
|
||||
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);
|
||||
|
||||
Command command = Commands.runOnce(() -> hasRun.set(true)).unless(unlessCondition::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
assertFalse(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);
|
||||
|
||||
Command command = Commands.runOnce(() -> hasRun.set(true)).onlyIf(onlyIfCondition::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
assertFalse(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());
|
||||
}
|
||||
}
|
||||
|
||||
// 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());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void withNameTest() {
|
||||
Command command = Commands.none();
|
||||
String name = "Named";
|
||||
Command named = command.withName(name);
|
||||
assertEquals(name, named.getName());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,73 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class CommandRequirementsTest extends CommandTestBase {
|
||||
@Test
|
||||
void requirementInterruptTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
|
||||
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();
|
||||
|
||||
verify(interrupted).initialize();
|
||||
verify(interrupted).execute();
|
||||
verify(interrupted).end(true);
|
||||
|
||||
verify(interrupter).initialize();
|
||||
verify(interrupter).execute();
|
||||
|
||||
assertFalse(scheduler.isScheduled(interrupted));
|
||||
assertTrue(scheduler.isScheduled(interrupter));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void requirementUninterruptibleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
|
||||
Command notInterrupted =
|
||||
Commands.idle(requirement)
|
||||
.withInterruptBehavior(Command.InterruptionBehavior.kCancelIncoming);
|
||||
MockCommandHolder interrupterHolder = new MockCommandHolder(true, requirement);
|
||||
Command interrupter = interrupterHolder.getMock();
|
||||
|
||||
scheduler.schedule(notInterrupted);
|
||||
scheduler.schedule(interrupter);
|
||||
|
||||
assertTrue(scheduler.isScheduled(notInterrupted));
|
||||
assertFalse(scheduler.isScheduled(interrupter));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void defaultCommandRequirementErrorTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem system = new SubsystemBase() {};
|
||||
|
||||
Command missingRequirement = Commands.idle();
|
||||
|
||||
assertThrows(
|
||||
IllegalArgumentException.class,
|
||||
() -> scheduler.setDefaultCommand(system, missingRequirement));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,144 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.times;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class CommandScheduleTest extends CommandTestBase {
|
||||
@Test
|
||||
void instantScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
holder.setFinished(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
scheduler.schedule(mockCommand);
|
||||
assertTrue(scheduler.isScheduled(mockCommand));
|
||||
verify(mockCommand).initialize();
|
||||
|
||||
scheduler.run();
|
||||
|
||||
verify(mockCommand).execute();
|
||||
verify(mockCommand).end(false);
|
||||
|
||||
assertFalse(scheduler.isScheduled(mockCommand));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void singleIterationScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
scheduler.schedule(mockCommand);
|
||||
|
||||
assertTrue(scheduler.isScheduled(mockCommand));
|
||||
|
||||
scheduler.run();
|
||||
holder.setFinished(true);
|
||||
scheduler.run();
|
||||
|
||||
verify(mockCommand).initialize();
|
||||
verify(mockCommand, times(2)).execute();
|
||||
verify(mockCommand).end(false);
|
||||
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void schedulerCancelTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
scheduler.schedule(mockCommand);
|
||||
|
||||
scheduler.run();
|
||||
scheduler.cancel(mockCommand);
|
||||
scheduler.run();
|
||||
|
||||
verify(mockCommand).execute();
|
||||
verify(mockCommand).end(true);
|
||||
verify(mockCommand, never()).end(false);
|
||||
|
||||
assertFalse(scheduler.isScheduled(mockCommand));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void notScheduledCancelTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
assertDoesNotThrow(() -> scheduler.cancel(mockCommand));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void smartDashboardCancelTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler();
|
||||
var inst = NetworkTableInstance.create()) {
|
||||
SmartDashboard.setNetworkTableInstance(inst);
|
||||
SmartDashboard.putData("Scheduler", scheduler);
|
||||
SmartDashboard.updateValues();
|
||||
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
scheduler.schedule(mockCommand);
|
||||
scheduler.run();
|
||||
SmartDashboard.updateValues();
|
||||
assertTrue(scheduler.isScheduled(mockCommand));
|
||||
|
||||
var table = inst.getTable("SmartDashboard");
|
||||
table.getEntry("Scheduler/Cancel").setIntegerArray(new long[] {mockCommand.hashCode()});
|
||||
SmartDashboard.updateValues();
|
||||
scheduler.run();
|
||||
assertFalse(scheduler.isScheduled(mockCommand));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,189 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertSame;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class CommandSchedulerTest extends CommandTestBase {
|
||||
@Test
|
||||
void schedulerLambdaTestNoInterrupt() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
scheduler.onCommandInitialize(command -> counter.incrementAndGet());
|
||||
scheduler.onCommandExecute(command -> counter.incrementAndGet());
|
||||
scheduler.onCommandFinish(command -> counter.incrementAndGet());
|
||||
|
||||
scheduler.schedule(Commands.none());
|
||||
scheduler.run();
|
||||
|
||||
assertEquals(counter.get(), 3);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void schedulerInterruptLambdaTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
scheduler.onCommandInterrupt(command -> counter.incrementAndGet());
|
||||
|
||||
Command command = Commands.idle();
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.cancel(command);
|
||||
|
||||
assertEquals(counter.get(), 1);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void schedulerInterruptNoCauseLambdaTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
scheduler.onCommandInterrupt(
|
||||
(interrupted, cause) -> {
|
||||
assertFalse(cause.isPresent());
|
||||
counter.incrementAndGet();
|
||||
});
|
||||
|
||||
Command command = Commands.run(() -> {});
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.cancel(command);
|
||||
|
||||
assertEquals(1, counter.get());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void schedulerInterruptCauseLambdaTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
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.schedule(command);
|
||||
scheduler.schedule(interruptor);
|
||||
|
||||
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();
|
||||
});
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.schedule(interruptorScheduler);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
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());
|
||||
}
|
||||
}
|
||||
|
||||
@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());
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void schedulerCancelAllTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
scheduler.onCommandInterrupt(command -> counter.incrementAndGet());
|
||||
scheduler.onCommandInterrupt((command, interruptor) -> assertFalse(interruptor.isPresent()));
|
||||
|
||||
Command command = Commands.idle();
|
||||
Command command2 = Commands.idle();
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.schedule(command2);
|
||||
scheduler.cancelAll();
|
||||
|
||||
assertEquals(counter.get(), 2);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void scheduleScheduledNoOp() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
|
||||
Command command = Commands.startEnd(counter::incrementAndGet, () -> {});
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.schedule(command);
|
||||
|
||||
assertEquals(counter.get(), 1);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,114 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.networktables.BooleanPublisher;
|
||||
import edu.wpi.first.networktables.NetworkTableInstance;
|
||||
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class CommandSendableButtonTest extends CommandTestBase {
|
||||
private NetworkTableInstance m_inst;
|
||||
private AtomicInteger m_schedule;
|
||||
private AtomicInteger m_cancel;
|
||||
private BooleanPublisher m_publish;
|
||||
private Command m_command;
|
||||
|
||||
@BeforeEach
|
||||
void setUp() {
|
||||
m_inst = NetworkTableInstance.create();
|
||||
SmartDashboard.setNetworkTableInstance(m_inst);
|
||||
m_schedule = new AtomicInteger();
|
||||
m_cancel = new AtomicInteger();
|
||||
m_command = Commands.startEnd(m_schedule::incrementAndGet, m_cancel::incrementAndGet);
|
||||
m_publish = m_inst.getBooleanTopic("/SmartDashboard/command/running").publish();
|
||||
SmartDashboard.putData("command", m_command);
|
||||
SmartDashboard.updateValues();
|
||||
}
|
||||
|
||||
@Test
|
||||
void trueAndNotScheduledSchedules() {
|
||||
// Not scheduled and true -> scheduled
|
||||
CommandScheduler.getInstance().run();
|
||||
SmartDashboard.updateValues();
|
||||
assertFalse(m_command.isScheduled());
|
||||
assertEquals(0, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
|
||||
m_publish.set(true);
|
||||
SmartDashboard.updateValues();
|
||||
CommandScheduler.getInstance().run();
|
||||
assertTrue(m_command.isScheduled());
|
||||
assertEquals(1, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void trueAndScheduledNoOp() {
|
||||
// Scheduled and true -> no-op
|
||||
CommandScheduler.getInstance().schedule(m_command);
|
||||
CommandScheduler.getInstance().run();
|
||||
SmartDashboard.updateValues();
|
||||
assertTrue(m_command.isScheduled());
|
||||
assertEquals(1, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
|
||||
m_publish.set(true);
|
||||
SmartDashboard.updateValues();
|
||||
CommandScheduler.getInstance().run();
|
||||
assertTrue(m_command.isScheduled());
|
||||
assertEquals(1, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void falseAndNotScheduledNoOp() {
|
||||
// Not scheduled and false -> no-op
|
||||
CommandScheduler.getInstance().run();
|
||||
SmartDashboard.updateValues();
|
||||
assertFalse(m_command.isScheduled());
|
||||
assertEquals(0, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
|
||||
m_publish.set(false);
|
||||
SmartDashboard.updateValues();
|
||||
CommandScheduler.getInstance().run();
|
||||
assertFalse(m_command.isScheduled());
|
||||
assertEquals(0, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void falseAndScheduledCancel() {
|
||||
// Scheduled and false -> cancel
|
||||
CommandScheduler.getInstance().schedule(m_command);
|
||||
CommandScheduler.getInstance().run();
|
||||
SmartDashboard.updateValues();
|
||||
assertTrue(m_command.isScheduled());
|
||||
assertEquals(1, m_schedule.get());
|
||||
assertEquals(0, m_cancel.get());
|
||||
|
||||
m_publish.set(false);
|
||||
SmartDashboard.updateValues();
|
||||
CommandScheduler.getInstance().run();
|
||||
assertFalse(m_command.isScheduled());
|
||||
assertEquals(1, m_schedule.get());
|
||||
assertEquals(1, m_cancel.get());
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void tearDown() {
|
||||
m_publish.close();
|
||||
m_inst.close();
|
||||
SmartDashboard.setNetworkTableInstance(NetworkTableInstance.getDefault());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,63 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.mockito.Mockito.mock;
|
||||
import static org.mockito.Mockito.when;
|
||||
|
||||
import edu.wpi.first.wpilibj.DriverStation;
|
||||
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
|
||||
import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
|
||||
import java.util.Set;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
|
||||
/** Basic setup for all {@link Command tests}. */
|
||||
public class CommandTestBase {
|
||||
protected CommandTestBase() {}
|
||||
|
||||
@BeforeEach
|
||||
void commandSetup() {
|
||||
CommandScheduler.getInstance().cancelAll();
|
||||
CommandScheduler.getInstance().enable();
|
||||
CommandScheduler.getInstance().getActiveButtonLoop().clear();
|
||||
CommandScheduler.getInstance().clearComposedCommands();
|
||||
CommandScheduler.getInstance().unregisterAllSubsystems();
|
||||
|
||||
setDSEnabled(true);
|
||||
}
|
||||
|
||||
public void setDSEnabled(boolean enabled) {
|
||||
DriverStationSim.setDsAttached(true);
|
||||
|
||||
DriverStationSim.setEnabled(enabled);
|
||||
DriverStationSim.notifyNewData();
|
||||
while (DriverStation.isEnabled() != enabled) {
|
||||
try {
|
||||
Thread.sleep(1);
|
||||
} catch (InterruptedException exception) {
|
||||
exception.printStackTrace();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
public static class MockCommandHolder {
|
||||
private final Command m_mockCommand = mock(Command.class);
|
||||
|
||||
public MockCommandHolder(boolean runWhenDisabled, Subsystem... requirements) {
|
||||
when(m_mockCommand.getRequirements()).thenReturn(Set.of(requirements));
|
||||
when(m_mockCommand.isFinished()).thenReturn(false);
|
||||
when(m_mockCommand.runsWhenDisabled()).thenReturn(runWhenDisabled);
|
||||
when(m_mockCommand.getInterruptionBehavior()).thenReturn(InterruptionBehavior.kCancelSelf);
|
||||
}
|
||||
|
||||
public Command getMock() {
|
||||
return m_mockCommand;
|
||||
}
|
||||
|
||||
public void setFinished(boolean finished) {
|
||||
when(m_mockCommand.isFinished()).thenReturn(finished);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,151 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.params.provider.Arguments.arguments;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import java.util.stream.Stream;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.Arguments;
|
||||
import org.junit.jupiter.params.provider.MethodSource;
|
||||
|
||||
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);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void conditionalCommandRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
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();
|
||||
|
||||
ConditionalCommand conditionalCommand =
|
||||
new ConditionalCommand(command1, command2, () -> true);
|
||||
|
||||
scheduler.schedule(conditionalCommand);
|
||||
scheduler.schedule(new InstantCommand(() -> {}, system3));
|
||||
|
||||
assertFalse(scheduler.isScheduled(conditionalCommand));
|
||||
|
||||
verify(command1).end(true);
|
||||
verify(command2, never()).end(true);
|
||||
}
|
||||
}
|
||||
|
||||
static Stream<Arguments> interruptible() {
|
||||
return Stream.of(
|
||||
arguments(
|
||||
"AllCancelSelf",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"AllCancelIncoming",
|
||||
InterruptionBehavior.kCancelIncoming,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"OneCancelSelfOneIncoming",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"OneCancelIncomingOneSelf",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
(BooleanSupplier) () -> true));
|
||||
}
|
||||
|
||||
@MethodSource
|
||||
@ParameterizedTest(name = "interruptible[{index}]: {0}")
|
||||
void interruptible(
|
||||
@SuppressWarnings("unused") String name,
|
||||
InterruptionBehavior expected,
|
||||
Command command1,
|
||||
Command command2,
|
||||
BooleanSupplier selector) {
|
||||
var command = Commands.either(command1, command2, selector);
|
||||
assertEquals(expected, command.getInterruptionBehavior());
|
||||
}
|
||||
|
||||
static Stream<Arguments> runsWhenDisabled() {
|
||||
return Stream.of(
|
||||
arguments(
|
||||
"AllFalse",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(false),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"AllTrue",
|
||||
true,
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(true),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"OneTrueOneFalse",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(false),
|
||||
(BooleanSupplier) () -> true),
|
||||
arguments(
|
||||
"OneFalseOneTrue",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(true),
|
||||
(BooleanSupplier) () -> true));
|
||||
}
|
||||
|
||||
@MethodSource
|
||||
@ParameterizedTest(name = "runsWhenDisabled[{index}]: {0}")
|
||||
void runsWhenDisabled(
|
||||
@SuppressWarnings("unused") String name,
|
||||
boolean expected,
|
||||
Command command1,
|
||||
Command command2,
|
||||
BooleanSupplier selector) {
|
||||
var command = Commands.either(command1, command2, selector);
|
||||
assertEquals(expected, command.runsWhenDisabled());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,80 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class DefaultCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void defaultCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder defaultHolder = new MockCommandHolder(true, hasDefaultCommand);
|
||||
Command defaultCommand = defaultHolder.getMock();
|
||||
|
||||
scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(defaultCommand));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void defaultCommandInterruptResumeTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
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);
|
||||
|
||||
assertFalse(scheduler.isScheduled(defaultCommand));
|
||||
assertTrue(scheduler.isScheduled(interrupter));
|
||||
|
||||
scheduler.cancel(interrupter);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(defaultCommand));
|
||||
assertFalse(scheduler.isScheduled(interrupter));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void defaultCommandDisableResumeTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Subsystem hasDefaultCommand = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder defaultHolder = new MockCommandHolder(false, hasDefaultCommand);
|
||||
Command defaultCommand = defaultHolder.getMock();
|
||||
|
||||
scheduler.setDefaultCommand(hasDefaultCommand, defaultCommand);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(defaultCommand));
|
||||
|
||||
setDSEnabled(false);
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(defaultCommand));
|
||||
|
||||
setDSEnabled(true);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(defaultCommand));
|
||||
|
||||
verify(defaultCommand).end(true);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,85 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.mock;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.only;
|
||||
import static org.mockito.Mockito.times;
|
||||
import static org.mockito.Mockito.verify;
|
||||
import static org.mockito.Mockito.when;
|
||||
|
||||
import java.util.Set;
|
||||
import java.util.function.Supplier;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.ValueSource;
|
||||
|
||||
class DeferredCommandTest extends CommandTestBase {
|
||||
@ParameterizedTest
|
||||
@ValueSource(booleans = {true, false})
|
||||
void deferredFunctionsTest(boolean interrupted) {
|
||||
MockCommandHolder innerCommand = new MockCommandHolder(false);
|
||||
DeferredCommand command = new DeferredCommand(innerCommand::getMock, Set.of());
|
||||
|
||||
command.initialize();
|
||||
verify(innerCommand.getMock()).initialize();
|
||||
|
||||
command.execute();
|
||||
verify(innerCommand.getMock()).execute();
|
||||
|
||||
assertFalse(command.isFinished());
|
||||
verify(innerCommand.getMock()).isFinished();
|
||||
|
||||
innerCommand.setFinished(true);
|
||||
assertTrue(command.isFinished());
|
||||
verify(innerCommand.getMock(), times(2)).isFinished();
|
||||
|
||||
command.end(interrupted);
|
||||
verify(innerCommand.getMock()).end(interrupted);
|
||||
}
|
||||
|
||||
@SuppressWarnings("unchecked")
|
||||
@Test
|
||||
void deferredSupplierOnlyCalledDuringInit() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Supplier<Command> supplier = (Supplier<Command>) mock(Supplier.class);
|
||||
when(supplier.get()).thenReturn(Commands.none(), Commands.none());
|
||||
|
||||
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, times(2)).get();
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void deferredRequirementsTest() {
|
||||
Subsystem subsystem = new Subsystem() {};
|
||||
DeferredCommand command = new DeferredCommand(Commands::none, Set.of(subsystem));
|
||||
|
||||
assertTrue(command.getRequirements().contains(subsystem));
|
||||
}
|
||||
|
||||
@Test
|
||||
void deferredNullCommandTest() {
|
||||
DeferredCommand command = new DeferredCommand(() -> null, Set.of());
|
||||
assertDoesNotThrow(
|
||||
() -> {
|
||||
command.initialize();
|
||||
command.execute();
|
||||
command.isFinished();
|
||||
command.end(false);
|
||||
});
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,44 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
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();
|
||||
|
||||
FunctionalCommand command =
|
||||
new FunctionalCommand(
|
||||
() -> cond1.set(true),
|
||||
() -> cond2.set(true),
|
||||
interrupted -> cond3.set(true),
|
||||
cond4::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
|
||||
cond4.set(true);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
assertTrue(cond1.get());
|
||||
assertTrue(cond2.get());
|
||||
assertTrue(cond3.get());
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,28 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class InstantCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void instantCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean cond = new AtomicBoolean();
|
||||
|
||||
InstantCommand command = new InstantCommand(() -> cond.set(true));
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(cond.get());
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,119 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
import static org.junit.jupiter.params.provider.Arguments.arguments;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
|
||||
import java.util.stream.Stream;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.Arguments;
|
||||
import org.junit.jupiter.params.provider.MethodSource;
|
||||
|
||||
abstract class MultiCompositionTestBase<T extends Command> extends SingleCompositionTestBase<T> {
|
||||
abstract T compose(Command... members);
|
||||
|
||||
@Override
|
||||
T composeSingle(Command member) {
|
||||
return compose(member);
|
||||
}
|
||||
|
||||
static Stream<Arguments> interruptible() {
|
||||
return Stream.of(
|
||||
arguments(
|
||||
"AllCancelSelf",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf)),
|
||||
arguments(
|
||||
"AllCancelIncoming",
|
||||
InterruptionBehavior.kCancelIncoming,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming)),
|
||||
arguments(
|
||||
"TwoCancelSelfOneIncoming",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming)),
|
||||
arguments(
|
||||
"TwoCancelIncomingOneSelf",
|
||||
InterruptionBehavior.kCancelSelf,
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelIncoming),
|
||||
Commands.idle().withInterruptBehavior(InterruptionBehavior.kCancelSelf)));
|
||||
}
|
||||
|
||||
@MethodSource
|
||||
@ParameterizedTest(name = "interruptible[{index}]: {0}")
|
||||
void interruptible(
|
||||
@SuppressWarnings("unused") String name,
|
||||
InterruptionBehavior expected,
|
||||
Command command1,
|
||||
Command command2,
|
||||
Command command3) {
|
||||
var command = compose(command1, command2, command3);
|
||||
assertEquals(expected, command.getInterruptionBehavior());
|
||||
}
|
||||
|
||||
static Stream<Arguments> runsWhenDisabled() {
|
||||
return Stream.of(
|
||||
arguments(
|
||||
"AllFalse",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(false)),
|
||||
arguments(
|
||||
"AllTrue",
|
||||
true,
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(true)),
|
||||
arguments(
|
||||
"TwoTrueOneFalse",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(true),
|
||||
Commands.idle().ignoringDisable(false)),
|
||||
arguments(
|
||||
"TwoFalseOneTrue",
|
||||
false,
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(false),
|
||||
Commands.idle().ignoringDisable(true)));
|
||||
}
|
||||
|
||||
@MethodSource
|
||||
@ParameterizedTest(name = "runsWhenDisabled[{index}]: {0}")
|
||||
void runsWhenDisabled(
|
||||
@SuppressWarnings("unused") String name,
|
||||
boolean expected,
|
||||
Command command1,
|
||||
Command command2,
|
||||
Command command3) {
|
||||
var command = compose(command1, command2, command3);
|
||||
assertEquals(expected, command.runsWhenDisabled());
|
||||
}
|
||||
|
||||
static Stream<Arguments> composeDuplicates() {
|
||||
Command a = Commands.none();
|
||||
Command b = Commands.none();
|
||||
return Stream.of(
|
||||
arguments("AA", new Command[] {a, a}),
|
||||
arguments("ABA", new Command[] {a, b, a}),
|
||||
arguments("BAA", new Command[] {b, a, a}));
|
||||
}
|
||||
|
||||
@MethodSource
|
||||
@ParameterizedTest(name = "composeDuplicates[{index}]: {0}")
|
||||
void composeDuplicates(@SuppressWarnings("unused") String name, Command[] commands) {
|
||||
assertThrows(IllegalArgumentException.class, () -> compose(commands));
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,46 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.api.parallel.ResourceLock;
|
||||
|
||||
class NotifierCommandTest extends CommandTestBase {
|
||||
@BeforeEach
|
||||
void setup() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void cleanup() {
|
||||
SimHooks.resumeTiming();
|
||||
}
|
||||
|
||||
@Test
|
||||
@ResourceLock("timing")
|
||||
void notifierCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
|
||||
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());
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,134 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.times;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ParallelCommandGroupTest extends MultiCompositionTestBase<ParallelCommandGroup> {
|
||||
@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();
|
||||
|
||||
Command group = new ParallelCommandGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2).initialize();
|
||||
|
||||
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);
|
||||
|
||||
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();
|
||||
|
||||
Command group = new ParallelCommandGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
command1Holder.setFinished(true);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
scheduler.cancel(group);
|
||||
|
||||
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);
|
||||
|
||||
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();
|
||||
|
||||
Command group = new ParallelCommandGroup(command1, command2);
|
||||
|
||||
assertDoesNotThrow(() -> scheduler.cancel(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelGroupRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
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();
|
||||
|
||||
Command group = new ParallelCommandGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.schedule(command3);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
assertTrue(scheduler.isScheduled(command3));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelGroupRequirementErrorTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
MockCommandHolder command2Holder = new MockCommandHolder(true, system2, system3);
|
||||
Command command2 = command2Holder.getMock();
|
||||
|
||||
assertThrows(
|
||||
IllegalArgumentException.class, () -> new ParallelCommandGroup(command1, command2));
|
||||
}
|
||||
|
||||
@Override
|
||||
public ParallelCommandGroup compose(Command... members) {
|
||||
return new ParallelCommandGroup(members);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,147 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
import static org.mockito.internal.verification.VerificationModeFactory.times;
|
||||
|
||||
import java.util.Arrays;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ParallelDeadlineGroupTest extends MultiCompositionTestBase<ParallelDeadlineGroup> {
|
||||
@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);
|
||||
}
|
||||
}
|
||||
|
||||
@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);
|
||||
|
||||
Command group = new ParallelDeadlineGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
scheduler.cancel(group);
|
||||
|
||||
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);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelDeadlineRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
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();
|
||||
|
||||
Command group = new ParallelDeadlineGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.schedule(command3);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
assertTrue(scheduler.isScheduled(command3));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelDeadlineRequirementErrorTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
MockCommandHolder command2Holder = new MockCommandHolder(true, system2, system3);
|
||||
Command command2 = command2Holder.getMock();
|
||||
|
||||
assertThrows(
|
||||
IllegalArgumentException.class, () -> new ParallelDeadlineGroup(command1, command2));
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelDeadlineSetDeadlineToDeadlineTest() {
|
||||
Command a = Commands.none();
|
||||
ParallelDeadlineGroup group = new ParallelDeadlineGroup(a);
|
||||
assertDoesNotThrow(() -> group.setDeadline(a));
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelDeadlineSetDeadlineDuplicateTest() {
|
||||
Command a = Commands.none();
|
||||
Command b = Commands.none();
|
||||
ParallelDeadlineGroup group = new ParallelDeadlineGroup(a, b);
|
||||
assertThrows(IllegalArgumentException.class, () -> group.setDeadline(b));
|
||||
}
|
||||
|
||||
@Override
|
||||
public ParallelDeadlineGroup compose(Command... members) {
|
||||
return new ParallelDeadlineGroup(members[0], Arrays.copyOfRange(members, 1, members.length));
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,210 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertNotNull;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.reset;
|
||||
import static org.mockito.Mockito.times;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ParallelRaceGroupTest extends MultiCompositionTestBase<ParallelRaceGroup> {
|
||||
@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();
|
||||
|
||||
Command group = new ParallelRaceGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2).initialize();
|
||||
|
||||
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);
|
||||
|
||||
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();
|
||||
|
||||
Command group = new ParallelRaceGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
scheduler.cancel(group);
|
||||
|
||||
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);
|
||||
|
||||
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();
|
||||
|
||||
Command group = new ParallelRaceGroup(command1, command2);
|
||||
|
||||
assertDoesNotThrow(() -> scheduler.cancel(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelRaceRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
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();
|
||||
|
||||
Command group = new ParallelRaceGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.schedule(command3);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
assertTrue(scheduler.isScheduled(command3));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelRaceRequirementErrorTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
Subsystem system3 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1, system2);
|
||||
Command command1 = command1Holder.getMock();
|
||||
MockCommandHolder command2Holder = new MockCommandHolder(true, system2, system3);
|
||||
Command command2 = command2Holder.getMock();
|
||||
|
||||
assertThrows(IllegalArgumentException.class, () -> new ParallelRaceGroup(command1, command2));
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelRaceOnlyCallsEndOnceTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true, system1);
|
||||
Command command1 = command1Holder.getMock();
|
||||
MockCommandHolder command2Holder = new MockCommandHolder(true, system2);
|
||||
Command command2 = command2Holder.getMock();
|
||||
MockCommandHolder command3Holder = new MockCommandHolder(true);
|
||||
Command command3 = command3Holder.getMock();
|
||||
|
||||
Command group1 = Commands.sequence(command1, command2);
|
||||
assertNotNull(group1);
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@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();
|
||||
|
||||
Command group = new ParallelRaceGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2).initialize();
|
||||
|
||||
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);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
|
||||
reset(command1);
|
||||
reset(command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2).initialize();
|
||||
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(group));
|
||||
command2Holder.setFinished(true);
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public ParallelRaceGroup compose(Command... members) {
|
||||
return new ParallelRaceGroup(members);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,34 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
|
||||
import java.io.ByteArrayOutputStream;
|
||||
import java.io.PrintStream;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
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!");
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
assertEquals(testOut.toString(), "Test!" + System.lineSeparator());
|
||||
} finally {
|
||||
System.setOut(originalOut);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,49 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class ProxyCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void proxyCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder command1Holder = new MockCommandHolder(true);
|
||||
Command command1 = command1Holder.getMock();
|
||||
|
||||
ProxyCommand scheduleCommand = new ProxyCommand(command1);
|
||||
|
||||
scheduler.schedule(scheduleCommand);
|
||||
|
||||
verify(command1).initialize();
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void proxyCommandEndTest() {
|
||||
try (CommandScheduler scheduler = CommandScheduler.getInstance()) {
|
||||
AtomicBoolean cond = new AtomicBoolean();
|
||||
|
||||
Command command = Commands.waitUntil(cond::get);
|
||||
|
||||
ProxyCommand scheduleCommand = new ProxyCommand(command);
|
||||
|
||||
scheduler.schedule(scheduleCommand);
|
||||
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(scheduleCommand));
|
||||
|
||||
cond.set(true);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
assertFalse(scheduler.isScheduled(scheduleCommand));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,85 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class RepeatCommandTest extends SingleCompositionTestBase<RepeatCommand> {
|
||||
@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);
|
||||
|
||||
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());
|
||||
|
||||
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(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(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());
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public RepeatCommand composeSingle(Command member) {
|
||||
return member.repeatedly();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,179 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static edu.wpi.first.wpilibj2.command.Commands.parallel;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.Map;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class RobotDisabledCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void robotDisabledCommandCancelTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(false);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
scheduler.schedule(mockCommand);
|
||||
|
||||
assertTrue(scheduler.isScheduled(mockCommand));
|
||||
|
||||
setDSEnabled(false);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertFalse(scheduler.isScheduled(mockCommand));
|
||||
|
||||
setDSEnabled(true);
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void runWhenDisabledTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
MockCommandHolder holder = new MockCommandHolder(true);
|
||||
Command mockCommand = holder.getMock();
|
||||
|
||||
scheduler.schedule(mockCommand);
|
||||
|
||||
assertTrue(scheduler.isScheduled(mockCommand));
|
||||
|
||||
setDSEnabled(false);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
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();
|
||||
|
||||
Command runWhenDisabled = new SequentialCommandGroup(command1, command2);
|
||||
Command dontRunWhenDisabled = new SequentialCommandGroup(command3, command4);
|
||||
|
||||
scheduler.schedule(runWhenDisabled);
|
||||
scheduler.schedule(dontRunWhenDisabled);
|
||||
|
||||
setDSEnabled(false);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
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();
|
||||
|
||||
Command runWhenDisabled = new ParallelCommandGroup(command1, command2);
|
||||
Command dontRunWhenDisabled = new ParallelCommandGroup(command3, command4);
|
||||
|
||||
scheduler.schedule(runWhenDisabled);
|
||||
scheduler.schedule(dontRunWhenDisabled);
|
||||
|
||||
setDSEnabled(false);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(runWhenDisabled));
|
||||
assertFalse(scheduler.isScheduled(dontRunWhenDisabled));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void conditionalRunWhenDisabledTest() {
|
||||
setDSEnabled(false);
|
||||
|
||||
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();
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true);
|
||||
Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true);
|
||||
|
||||
scheduler.schedule(runWhenDisabled, dontRunWhenDisabled);
|
||||
|
||||
assertTrue(scheduler.isScheduled(runWhenDisabled));
|
||||
assertFalse(scheduler.isScheduled(dontRunWhenDisabled));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void selectRunWhenDisabledTest() {
|
||||
setDSEnabled(false);
|
||||
|
||||
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 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);
|
||||
|
||||
assertTrue(scheduler.isScheduled(runWhenDisabled));
|
||||
assertFalse(scheduler.isScheduled(dontRunWhenDisabled));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void parallelConditionalRunWhenDisabledTest() {
|
||||
setDSEnabled(false);
|
||||
|
||||
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();
|
||||
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
Command runWhenDisabled = new ConditionalCommand(command1, command2, () -> true);
|
||||
Command dontRunWhenDisabled = new ConditionalCommand(command3, command4, () -> true);
|
||||
|
||||
Command parallel = parallel(runWhenDisabled, dontRunWhenDisabled);
|
||||
|
||||
scheduler.schedule(parallel);
|
||||
|
||||
assertFalse(scheduler.isScheduled(runWhenDisabled));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,28 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class RunCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void runCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
|
||||
RunCommand command = new RunCommand(counter::incrementAndGet);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
|
||||
assertEquals(3, counter.get());
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,43 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
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();
|
||||
|
||||
ScheduleCommand scheduleCommand = new ScheduleCommand(command1, command2);
|
||||
|
||||
scheduler.schedule(scheduleCommand);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2).initialize();
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void scheduleCommandDuringRunTest() {
|
||||
try (CommandScheduler scheduler = CommandScheduler.getInstance()) {
|
||||
Command toSchedule = Commands.none();
|
||||
ScheduleCommand scheduleCommand = new ScheduleCommand(toSchedule);
|
||||
Command group = Commands.sequence(Commands.none(), scheduleCommand);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.schedule(Commands.idle());
|
||||
scheduler.run();
|
||||
assertDoesNotThrow(scheduler::run);
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,464 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command.InterruptionBehavior;
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.EnumSource;
|
||||
|
||||
class SchedulingRecursionTest extends CommandTestBase {
|
||||
/**
|
||||
* <a href="https://github.com/wpilibsuite/allwpilib/issues/4259">wpilibsuite/allwpilib#4259</a>.
|
||||
*/
|
||||
@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 = requirement.run(() -> hasOtherRun.set(true));
|
||||
|
||||
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 = requirement.run(() -> hasOtherRun.set(true));
|
||||
|
||||
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 = requirement.run(() -> hasOtherRun.set(true));
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void cancelFromInterruptAction() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
Command selfCancels = Commands.idle();
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@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));
|
||||
}
|
||||
}
|
||||
|
||||
@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));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void scheduleFromEndCancel() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicInteger counter = new AtomicInteger();
|
||||
Subsystem requirement = new SubsystemBase() {};
|
||||
Command other = requirement.runOnce(() -> {});
|
||||
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() {};
|
||||
Command other = requirement.runOnce(() -> {});
|
||||
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() {};
|
||||
Command other = requirement.runOnce(() -> {});
|
||||
Command selfCancels = requirement.runOnce(() -> {});
|
||||
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 = requirement.runOnce(() -> {}).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 = requirement.runOnce(() -> {});
|
||||
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));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,118 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import java.util.HashMap;
|
||||
import java.util.Map;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class SelectCommandTest extends MultiCompositionTestBase<SelectCommand<Integer>> {
|
||||
@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<String> 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<String> selectCommand =
|
||||
new SelectCommand<>(
|
||||
Map.ofEntries(
|
||||
Map.entry("one", command1),
|
||||
Map.entry("two", command2),
|
||||
Map.entry("three", command3)),
|
||||
() -> "four");
|
||||
|
||||
assertDoesNotThrow(() -> scheduler.schedule(selectCommand));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void selectCommandRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
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<String> selectCommand =
|
||||
new SelectCommand<>(
|
||||
Map.ofEntries(
|
||||
Map.entry("one", command1),
|
||||
Map.entry("two", command2),
|
||||
Map.entry("three", command3)),
|
||||
() -> "one");
|
||||
|
||||
scheduler.schedule(selectCommand);
|
||||
scheduler.schedule(system3.runOnce(() -> {}));
|
||||
|
||||
assertFalse(scheduler.isScheduled(selectCommand));
|
||||
|
||||
verify(command1).end(true);
|
||||
verify(command2, never()).end(true);
|
||||
verify(command3, never()).end(true);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public SelectCommand<Integer> compose(Command... members) {
|
||||
var map = new HashMap<Integer, Command>();
|
||||
for (int i = 0; i < members.length; i++) {
|
||||
map.put(i, members[i]);
|
||||
}
|
||||
return new SelectCommand<>(map, () -> 0);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,129 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertDoesNotThrow;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class SequentialCommandGroupTest extends MultiCompositionTestBase<SequentialCommandGroup> {
|
||||
@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();
|
||||
|
||||
Command group = new SequentialCommandGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command2, never()).initialize();
|
||||
|
||||
command1Holder.setFinished(true);
|
||||
scheduler.run();
|
||||
|
||||
verify(command1).execute();
|
||||
verify(command1).end(false);
|
||||
verify(command2).initialize();
|
||||
verify(command2, never()).execute();
|
||||
verify(command2, never()).end(false);
|
||||
|
||||
command2Holder.setFinished(true);
|
||||
scheduler.run();
|
||||
|
||||
verify(command1).execute();
|
||||
verify(command1).end(false);
|
||||
verify(command2).execute();
|
||||
verify(command2).end(false);
|
||||
|
||||
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));
|
||||
}
|
||||
}
|
||||
|
||||
@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();
|
||||
|
||||
Command group = new SequentialCommandGroup(command1, command2);
|
||||
|
||||
assertDoesNotThrow(() -> scheduler.cancel(group));
|
||||
}
|
||||
}
|
||||
|
||||
@Test
|
||||
void sequentialGroupRequirementTest() {
|
||||
Subsystem system1 = new SubsystemBase() {};
|
||||
Subsystem system2 = new SubsystemBase() {};
|
||||
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();
|
||||
|
||||
Command group = new SequentialCommandGroup(command1, command2);
|
||||
|
||||
scheduler.schedule(group);
|
||||
scheduler.schedule(command3);
|
||||
|
||||
assertFalse(scheduler.isScheduled(group));
|
||||
assertTrue(scheduler.isScheduled(command3));
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public SequentialCommandGroup compose(Command... members) {
|
||||
return new SequentialCommandGroup(members);
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,61 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertThrows;
|
||||
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.params.ParameterizedTest;
|
||||
import org.junit.jupiter.params.provider.EnumSource;
|
||||
import org.junit.jupiter.params.provider.ValueSource;
|
||||
|
||||
public abstract class SingleCompositionTestBase<T extends Command> extends CommandTestBase {
|
||||
abstract T composeSingle(Command member);
|
||||
|
||||
@EnumSource(Command.InterruptionBehavior.class)
|
||||
@ParameterizedTest
|
||||
void interruptible(Command.InterruptionBehavior interruptionBehavior) {
|
||||
var command = composeSingle(Commands.idle().withInterruptBehavior(interruptionBehavior));
|
||||
assertEquals(interruptionBehavior, command.getInterruptionBehavior());
|
||||
}
|
||||
|
||||
@ValueSource(booleans = {true, false})
|
||||
@ParameterizedTest
|
||||
void runWhenDisabled(boolean runsWhenDisabled) {
|
||||
var command = composeSingle(Commands.idle().ignoringDisable(runsWhenDisabled));
|
||||
assertEquals(runsWhenDisabled, command.runsWhenDisabled());
|
||||
}
|
||||
|
||||
@Test
|
||||
@SuppressWarnings("NoDiscard")
|
||||
void commandInOtherCompositionTest() {
|
||||
var command = Commands.none();
|
||||
new WrapperCommand(command) {};
|
||||
assertThrows(IllegalArgumentException.class, () -> composeSingle(command));
|
||||
}
|
||||
|
||||
@Test
|
||||
void commandInMultipleCompositionsTest() {
|
||||
var command = Commands.none();
|
||||
composeSingle(command);
|
||||
assertThrows(IllegalArgumentException.class, () -> composeSingle(command));
|
||||
}
|
||||
|
||||
@Test
|
||||
void composeThenScheduleTest() {
|
||||
var command = Commands.none();
|
||||
composeSingle(command);
|
||||
assertThrows(
|
||||
IllegalArgumentException.class, () -> CommandScheduler.getInstance().schedule(command));
|
||||
}
|
||||
|
||||
@Test
|
||||
void scheduleThenComposeTest() {
|
||||
var command = Commands.idle();
|
||||
CommandScheduler.getInstance().schedule(command);
|
||||
assertThrows(IllegalArgumentException.class, () -> composeSingle(command));
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,34 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class StartEndCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void startEndCommandScheduleTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean cond1 = new AtomicBoolean();
|
||||
AtomicBoolean cond2 = new AtomicBoolean();
|
||||
|
||||
StartEndCommand command = new StartEndCommand(() -> cond1.set(true), () -> cond2.set(true));
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
|
||||
scheduler.cancel(command);
|
||||
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
assertTrue(cond1.get());
|
||||
assertTrue(cond2.get());
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,82 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.ArgumentMatchers.anyDouble;
|
||||
import static org.mockito.ArgumentMatchers.notNull;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
import static org.mockito.Mockito.when;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
import org.junit.jupiter.api.parallel.ResourceLock;
|
||||
|
||||
class WaitCommandTest extends CommandTestBase {
|
||||
@BeforeEach
|
||||
void setup() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void cleanup() {
|
||||
SimHooks.resumeTiming();
|
||||
}
|
||||
|
||||
@Test
|
||||
@ResourceLock("timing")
|
||||
void waitCommandTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
WaitCommand waitCommand = new WaitCommand(2);
|
||||
|
||||
scheduler.schedule(waitCommand);
|
||||
scheduler.run();
|
||||
SimHooks.stepTiming(1);
|
||||
scheduler.run();
|
||||
|
||||
assertTrue(scheduler.isScheduled(waitCommand));
|
||||
|
||||
SimHooks.stepTiming(2);
|
||||
|
||||
scheduler.run();
|
||||
|
||||
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();
|
||||
|
||||
Command timeout = command1.withTimeout(2);
|
||||
|
||||
scheduler.schedule(timeout);
|
||||
scheduler.run();
|
||||
|
||||
verify(command1).initialize();
|
||||
verify(command1).execute();
|
||||
assertFalse(scheduler.isScheduled(command1));
|
||||
assertTrue(scheduler.isScheduled(timeout));
|
||||
|
||||
SimHooks.stepTiming(3);
|
||||
scheduler.run();
|
||||
|
||||
verify(command1).end(true);
|
||||
verify(command1, never()).end(false);
|
||||
assertFalse(scheduler.isScheduled(timeout));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,29 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class WaitUntilCommandTest extends CommandTestBase {
|
||||
@Test
|
||||
void waitUntilTest() {
|
||||
try (CommandScheduler scheduler = new CommandScheduler()) {
|
||||
AtomicBoolean condition = new AtomicBoolean();
|
||||
|
||||
Command command = new WaitUntilCommand(condition::get);
|
||||
|
||||
scheduler.schedule(command);
|
||||
scheduler.run();
|
||||
assertTrue(scheduler.isScheduled(command));
|
||||
condition.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(scheduler.isScheduled(command));
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,48 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command.button;
|
||||
|
||||
import static org.mockito.Mockito.never;
|
||||
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;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class NetworkButtonTest extends CommandTestBase {
|
||||
NetworkTableInstance m_inst;
|
||||
|
||||
@BeforeEach
|
||||
void setup() {
|
||||
m_inst = NetworkTableInstance.create();
|
||||
m_inst.startLocal();
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void teardown() {
|
||||
m_inst.close();
|
||||
}
|
||||
|
||||
@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();
|
||||
|
||||
var button = new NetworkButton(m_inst, "TestTable", "Test");
|
||||
pub.set(false);
|
||||
button.onTrue(command);
|
||||
scheduler.run();
|
||||
verify(command, never()).initialize();
|
||||
pub.set(true);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
verify(command).initialize();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,57 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command.button;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
|
||||
import edu.wpi.first.wpilibj.simulation.DriverStationSim;
|
||||
import edu.wpi.first.wpilibj2.command.CommandTestBase;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class RobotModeTriggersTest extends CommandTestBase {
|
||||
@Test
|
||||
void autonomousTest() {
|
||||
DriverStationSim.resetData();
|
||||
DriverStationSim.setAutonomous(true);
|
||||
DriverStationSim.setTest(false);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
Trigger auto = RobotModeTriggers.autonomous();
|
||||
assertTrue(auto.getAsBoolean());
|
||||
}
|
||||
|
||||
@Test
|
||||
void teleopTest() {
|
||||
DriverStationSim.resetData();
|
||||
DriverStationSim.setAutonomous(false);
|
||||
DriverStationSim.setTest(false);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
Trigger teleop = RobotModeTriggers.teleop();
|
||||
assertTrue(teleop.getAsBoolean());
|
||||
}
|
||||
|
||||
@Test
|
||||
void testModeTest() {
|
||||
DriverStationSim.resetData();
|
||||
DriverStationSim.setAutonomous(false);
|
||||
DriverStationSim.setTest(true);
|
||||
DriverStationSim.setEnabled(true);
|
||||
DriverStationSim.notifyNewData();
|
||||
Trigger test = RobotModeTriggers.test();
|
||||
assertTrue(test.getAsBoolean());
|
||||
}
|
||||
|
||||
@Test
|
||||
void disabledTest() {
|
||||
DriverStationSim.resetData();
|
||||
DriverStationSim.setAutonomous(false);
|
||||
DriverStationSim.setTest(false);
|
||||
DriverStationSim.setEnabled(false);
|
||||
DriverStationSim.notifyNewData();
|
||||
Trigger disabled = RobotModeTriggers.disabled();
|
||||
assertTrue(disabled.getAsBoolean());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,278 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command.button;
|
||||
|
||||
import static org.junit.jupiter.api.Assertions.assertEquals;
|
||||
import static org.junit.jupiter.api.Assertions.assertFalse;
|
||||
import static org.junit.jupiter.api.Assertions.assertTrue;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
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;
|
||||
import edu.wpi.first.wpilibj2.command.StartEndCommand;
|
||||
import edu.wpi.first.wpilibj2.command.WaitUntilCommand;
|
||||
import java.util.concurrent.atomic.AtomicBoolean;
|
||||
import java.util.concurrent.atomic.AtomicInteger;
|
||||
import java.util.function.BooleanSupplier;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class TriggerTest extends CommandTestBase {
|
||||
@Test
|
||||
void onTrueTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicBoolean finished = new AtomicBoolean(false);
|
||||
Command command1 = new WaitUntilCommand(finished::get);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(false);
|
||||
button.onTrue(command1);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertTrue(command1.isScheduled());
|
||||
finished.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
}
|
||||
|
||||
@Test
|
||||
void onFalseTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicBoolean finished = new AtomicBoolean(false);
|
||||
Command command1 = new WaitUntilCommand(finished::get);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(true);
|
||||
button.onFalse(command1);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertTrue(command1.isScheduled());
|
||||
finished.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
}
|
||||
|
||||
@Test
|
||||
void onChangeTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicBoolean finished = new AtomicBoolean(false);
|
||||
Command command1 = new WaitUntilCommand(finished::get);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(true);
|
||||
button.onChange(command1);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertTrue(command1.isScheduled());
|
||||
finished.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
finished.set(false);
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertTrue(command1.isScheduled());
|
||||
finished.set(true);
|
||||
scheduler.run();
|
||||
assertFalse(command1.isScheduled());
|
||||
}
|
||||
|
||||
@Test
|
||||
void whileTrueRepeatedlyTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicInteger inits = new AtomicInteger(0);
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
// the repeatedly() here is the point!
|
||||
Command command1 =
|
||||
new FunctionalCommand(
|
||||
inits::incrementAndGet,
|
||||
() -> {},
|
||||
interrupted -> {},
|
||||
() -> counter.incrementAndGet() % 2 == 0)
|
||||
.repeatedly();
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(false);
|
||||
button.whileTrue(command1);
|
||||
scheduler.run();
|
||||
assertEquals(0, inits.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertEquals(1, inits.get());
|
||||
scheduler.run();
|
||||
assertEquals(1, inits.get());
|
||||
scheduler.run();
|
||||
assertEquals(2, inits.get());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertEquals(2, inits.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void whileTrueLambdaRunTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicInteger counter = new AtomicInteger(0);
|
||||
// the repeatedly() here is the point!
|
||||
Command command1 = new RunCommand(counter::incrementAndGet);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(false);
|
||||
button.whileTrue(command1);
|
||||
scheduler.run();
|
||||
assertEquals(0, counter.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertEquals(1, counter.get());
|
||||
scheduler.run();
|
||||
assertEquals(2, counter.get());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertEquals(2, counter.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void whileTrueOnceTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicInteger startCounter = new AtomicInteger(0);
|
||||
AtomicInteger endCounter = new AtomicInteger(0);
|
||||
Command command1 =
|
||||
new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(false);
|
||||
button.whileTrue(command1);
|
||||
scheduler.run();
|
||||
assertEquals(0, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(1, endCounter.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void toggleOnTrueTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicInteger startCounter = new AtomicInteger(0);
|
||||
AtomicInteger endCounter = new AtomicInteger(0);
|
||||
Command command1 =
|
||||
new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
button.setPressed(false);
|
||||
button.toggleOnTrue(command1);
|
||||
scheduler.run();
|
||||
assertEquals(0, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(false);
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(1, endCounter.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void cancelWhenActiveTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
AtomicInteger startCounter = new AtomicInteger(0);
|
||||
AtomicInteger endCounter = new AtomicInteger(0);
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
Command command1 =
|
||||
new StartEndCommand(startCounter::incrementAndGet, endCounter::incrementAndGet)
|
||||
.until(button);
|
||||
|
||||
button.setPressed(false);
|
||||
scheduler.schedule(command1);
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(0, endCounter.get());
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(1, endCounter.get());
|
||||
scheduler.run();
|
||||
assertEquals(1, startCounter.get());
|
||||
assertEquals(1, endCounter.get());
|
||||
}
|
||||
|
||||
@Test
|
||||
void triggerCompositionTest() {
|
||||
InternalButton button1 = new InternalButton();
|
||||
InternalButton button2 = new InternalButton();
|
||||
|
||||
button1.setPressed(true);
|
||||
button2.setPressed(false);
|
||||
|
||||
assertFalse(button1.and(button2).getAsBoolean());
|
||||
assertTrue(button1.or(button2).getAsBoolean());
|
||||
assertFalse(button1.negate().getAsBoolean());
|
||||
assertTrue(button1.and(button2.negate()).getAsBoolean());
|
||||
}
|
||||
|
||||
@Test
|
||||
void triggerCompositionSupplierTest() {
|
||||
InternalButton button1 = new InternalButton();
|
||||
BooleanSupplier booleanSupplier = () -> false;
|
||||
|
||||
button1.setPressed(true);
|
||||
|
||||
assertFalse(button1.and(booleanSupplier).getAsBoolean());
|
||||
assertTrue(button1.or(booleanSupplier).getAsBoolean());
|
||||
}
|
||||
|
||||
@Test
|
||||
void debounceTest() {
|
||||
CommandScheduler scheduler = CommandScheduler.getInstance();
|
||||
MockCommandHolder commandHolder = new MockCommandHolder(true);
|
||||
Command command = commandHolder.getMock();
|
||||
|
||||
InternalButton button = new InternalButton();
|
||||
Trigger debounced = button.debounce(0.1);
|
||||
|
||||
debounced.onTrue(command);
|
||||
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
verify(command, never()).initialize();
|
||||
|
||||
SimHooks.stepTiming(0.3);
|
||||
|
||||
button.setPressed(true);
|
||||
scheduler.run();
|
||||
verify(command).initialize();
|
||||
}
|
||||
|
||||
@Test
|
||||
void booleanSupplierTest() {
|
||||
InternalButton button = new InternalButton();
|
||||
|
||||
assertFalse(button.getAsBoolean());
|
||||
button.setPressed(true);
|
||||
assertTrue(button.getAsBoolean());
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,143 @@
|
||||
// Copyright (c) FIRST and other WPILib contributors.
|
||||
// Open Source Software; you can modify and/or share it under the terms of
|
||||
// the WPILib BSD license file in the root directory of this project.
|
||||
|
||||
package edu.wpi.first.wpilibj2.command.sysid;
|
||||
|
||||
import static edu.wpi.first.units.Units.Volts;
|
||||
import static org.mockito.ArgumentMatchers.any;
|
||||
import static org.mockito.Mockito.atLeastOnce;
|
||||
import static org.mockito.Mockito.clearInvocations;
|
||||
import static org.mockito.Mockito.inOrder;
|
||||
import static org.mockito.Mockito.mock;
|
||||
import static org.mockito.Mockito.never;
|
||||
import static org.mockito.Mockito.verify;
|
||||
|
||||
import edu.wpi.first.hal.HAL;
|
||||
import edu.wpi.first.units.measure.Voltage;
|
||||
import edu.wpi.first.wpilibj.simulation.SimHooks;
|
||||
import edu.wpi.first.wpilibj.sysid.SysIdRoutineLog;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Subsystem;
|
||||
import org.junit.jupiter.api.AfterEach;
|
||||
import org.junit.jupiter.api.BeforeEach;
|
||||
import org.junit.jupiter.api.Test;
|
||||
|
||||
class SysIdRoutineTest {
|
||||
interface Mechanism extends Subsystem {
|
||||
void recordState(SysIdRoutineLog.State state);
|
||||
|
||||
void drive(Voltage voltage);
|
||||
|
||||
void log(SysIdRoutineLog log);
|
||||
}
|
||||
|
||||
Mechanism m_mechanism;
|
||||
SysIdRoutine m_sysidRoutine;
|
||||
Command m_quasistaticForward;
|
||||
Command m_quasistaticReverse;
|
||||
Command m_dynamicForward;
|
||||
Command m_dynamicReverse;
|
||||
|
||||
void runCommand(Command command) {
|
||||
command.initialize();
|
||||
command.execute();
|
||||
command.execute();
|
||||
SimHooks.stepTiming(1);
|
||||
command.execute();
|
||||
command.end(true);
|
||||
}
|
||||
|
||||
@BeforeEach
|
||||
void setup() {
|
||||
HAL.initialize(500, 0);
|
||||
SimHooks.pauseTiming();
|
||||
m_mechanism = mock(Mechanism.class);
|
||||
m_sysidRoutine =
|
||||
new SysIdRoutine(
|
||||
new SysIdRoutine.Config(null, null, null, m_mechanism::recordState),
|
||||
new SysIdRoutine.Mechanism(m_mechanism::drive, m_mechanism::log, new Subsystem() {}));
|
||||
m_quasistaticForward = m_sysidRoutine.quasistatic(SysIdRoutine.Direction.kForward);
|
||||
m_quasistaticReverse = m_sysidRoutine.quasistatic(SysIdRoutine.Direction.kReverse);
|
||||
m_dynamicForward = m_sysidRoutine.dynamic(SysIdRoutine.Direction.kForward);
|
||||
m_dynamicReverse = m_sysidRoutine.dynamic(SysIdRoutine.Direction.kReverse);
|
||||
}
|
||||
|
||||
@AfterEach
|
||||
void cleanupAll() {
|
||||
SimHooks.resumeTiming();
|
||||
}
|
||||
|
||||
@Test
|
||||
void recordStateBookendsMotorLogging() {
|
||||
runCommand(m_quasistaticForward);
|
||||
|
||||
var orderCheck = inOrder(m_mechanism);
|
||||
|
||||
orderCheck.verify(m_mechanism).recordState(SysIdRoutineLog.State.kQuasistaticForward);
|
||||
orderCheck.verify(m_mechanism).drive(any());
|
||||
orderCheck.verify(m_mechanism).log(any());
|
||||
orderCheck.verify(m_mechanism).recordState(SysIdRoutineLog.State.kNone);
|
||||
orderCheck.verifyNoMoreInteractions();
|
||||
|
||||
clearInvocations(m_mechanism);
|
||||
orderCheck = inOrder(m_mechanism);
|
||||
runCommand(m_dynamicForward);
|
||||
|
||||
orderCheck.verify(m_mechanism).recordState(SysIdRoutineLog.State.kDynamicForward);
|
||||
orderCheck.verify(m_mechanism).drive(any());
|
||||
orderCheck.verify(m_mechanism).log(any());
|
||||
orderCheck.verify(m_mechanism).recordState(SysIdRoutineLog.State.kNone);
|
||||
orderCheck.verifyNoMoreInteractions();
|
||||
}
|
||||
|
||||
@Test
|
||||
void testsDeclareCorrectState() {
|
||||
runCommand(m_quasistaticForward);
|
||||
verify(m_mechanism, atLeastOnce()).recordState(SysIdRoutineLog.State.kQuasistaticForward);
|
||||
|
||||
runCommand(m_quasistaticReverse);
|
||||
verify(m_mechanism, atLeastOnce()).recordState(SysIdRoutineLog.State.kQuasistaticReverse);
|
||||
|
||||
runCommand(m_dynamicForward);
|
||||
verify(m_mechanism, atLeastOnce()).recordState(SysIdRoutineLog.State.kDynamicForward);
|
||||
|
||||
runCommand(m_dynamicReverse);
|
||||
verify(m_mechanism, atLeastOnce()).recordState(SysIdRoutineLog.State.kDynamicReverse);
|
||||
}
|
||||
|
||||
@Test
|
||||
void testsOutputCorrectVoltage() {
|
||||
runCommand(m_quasistaticForward);
|
||||
var orderCheck = inOrder(m_mechanism);
|
||||
|
||||
orderCheck.verify(m_mechanism, atLeastOnce()).drive(Volts.of(1));
|
||||
orderCheck.verify(m_mechanism).drive(Volts.of(0));
|
||||
orderCheck.verify(m_mechanism, never()).drive(any());
|
||||
|
||||
clearInvocations(m_mechanism);
|
||||
runCommand(m_quasistaticReverse);
|
||||
orderCheck = inOrder(m_mechanism);
|
||||
|
||||
orderCheck.verify(m_mechanism, atLeastOnce()).drive(Volts.of(-1));
|
||||
orderCheck.verify(m_mechanism).drive(Volts.of(0));
|
||||
orderCheck.verify(m_mechanism, never()).drive(any());
|
||||
|
||||
clearInvocations(m_mechanism);
|
||||
runCommand(m_dynamicForward);
|
||||
orderCheck = inOrder(m_mechanism);
|
||||
|
||||
orderCheck.verify(m_mechanism, atLeastOnce()).drive(Volts.of(7));
|
||||
orderCheck.verify(m_mechanism).drive(Volts.of(0));
|
||||
orderCheck.verify(m_mechanism, never()).drive(any());
|
||||
|
||||
clearInvocations(m_mechanism);
|
||||
runCommand(m_dynamicForward);
|
||||
orderCheck = inOrder(m_mechanism);
|
||||
|
||||
runCommand(m_dynamicReverse);
|
||||
orderCheck.verify(m_mechanism, atLeastOnce()).drive(Volts.of(-7));
|
||||
orderCheck.verify(m_mechanism).drive(Volts.of(0));
|
||||
orderCheck.verify(m_mechanism, never()).drive(any());
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user