[cmd3] Add rising and falling edge trigger factories (#8366)

`Trigger.getAsBoolean()` behavior has been changed from passing through
the underlying boolean supplier to returning the latest cached signal as
determined by the most recent call to `poll()`. This allows rising and
falling edge triggers to have a consistent return value over an entire
polling cycle, rather than only being high for the _first_ check in a
cycle.

Closes #8309
This commit is contained in:
Sam Carlberg
2026-05-07 19:32:34 -04:00
committed by GitHub
parent 5964443038
commit 62e0bc515c
6 changed files with 546 additions and 28 deletions

View File

@@ -69,6 +69,8 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
* <ol>
* <li>Cancel any commands bound to scopes that have gone inactive, such as having been scheduled
* in an opmode that's no longer selected on the driverstation.
* <li>Cancel any triggers that were created in scopes that have gone inactive, such as being
* constructed in an opmode that's no longer selected on the driverstation.
* <li>Call {@link #sideload(Consumer) periodic sideload functions}.
* <li>Poll all registered triggers to queue and cancel commands.
* <li>Queue default commands for any mechanisms without a running command. The queued commands
@@ -110,6 +112,8 @@ public final class Scheduler implements ProtobufSerializable {
*/
private final Collection<Binding> m_activeBindings = new ArrayList<>();
private final Collection<Trigger> m_boundTriggers = new ArrayList<>();
/** The set of commands scheduled since the start of the previous run. */
private final SequencedSet<CommandState> m_queuedToRun = new LinkedHashSet<>();
@@ -545,6 +549,8 @@ public final class Scheduler implements ProtobufSerializable {
* <ol>
* <li>Cancel any commands bound to scopes that have gone inactive, such as having been
* scheduled in an opmode that's no longer selected on the driverstation
* <li>Cancel any triggers that were created in scopes that have gone inactive, such as being
* constructed in an opmode that's no longer selected on the driverstation
* <li>Run sideloaded functions from {@link #sideload(Consumer)} and {@link
* #addPeriodic(Runnable)}
* <li>Update trigger bindings to queue and cancel bound commands
@@ -563,6 +569,11 @@ public final class Scheduler implements ProtobufSerializable {
// Cancel any commands with stale binding scopes
cancelStaleBindings();
// Unbind any triggers with stale creation scopes.
// This allows triggers that can never be used again to be garbage collected to reduce
// memory usage and avoid potential OOMs from poorly written user code.
unbindStaleTriggers();
// Sideloads may change some state that affects triggers. Run them first.
runPeriodicSideloads();
@@ -594,6 +605,25 @@ public final class Scheduler implements ProtobufSerializable {
}
}
private void unbindStaleTriggers() {
for (var iterator = m_boundTriggers.iterator(); iterator.hasNext(); ) {
var trigger = iterator.next();
if (!trigger.isScopeActive()) {
trigger.unbind();
iterator.remove();
}
}
}
/**
* Adds a bound trigger to this scheduler. The trigger will be unbound from the event loop when
* its creation scope becomes inactive and may be eligible for garbage collection.
*/
// package-private for Trigger to call when constructed
void addBoundTrigger(Trigger trigger) {
m_boundTriggers.add(trigger);
}
private void promoteScheduledCommands() {
// Clear any commands that conflict with the scheduled set
for (var queuedState : m_queuedToRun) {

View File

@@ -45,16 +45,23 @@ public class Trigger implements BooleanSupplier {
private final BooleanSupplier m_condition;
private final EventLoop m_loop;
private final Scheduler m_scheduler;
/** The value of the signal before the most recent call to {@link #poll()}. May be null. */
private Signal m_previousSignal;
/** The value of the signal from the most recent call to {@link #poll()}. May be null. */
private Signal m_cachedSignal;
private final Map<BindingType, List<Binding>> m_bindings = new EnumMap<>(BindingType.class);
private final Runnable m_eventLoopCallback = this::poll;
private boolean m_isBoundToEventLoop; // used for lazily binding to the event loop
private boolean m_bound = true;
private final BindingScope m_creationScope;
/**
* Represents the state of a signal: high or low. Used instead of a boolean for nullity on the
* first run, when the previous signal value is undefined and unknown.
*/
private enum Signal {
enum Signal {
/** The signal is high. */
HIGH,
/** The signal is low. */
@@ -69,9 +76,10 @@ public class Trigger implements BooleanSupplier {
* @param condition the condition represented by this trigger
*/
public Trigger(Scheduler scheduler, BooleanSupplier condition) {
m_scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger");
m_loop = scheduler.getDefaultEventLoop();
m_condition = requireNonNullParam(condition, "condition", "Trigger");
this(
requireNonNullParam(scheduler, "scheduler", "Trigger"),
scheduler.getDefaultEventLoop(),
requireNonNullParam(condition, "condition", "Trigger"));
}
/**
@@ -93,10 +101,15 @@ public class Trigger implements BooleanSupplier {
* @param loop The event loop to poll the trigger.
* @param condition the condition represented by this trigger
*/
@SuppressWarnings("this-escape")
public Trigger(Scheduler scheduler, EventLoop loop, BooleanSupplier condition) {
m_scheduler = requireNonNullParam(scheduler, "scheduler", "Trigger");
m_loop = requireNonNullParam(loop, "loop", "Trigger");
m_condition = requireNonNullParam(condition, "condition", "Trigger");
m_creationScope = BindingScope.createNarrowestScope(m_scheduler);
m_scheduler.addBoundTrigger(this);
m_loop.bind(m_eventLoopCallback);
}
/**
@@ -177,9 +190,20 @@ public class Trigger implements BooleanSupplier {
return this;
}
/**
* Gets the boolean state of the trigger. Because triggers are checked when their event loop is
* polled, which by default occurs when {@link Scheduler#run()} is called in user code, but may
* differ for custom event loops, the state is only valid immediately after the event loop is
* polled. If the underlying signal changes without a subsequent event loop poll, the return value
* from {@code getAsBoolean()} may not agree with the result of checking the signal directly.
*
* <p>This method will always return {@code false} before being polled by an event loop.
*
* @return The state of the trigger.
*/
@Override
public boolean getAsBoolean() {
return m_condition.getAsBoolean();
return m_cachedSignal == Signal.HIGH;
}
/**
@@ -189,8 +213,7 @@ public class Trigger implements BooleanSupplier {
* @return A trigger which is active when both component triggers are active.
*/
public Trigger and(BooleanSupplier trigger) {
return new Trigger(
m_scheduler, m_loop, () -> m_condition.getAsBoolean() && trigger.getAsBoolean());
return new Trigger(m_scheduler, m_loop, () -> getAsBoolean() && trigger.getAsBoolean());
}
/**
@@ -200,8 +223,7 @@ public class Trigger implements BooleanSupplier {
* @return A trigger which is active when either component trigger is active.
*/
public Trigger or(BooleanSupplier trigger) {
return new Trigger(
m_scheduler, m_loop, () -> m_condition.getAsBoolean() || trigger.getAsBoolean());
return new Trigger(m_scheduler, m_loop, () -> getAsBoolean() || trigger.getAsBoolean());
}
/**
@@ -211,7 +233,7 @@ public class Trigger implements BooleanSupplier {
* @return the negated trigger
*/
public Trigger negate() {
return new Trigger(m_scheduler, m_loop, () -> !m_condition.getAsBoolean());
return new Trigger(m_scheduler, m_loop, () -> !getAsBoolean());
}
/**
@@ -235,7 +257,37 @@ public class Trigger implements BooleanSupplier {
*/
public Trigger debounce(Time duration, Debouncer.DebounceType type) {
var debouncer = new Debouncer(duration.in(Seconds), type);
return new Trigger(m_scheduler, m_loop, () -> debouncer.calculate(m_condition.getAsBoolean()));
return new Trigger(m_scheduler, m_loop, () -> debouncer.calculate(getAsBoolean()));
}
/**
* Creates a trigger that activates on a rising edge of this trigger's signal. The rising edge
* trigger is active in the same cycle that this trigger's condition is {@code true} while its
* condition in the previous cycle was {@code false}. The resulting trigger will only be active
* for that single cycle before going inactive again; therefore, {@link #onTrue(Command)} should
* be used instead of {@link #whileTrue(Command)}, as commands bound using the latter method will
* be immediately canceled after a single scheduler cycle.
*
* @return A rising edge trigger.
*/
public Trigger risingEdge() {
return new Trigger(
m_scheduler, m_loop, () -> m_cachedSignal == Signal.HIGH && m_previousSignal == Signal.LOW);
}
/**
* Creates a trigger that activates on a falling edge of this trigger's signal. The falling edge
* trigger is active in the same cycle that this trigger's condition is {@code false} while its
* condition in the previous cycle was {@code true}. The resulting trigger will only be active for
* that single cycle before going inactive again; therefore, {@link #onTrue(Command)} should be
* used instead of {@link #whileTrue(Command)}, as commands bound using the latter method will be
* immediately canceled after a single scheduler cycle.
*
* @return A falling edge trigger.
*/
public Trigger fallingEdge() {
return new Trigger(
m_scheduler, m_loop, () -> m_cachedSignal == Signal.LOW && m_previousSignal == Signal.HIGH);
}
private void poll() {
@@ -244,14 +296,15 @@ public class Trigger implements BooleanSupplier {
// and those scopes may become inactive.
clearStaleBindings();
var signal = readSignal();
m_previousSignal = m_cachedSignal;
m_cachedSignal = readSignal();
if (signal == m_previousSignal) {
if (m_cachedSignal == m_previousSignal) {
// No change in the signal. Nothing to do
return;
}
if (signal == Signal.HIGH) {
if (m_cachedSignal == Signal.HIGH) {
// Signal is now high when it wasn't before - a rising edge
scheduleBindings(BindingType.SCHEDULE_ON_RISING_EDGE);
scheduleBindings(BindingType.RUN_WHILE_HIGH);
@@ -259,15 +312,13 @@ public class Trigger implements BooleanSupplier {
toggleBindings(BindingType.TOGGLE_ON_RISING_EDGE);
}
if (signal == Signal.LOW) {
if (m_cachedSignal == Signal.LOW) {
// Signal is now low when it wasn't before - a falling edge
scheduleBindings(BindingType.SCHEDULE_ON_FALLING_EDGE);
scheduleBindings(BindingType.RUN_WHILE_LOW);
cancelBindings(BindingType.RUN_WHILE_HIGH);
toggleBindings(BindingType.TOGGLE_ON_FALLING_EDGE);
}
m_previousSignal = signal;
}
private Signal readSignal() {
@@ -289,7 +340,7 @@ public class Trigger implements BooleanSupplier {
continue;
}
// The scope is no long active. Remove the binding and immediately cancel its command.
// The scope is no longer active. Remove the binding and immediately cancel its command.
iterator.remove();
m_scheduler.cancel(binding.command());
}
@@ -336,6 +387,59 @@ public class Trigger implements BooleanSupplier {
});
}
/**
* Package-private for testing. Reads the signal of the trigger as it was <i>after</i> the most
* recent call to {@link #poll()}. May be null.
*
* @return The most recent signal.
*/
Signal getCachedSignal() {
return m_cachedSignal;
}
/**
* Package-private for testing. Reads the signal of the trigger as it was <i>before</i> the most
* recent call to {@link #poll()}. May be null.
*
* @return The previous signal.
*/
Signal getPreviousSignal() {
return m_previousSignal;
}
/** Checks if the creation scope is currently active. */
// package-private for the scheduler to access
boolean isScopeActive() {
return m_creationScope.active();
}
/**
* Unbinds this trigger from the event loop and clears all command bindings; any bound commands
* that are currently running will be canceled. The trigger may be garbage collected if no other
* references exist in user code. Binding a command to a trigger via {@link #onTrue(Command)} or
* similar will re-bind the trigger to the event loop.
*
* <p>Note: because triggers are only updated when they're bound to an event loop, calling {@code
* #unbind()} will result in {@link #getAsBoolean()} continuing to return the same value until the
* trigger is re-bound.
*
* <p>This method is automatically called by the associated {@link Scheduler} when the trigger's
* creation scope becomes inactive: a trigger created inside a command will be unbound when that
* command completes, and may be eligible for garbage collection; and a trigger created while an
* opmode is running will be unbound when that opmode ends (and also may be eligible for garbage
* collection).
*/
public void unbind() {
// Ensure all bound commands are canceled
m_bindings.forEach(
(_, bindings) -> {
bindings.forEach(binding -> m_scheduler.cancel(binding.command()));
});
m_bindings.clear();
m_loop.unbind(m_eventLoopCallback); // note: ConcurrentModificationException if called in poll()
m_bound = false;
}
// package-private for testing
void addBinding(BindingScope scope, BindingType bindingType, Command command) {
// Note: we use a throwable here instead of Thread.currentThread().getStackTrace() for easier
@@ -344,9 +448,11 @@ public class Trigger implements BooleanSupplier {
.computeIfAbsent(bindingType, _k -> new ArrayList<>())
.add(new Binding(scope, bindingType, command, new Throwable().getStackTrace()));
if (!m_isBoundToEventLoop) {
if (!m_bound) {
// Ensure we're bound to the event loop.
// Otherwise, the command binding will never fire.
m_loop.bind(m_eventLoopCallback);
m_isBoundToEventLoop = true;
m_bound = true;
}
}

View File

@@ -4,12 +4,14 @@
package org.wpilib.command3;
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 java.util.List;
import java.util.concurrent.atomic.AtomicBoolean;
import java.util.function.BooleanSupplier;
import org.junit.jupiter.api.Test;
class TriggerTest extends CommandTestBase {
@@ -276,4 +278,369 @@ class TriggerTest extends CommandTestBase {
assertEquals(List.of(), m_scheduler.getRunningCommands().stream().map(Command::name).toList());
assertFalse(triggeredCommandRan.get(), "Command was unexpectedly triggered");
}
@Test
void risingEdge() {
var signal = new AtomicBoolean(false);
var baseTrigger = new Trigger(m_scheduler, signal::get);
var risingEdgeTrigger = baseTrigger.risingEdge();
assertAll(
"Signals start null",
() -> assertEquals(null, baseTrigger.getCachedSignal()),
() -> assertEquals(null, baseTrigger.getPreviousSignal()),
() -> assertEquals(null, risingEdgeTrigger.getCachedSignal()),
() -> assertEquals(null, risingEdgeTrigger.getPreviousSignal()));
m_scheduler.run();
assertAll(
"First run (base signal stays low)",
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getCachedSignal()),
() -> assertEquals(null, baseTrigger.getPreviousSignal()),
() -> assertEquals(Trigger.Signal.LOW, risingEdgeTrigger.getCachedSignal()),
() -> assertEquals(null, risingEdgeTrigger.getPreviousSignal()));
signal.set(true);
m_scheduler.run();
assertAll(
"Second run (base signal goes high)",
() -> assertEquals(Trigger.Signal.HIGH, baseTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getPreviousSignal()),
() ->
assertEquals(
Trigger.Signal.HIGH,
risingEdgeTrigger.getCachedSignal(),
"Rising edge trigger did not go high"),
() -> assertEquals(Trigger.Signal.LOW, risingEdgeTrigger.getPreviousSignal()));
m_scheduler.run();
assertAll(
"Third run (base signal stays high)",
() -> assertEquals(Trigger.Signal.HIGH, baseTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.HIGH, baseTrigger.getPreviousSignal()),
() ->
assertEquals(
Trigger.Signal.LOW,
risingEdgeTrigger.getCachedSignal(),
"Rising edge trigger did not go low"),
() ->
assertEquals(
Trigger.Signal.HIGH,
risingEdgeTrigger.getPreviousSignal(),
"Rising edge trigger was not previously high"));
}
@Test
void fallingEdge() {
var signal = new AtomicBoolean(false);
var baseTrigger = new Trigger(m_scheduler, signal::get);
var fallingEdgeTrigger = baseTrigger.fallingEdge();
assertAll(
"Signals start null",
() -> assertEquals(null, baseTrigger.getCachedSignal()),
() -> assertEquals(null, baseTrigger.getPreviousSignal()),
() -> assertEquals(null, fallingEdgeTrigger.getCachedSignal()),
() -> assertEquals(null, fallingEdgeTrigger.getPreviousSignal()));
m_scheduler.run();
assertAll(
"First run (base signal stays low)",
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getCachedSignal()),
() -> assertEquals(null, baseTrigger.getPreviousSignal()),
() -> assertEquals(Trigger.Signal.LOW, fallingEdgeTrigger.getCachedSignal()),
() -> assertEquals(null, fallingEdgeTrigger.getPreviousSignal()));
signal.set(true);
m_scheduler.run();
assertAll(
"Second run (base signal goes high)",
() -> assertEquals(Trigger.Signal.HIGH, baseTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getPreviousSignal()),
() -> assertEquals(Trigger.Signal.LOW, fallingEdgeTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.LOW, fallingEdgeTrigger.getPreviousSignal()));
signal.set(false);
m_scheduler.run();
assertAll(
"Third run (base signal goes low)",
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.HIGH, baseTrigger.getPreviousSignal()),
() ->
assertEquals(
Trigger.Signal.HIGH,
fallingEdgeTrigger.getCachedSignal(),
"Falling edge trigger did not go high"),
() ->
assertEquals(
Trigger.Signal.LOW,
fallingEdgeTrigger.getPreviousSignal(),
"Falling edge trigger was not previously low"));
m_scheduler.run();
assertAll(
"Fourth run (base signal stays low)",
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getCachedSignal()),
() -> assertEquals(Trigger.Signal.LOW, baseTrigger.getPreviousSignal()),
() ->
assertEquals(
Trigger.Signal.LOW,
fallingEdgeTrigger.getCachedSignal(),
"Falling edge trigger did not go low"),
() ->
assertEquals(
Trigger.Signal.HIGH,
fallingEdgeTrigger.getPreviousSignal(),
"Falling edge trigger was not previously high"));
}
@Test
void ensureBoundBindsDependencies() {
var a = new AtomicBoolean(false);
var b = new AtomicBoolean(false);
var baseA = new Trigger(m_scheduler, a::get);
var baseB = new Trigger(m_scheduler, b::get);
// Compose a trigger that depends on an intermediate, unbound risingEdge() trigger
var composed = baseA.and(baseB.risingEdge());
var command = Command.noRequirements(Coroutine::park).named("Cmd");
// Bind only the composed trigger; ensureBound() must bind dependencies first so polling order
// updates base triggers before evaluating the composed condition.
composed.onTrue(command);
// First run initializes all signals to LOW
m_scheduler.run();
assertFalse(
m_scheduler.isRunning(command), "Command should not run on first initialization run");
// Cause both conditions to be true in the same cycle: A is true, and B has a rising edge
a.set(true);
b.set(true);
m_scheduler.run();
assertTrue(
m_scheduler.isRunning(command),
"Top-level composed trigger did not fire when dependency rising edge occurred");
}
@Test
void ensureBoundDeeplyNestedDependencies() {
var a = new AtomicBoolean(false);
var b = new AtomicBoolean(false);
var c = new AtomicBoolean(false);
var baseA = new Trigger(m_scheduler, a::get);
var baseB = new Trigger(m_scheduler, b::get);
var baseC = new Trigger(m_scheduler, c::get);
// Two levels of nesting: baseA AND (baseB.risingEdge() AND baseC.risingEdge())
final var nested = baseA.and(baseB.risingEdge().and(baseC.risingEdge()));
// Initialize signals
m_scheduler.run();
// Trigger both rising edges and set A high in the same cycle
a.set(true);
b.set(true);
c.set(true);
m_scheduler.run();
assertTrue(
nested.getAsBoolean(),
"Deeply nested composed trigger did not fire; dependencies may not have been bound first");
}
@Test
void composedAnd() {
var signalA = new AtomicBoolean(false);
var signalB = new AtomicBoolean(false);
var triggerA = new Trigger(m_scheduler, flickering(signalA));
var triggerB = new Trigger(m_scheduler, flickering(signalB));
var andTrigger = triggerA.and(triggerB);
m_scheduler.run();
assertFalse(andTrigger.getAsBoolean());
signalA.set(true);
m_scheduler.run();
assertFalse(andTrigger.getAsBoolean());
signalA.set(true);
signalB.set(true);
m_scheduler.run();
assertTrue(andTrigger.getAsBoolean());
signalA.set(false);
m_scheduler.run();
assertFalse(andTrigger.getAsBoolean());
}
@Test
void composedAndWithSupplier() {
var signalA = new AtomicBoolean(false);
var signalB = new AtomicBoolean(false);
var triggerA = new Trigger(m_scheduler, flickering(signalA));
var andTrigger = triggerA.and(flickering(signalB));
m_scheduler.run();
assertFalse(andTrigger.getAsBoolean());
signalA.set(true);
signalB.set(true);
m_scheduler.run();
assertTrue(andTrigger.getAsBoolean());
signalB.set(false);
m_scheduler.run();
assertFalse(andTrigger.getAsBoolean());
}
@Test
void composedOr() {
var signalA = new AtomicBoolean(false);
var signalB = new AtomicBoolean(false);
var triggerA = new Trigger(m_scheduler, flickering(signalA));
var triggerB = new Trigger(m_scheduler, flickering(signalB));
var orTrigger = triggerA.or(triggerB);
m_scheduler.run();
assertFalse(orTrigger.getAsBoolean());
signalA.set(true);
m_scheduler.run();
assertTrue(orTrigger.getAsBoolean());
signalA.set(false);
m_scheduler.run();
assertFalse(orTrigger.getAsBoolean());
signalB.set(true);
m_scheduler.run();
assertTrue(orTrigger.getAsBoolean());
}
@Test
void composedOrWithSupplier() {
var signalA = new AtomicBoolean(false);
var signalB = new AtomicBoolean(false);
var triggerA = new Trigger(m_scheduler, flickering(signalA));
var orTrigger = triggerA.or(flickering(signalB));
m_scheduler.run();
assertFalse(orTrigger.getAsBoolean());
signalB.set(true);
m_scheduler.run();
assertTrue(orTrigger.getAsBoolean());
}
@Test
void composedNegate() {
var signal = new AtomicBoolean(false);
var trigger = new Trigger(m_scheduler, flickering(signal));
var negated = trigger.negate();
m_scheduler.run();
assertTrue(negated.getAsBoolean());
signal.set(true);
m_scheduler.run();
assertFalse(negated.getAsBoolean());
}
@Test
void selfComposition() {
var signal = new AtomicBoolean(false);
var trigger = new Trigger(m_scheduler, flickering(signal));
var selfAnd = trigger.and(trigger);
var selfOr = trigger.or(trigger);
m_scheduler.run();
assertFalse(selfAnd.getAsBoolean());
assertFalse(selfOr.getAsBoolean());
signal.set(true);
m_scheduler.run();
assertTrue(selfAnd.getAsBoolean());
assertTrue(selfOr.getAsBoolean());
}
@Test
void complexComposition() {
var signalA = new AtomicBoolean(false);
var signalB = new AtomicBoolean(false);
var signalC = new AtomicBoolean(false);
var triggerA = new Trigger(m_scheduler, flickering(signalA));
var triggerB = new Trigger(m_scheduler, flickering(signalB));
var triggerC = new Trigger(m_scheduler, flickering(signalC));
// (A and B) or (not C)
var composed = triggerA.and(triggerB).or(triggerC.negate());
// Initially A=F, B=F, C=F. (F and F) or (not F) -> F or T -> T
m_scheduler.run();
assertTrue(composed.getAsBoolean());
// A=T, B=T, C=T. (T and T) or (not T) -> T or F -> T
signalA.set(true);
signalB.set(true);
signalC.set(true);
m_scheduler.run();
assertTrue(composed.getAsBoolean());
// A=F, B=T, C=T. (F and T) or (not T) -> F or F -> F
signalA.set(false);
signalC.set(true); // Ensure C is high for next run if it flickered
m_scheduler.run();
assertFalse(composed.getAsBoolean());
}
@Test
void triggerUnbindsWhenCommandScopeInactive() {
var triggerSignal = new AtomicBoolean(false);
var commandRan = new AtomicBoolean(false);
var innerCommand = Command.noRequirements(_ -> commandRan.set(true)).named("Inner");
var outerCommand =
Command.noRequirements(
co -> {
var trigger = new Trigger(m_scheduler, triggerSignal::get);
trigger.onTrue(innerCommand);
co.park();
})
.named("Outer");
m_scheduler.schedule(outerCommand);
m_scheduler.run();
assertTrue(m_scheduler.isRunning(outerCommand));
triggerSignal.set(true);
m_scheduler.run();
assertTrue(commandRan.get());
// Cancel outer command, trigger should now be out of scope
m_scheduler.cancel(outerCommand);
m_scheduler.run();
assertFalse(m_scheduler.isRunning(outerCommand));
// The trigger should have unbound itself during the last run() call.
}
private BooleanSupplier flickering(AtomicBoolean signal) {
return () -> {
boolean val = signal.get();
if (val) {
signal.set(false);
}
return val;
};
}
}

View File

@@ -187,7 +187,8 @@ and manually scheduled commands.
A command scheduled in a certain scope, a trigger binding created in a certain scope, or a default command set in
a certain scope will only exist _within that scope_. Changing the default command for a mechanism within a custom opmode
will only be applied while that opmode is active; when the opmode exits, the default command specified in the robot
constructor (or mechanism constructor) will be reapplied.
constructor (or mechanism constructor) will be reapplied. Triggers created in a scope will be unbound from the event
loop and be allowed to be garbage collected if no existing references exist.
```java
class Robot extends OpModeRobot {
@@ -420,12 +421,13 @@ and `Command` (a scope for a specific running command).
### Scheduler `run()` Cycle
1. Cancel commands bound to inactive scopes
2. Run periodic sideload functions
3. Poll the event loop for triggers (which may queue or cancel commands)
4. Schedule default commands for the next iteration to pick up and start running
5. Promote scheduled commands to running
2. Cancel triggers bound to inactive scopes
3. Run periodic sideload functions
4. Poll the event loop for triggers (which may queue or cancel commands)
5. Schedule default commands for the next iteration to pick up and start running
6. Promote scheduled commands to running
1. Cancels any running commands that conflict with scheduled ones
6. Iterate over running commands
7. Iterate over running commands
1. Mount
2. Run until yield point is reached or an error is raised
3. Unmount

View File

@@ -176,7 +176,7 @@ module PUBLIC "-//Puppy Crawl//DTD Check Configuration 1.3//EN"
</module>
<module name="LambdaParameterName">
<property name="format"
value="^(_?[a-zA-Z]|_?[a-z][a-zA-Z0-9]+)$" />
value="^(_|_?[a-zA-Z]|_?[a-z][a-zA-Z0-9]+)$" />
<message key="name.invalidPattern"
value="Lambda parameter name ''{0}'' must match pattern ''{1}''." />
</module>

View File

@@ -30,6 +30,19 @@ public final class EventLoop {
m_bindings.add(action);
}
/**
* Unbind an action from running when the loop is polled. Has no effect if the given action is not
* already bound.
*
* @param action the action to unbind.
*/
public void unbind(Runnable action) {
if (m_running) {
throw new ConcurrentModificationException("Cannot unbind EventLoop while it is running");
}
m_bindings.remove(action);
}
/** Poll all bindings. */
@SuppressWarnings("PMD.UnusedAssignment")
public void poll() {