Skip to content

Commit

Permalink
Revisions to Status system
Browse files Browse the repository at this point in the history
  • Loading branch information
ryancahoon-zoox authored and rcahoon committed Nov 11, 2024
1 parent 473e228 commit 9fe1b44
Show file tree
Hide file tree
Showing 18 changed files with 236 additions and 95 deletions.
12 changes: 11 additions & 1 deletion .vscode/settings.json
Original file line number Diff line number Diff line change
Expand Up @@ -33,5 +33,15 @@
"diffEditor.ignoreTrimWhitespace": false,
"java.format.settings.url": "https://raw.githubusercontent.com/google/styleguide/gh-pages/eclipse-java-google-style.xml",
"java.checkstyle.configuration": "${workspaceFolder}/.github/linters/checkstyle.xml",
"java.checkstyle.version": "9.3"
"java.checkstyle.version": "9.3",
"java.completion.favoriteStaticMembers": [
"com.team766.framework.Conditions.*",
"com.team766.framework.StatusBus.*",
"org.junit.Assert.*",
"org.junit.Assume.*",
"org.junit.jupiter.api.Assertions.*",
"org.junit.jupiter.api.Assumptions.*",
"org.junit.jupiter.api.DynamicContainer.*",
"org.junit.jupiter.api.DynamicTest.*",
],
}
87 changes: 62 additions & 25 deletions src/main/java/com/team766/framework3/Conditions.java
Original file line number Diff line number Diff line change
@@ -1,47 +1,84 @@
package com.team766.framework3;

import com.team766.library.Holder;
import java.util.Optional;
import java.util.function.BooleanSupplier;
import java.util.function.Predicate;
import java.util.function.Supplier;

/**
* Pre-canned Conditions used frqeuently in robot programming.
*/
public class Conditions {
public static <T> T waitFor(Context context, Supplier<Optional<T>> supplier) {
final Holder<T> result = new Holder<>();
context.waitFor(
() -> {
final var t = supplier.get();
t.ifPresent(result::set);
return t.isPresent();
});
return result.value;
}

public static <T> Optional<T> waitForValueOrTimeout(
Context context, Supplier<Optional<T>> supplier, double timeoutSeconds) {
final Holder<Optional<T>> result = new Holder<>(Optional.empty());
context.waitForConditionOrTimeout(
() -> {
result.value = supplier.get();
return result.value.isPresent();
},
timeoutSeconds);
return result.value;
}

public static <S extends Status> boolean checkForStatus(Class<S> statusClass) {
return StatusBus.getStatusEntry(statusClass).isPresent();
}

/**
* Predicate that checks whether or not the latest {@link Status} passes the
* check provided by {@link Checker}.
* check provided by {@code predicate}.
*/
public static class StatusCheck<S extends Status> implements BooleanSupplier {
public static <S extends Status> boolean checkForStatusWith(
Class<S> statusClass, Predicate<S> predicate) {
return StatusBus.getStatusValue(statusClass, predicate::test).orElse(false);
}

/** Functional interface for checking whether or not a {@link Status} passes desired criteria. */
@FunctionalInterface
public interface Checker<S> {
boolean check(S status);
}
public static <S extends Status> boolean checkForStatusEntryWith(
Class<S> statusClass, Predicate<StatusBus.Entry<S>> predicate) {
return StatusBus.getStatusEntry(statusClass).map(predicate::test).orElse(false);
}

private final Class<S> clazz;
private final Checker<S> checker;
public static <T extends Status> T waitForStatus(Context context, Class<T> statusClass) {
return waitFor(context, () -> StatusBus.getStatus(statusClass));
}

public StatusCheck(Class<S> clazz, Checker<S> checker) {
this.clazz = clazz;
this.checker = checker;
}
public static <T extends Status> Optional<T> waitForStatusOrTimeout(
Context context, Class<T> statusClass, double timeoutSeconds) {
return waitForValueOrTimeout(
context, () -> StatusBus.getStatus(statusClass), timeoutSeconds);
}

public boolean getAsBoolean() {
S status = StatusBus.getInstance().getStatus(clazz);
return checker.check(status);
}
public static <T extends Status> T waitForStatus(
Context context, Class<T> statusClass, Predicate<T> predicate) {
return waitFor(context, () -> StatusBus.getStatus(statusClass).filter(predicate));
}

/**
* Predicate that checks if the provided {@link Request} has been fulfilled by checking
* the latest {@link Status}.
*/
public static class AwaitRequest<S extends Status> extends StatusCheck<S> {
public static <T extends Status> Optional<T> waitForStatusOrTimeout(
Context context, Class<T> statusClass, Predicate<T> predicate, double timeoutSeconds) {
return waitForValueOrTimeout(
context, () -> StatusBus.getStatus(statusClass).filter(predicate), timeoutSeconds);
}

public AwaitRequest(Class<S> clazz, Request<S> request) {
super(clazz, request::isDone);
}
public static void waitForRequest(Context context, Request request) {
context.waitFor(request::isDone);
}

public static void waitForRequestOrTimeout(
Context context, Request request, double timeoutSeconds) {
context.waitForConditionOrTimeout(request::isDone, timeoutSeconds);
}

public static final class Toggle implements BooleanSupplier {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -5,12 +5,12 @@
public final class FunctionalInstantProcedure extends InstantProcedure {
private final Runnable runnable;

public FunctionalInstantProcedure(Set<Mechanism<?>> reservations, Runnable runnable) {
public FunctionalInstantProcedure(Set<Mechanism<?, ?>> reservations, Runnable runnable) {
this(runnable.toString(), reservations, runnable);
}

public FunctionalInstantProcedure(
String name, Set<Mechanism<?>> reservations, Runnable runnable) {
String name, Set<Mechanism<?, ?>> reservations, Runnable runnable) {
super(name, reservations);
this.runnable = runnable;
}
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/com/team766/framework3/FunctionalProcedure.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,12 +6,12 @@
public final class FunctionalProcedure extends Procedure {
private final Consumer<Context> runnable;

public FunctionalProcedure(Set<Mechanism<?>> reservations, Consumer<Context> runnable) {
public FunctionalProcedure(Set<Mechanism<?, ?>> reservations, Consumer<Context> runnable) {
this(runnable.toString(), reservations, runnable);
}

public FunctionalProcedure(
String name, Set<Mechanism<?>> reservations, Consumer<Context> runnable) {
String name, Set<Mechanism<?, ?>> reservations, Consumer<Context> runnable) {
super(name, reservations);
this.runnable = runnable;
}
Expand Down
2 changes: 1 addition & 1 deletion src/main/java/com/team766/framework3/InstantProcedure.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ protected InstantProcedure() {
super();
}

protected InstantProcedure(String name, Set<Mechanism<?>> reservations) {
protected InstantProcedure(String name, Set<Mechanism<?, ?>> reservations) {
super(name, reservations);
}

Expand Down
21 changes: 16 additions & 5 deletions src/main/java/com/team766/framework3/Mechanism.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,15 +4,18 @@
import com.team766.logging.LoggerExceptionUtils;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import java.util.NoSuchElementException;
import java.util.Objects;

public abstract class Mechanism<R extends Request<?>> extends SubsystemBase implements LoggingBase {
public abstract class Mechanism<R extends Request, S extends Record & Status> extends SubsystemBase
implements LoggingBase {
private Thread m_runningPeriodic = null;

private Mechanism<?> superstructure = null;
private Mechanism<?, ?> superstructure = null;

private R request = null;
private boolean isRequestNew = false;
private S status = null;

/**
* This Command runs when no other Command (i.e. Procedure) is reserving this Mechanism.
Expand Down Expand Up @@ -56,7 +59,7 @@ public Category getLoggerCategory() {
return Category.MECHANISMS;
}

public void setSuperstructure(Mechanism<?> s) {
public void setSuperstructure(Mechanism<?, ?> s) {
Objects.requireNonNull(s);
if (superstructure != null) {
throw new IllegalStateException();
Expand Down Expand Up @@ -113,6 +116,13 @@ protected void checkContextReservation() {
ReservingCommand.checkCurrentCommandHasReservation(this);
}

public S getMechanismStatus() {
if (status == null) {
throw new NoSuchElementException(getName() + " has not published a status yet");
}
return status;
}

@Override
public final void periodic() {
super.periodic();
Expand All @@ -124,7 +134,8 @@ public final void periodic() {
}
boolean wasRequestNew = isRequestNew;
isRequestNew = false;
run(request, wasRequestNew);
status = run(request, wasRequestNew);
StatusBus.publishStatus(status);
} catch (Exception ex) {
ex.printStackTrace();
LoggerExceptionUtils.logException(ex);
Expand All @@ -133,5 +144,5 @@ public final void periodic() {
}
}

protected abstract void run(R request, boolean isRequestNew);
protected abstract S run(R request, boolean isRequestNew);
}
14 changes: 7 additions & 7 deletions src/main/java/com/team766/framework3/Procedure.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,19 +22,19 @@ private static synchronized int createNewId() {
}

private final String name;
private final Set<Mechanism<?>> reservations;
private final Set<Mechanism<?, ?>> reservations;

protected Procedure() {
this.name = createName();
this.reservations = Sets.newHashSet();
}

protected Procedure(Set<Mechanism<?>> reservations) {
protected Procedure(Set<Mechanism<?, ?>> reservations) {
this.name = createName();
this.reservations = reservations;
}

protected Procedure(String name, Set<Mechanism<?>> reservations) {
protected Procedure(String name, Set<Mechanism<?, ?>> reservations) {
this.name = name;
this.reservations = reservations;
}
Expand All @@ -59,22 +59,22 @@ public Category getLoggerCategory() {
return Category.PROCEDURES;
}

protected final <M extends Mechanism<?>> M reserve(M m) {
protected final <M extends Mechanism<?, ?>> M reserve(M m) {
reservations.add(m);
return m;
}

protected final void reserve(Mechanism<?>... ms) {
protected final void reserve(Mechanism<?, ?>... ms) {
for (var m : ms) {
reservations.add(m);
}
}

protected final void reserve(Collection<? extends Mechanism<?>> ms) {
protected final void reserve(Collection<? extends Mechanism<?, ?>> ms) {
reservations.addAll(ms);
}

public final Set<Mechanism<?>> reservations() {
public final Set<Mechanism<?, ?>> reservations() {
return reservations;
}

Expand Down
7 changes: 3 additions & 4 deletions src/main/java/com/team766/framework3/Request.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,13 +9,12 @@
*
* Each Mechanism will have its own implementation of the {@link Request} marker interface.
*/
public interface Request<S extends Status> {
public interface Request {

/**
* Checks whether or not this request has been fulfilled, via the supplied {@link Status}. This
* {@link Status} should be the latest one retrieved via {@link StatusBus#getStatus(Class)}.
* Checks whether or not this request has been fulfilled.
*/
boolean isDone(S status);
boolean isDone();

// TODO(MF3): do we need any way of checking if the request has been bumped/canceled?
}
14 changes: 8 additions & 6 deletions src/main/java/com/team766/framework3/Rule.java
Original file line number Diff line number Diff line change
Expand Up @@ -134,15 +134,17 @@ public Builder withOnTriggeringProcedure(
}

public Builder withOnTriggeringProcedure(
RulePersistence rulePersistence, Set<Mechanism<?>> reservations, Runnable action) {
RulePersistence rulePersistence,
Set<Mechanism<?, ?>> reservations,
Runnable action) {
applyRulePersistence(
rulePersistence, () -> new FunctionalInstantProcedure(reservations, action));
return this;
}

public Builder withOnTriggeringProcedure(
RulePersistence rulePersistence,
Set<Mechanism<?>> reservations,
Set<Mechanism<?, ?>> reservations,
Consumer<Context> action) {
applyRulePersistence(
rulePersistence, () -> new FunctionalProcedure(reservations, action));
Expand All @@ -156,7 +158,7 @@ public Builder withFinishedTriggeringProcedure(Supplier<Procedure> action) {
}

public Builder withFinishedTriggeringProcedure(
Set<Mechanism<?>> reservations, Runnable action) {
Set<Mechanism<?, ?>> reservations, Runnable action) {
this.finishedTriggeringProcedure =
() -> new FunctionalInstantProcedure(reservations, action);
return this;
Expand Down Expand Up @@ -204,7 +206,7 @@ public List<Rule> build(BooleanSupplier parentPredicate) {
private final BooleanSupplier predicate;
private final Map<TriggerType, Supplier<Procedure>> triggerProcedures =
Maps.newEnumMap(TriggerType.class);
private final Map<TriggerType, Set<Mechanism<?>>> triggerReservations =
private final Map<TriggerType, Set<Mechanism<?, ?>>> triggerReservations =
Maps.newEnumMap(TriggerType.class);
private final Map<TriggerType, Cancellation> triggerCancellation =
Maps.newEnumMap(TriggerType.class);
Expand Down Expand Up @@ -246,7 +248,7 @@ private Rule(
}
}

private static Set<Mechanism<?>> getReservationsForProcedure(Supplier<Procedure> supplier) {
private static Set<Mechanism<?, ?>> getReservationsForProcedure(Supplier<Procedure> supplier) {
if (supplier != null) {
Procedure procedure = supplier.get();
if (procedure != null) {
Expand Down Expand Up @@ -284,7 +286,7 @@ public String getName() {
}
}

/* package */ Set<Mechanism<?>> getMechanismsToReserve() {
/* package */ Set<Mechanism<?, ?>> getMechanismsToReserve() {
if (triggerReservations.containsKey(currentTriggerType)) {
return triggerReservations.get(currentTriggerType);
}
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/com/team766/framework3/RuleEngine.java
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ protected Rule getRuleForTriggeredProcedure(Command command) {
}

public final void run() {
Set<Mechanism<?>> mechanismsToUse = new HashSet<>();
Set<Mechanism<?, ?>> mechanismsToUse = new HashSet<>();

// TODO(MF3): when creating a Procedure, check that the reservations are the same as
// what the Rule pre-computed.
Expand All @@ -95,9 +95,9 @@ public final void run() {
int priority = getPriorityForRule(rule);

// see if there are mechanisms a potential procedure would want to reserve
Set<Mechanism<?>> reservations = rule.getMechanismsToReserve();
Set<Mechanism<?, ?>> reservations = rule.getMechanismsToReserve();
log(Severity.INFO, "Rule " + rule.getName() + " would reserve " + reservations);
for (Mechanism<?> mechanism : reservations) {
for (Mechanism<?, ?> mechanism : reservations) {
// see if any of the mechanisms higher priority rules will use would also be
// used by this lower priority rule's procedure.
if (mechanismsToUse.contains(mechanism)) {
Expand Down
Loading

0 comments on commit 9fe1b44

Please sign in to comment.