Skip to content
This repository has been archived by the owner on Jan 13, 2025. It is now read-only.

Commit

Permalink
code review
Browse files Browse the repository at this point in the history
  • Loading branch information
rcahoon committed Sep 13, 2024
1 parent 193e68f commit ede56f7
Show file tree
Hide file tree
Showing 13 changed files with 92 additions and 74 deletions.
13 changes: 4 additions & 9 deletions src/main/java/com/team766/framework3/AutonomousMode.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,21 +5,16 @@
import java.util.function.Supplier;

public class AutonomousMode implements AutonomousSelector.Selectable<AutonomousMode> {
private final Supplier<Command> m_constructor;
private final Supplier<Procedure> m_constructor;
private final String m_name;

public AutonomousMode(final String name, final Supplier<Command> constructor) {
m_constructor = constructor;
public AutonomousMode(final String name, final Supplier<Procedure> constructor) {
m_name = name;
}

public AutonomousMode(
final String name, final com.google.common.base.Supplier<Procedure> constructor) {
this(name, () -> new ContextImpl(constructor.get()));
m_constructor = () -> constructor.get();
}

public Command instantiate() {
return m_constructor.get();
return m_constructor.get().createCommand();
}

public String name() {
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/com/team766/framework3/Context.java
Original file line number Diff line number Diff line change
Expand Up @@ -94,18 +94,23 @@ public interface Context {
/**
* Run the given Procedure synchronously (the calling Procedure will not resume until this one
* has finished).
* The given procedure must only reserve Mechanisms that were reserved by the calling Procedure.
*/
void runSync(final Procedure func);

/**
* Run the given Procedures at the same time. The calling Procedure will resume after all
* Procedures in the group finish.
* The given procedures must only reserve Mechanisms that were reserved by the calling Procedure,
* and their reservations must not overlap.
*/
void runParallel(Procedure... procedures);

/**
* Run the given Procedures at the same time. The calling Procedure will resume once any
* Procedure in the group finishes, and the others will be cancelled.
* The given procedures must only reserve Mechanisms that were reserved by the calling Procedure,
* and their reservations must not overlap.
*/
void runParallelRace(Procedure... procedures);
}
8 changes: 4 additions & 4 deletions src/main/java/com/team766/framework3/ContextImpl.java
Original file line number Diff line number Diff line change
Expand Up @@ -360,23 +360,23 @@ public void runSync(final Procedure procedure) {

@Override
public void runParallel(Procedure... procedures) {
var contexts = new ContextImpl[procedures.length];
var contexts = new Command[procedures.length];
for (int i = 0; i < contexts.length; ++i) {
var procedure = procedures[i];
checkProcedureReservationsSubset(procedure);
contexts[i] = new ContextImpl(procedure);
contexts[i] = procedure.createCommand();
}
// NOTE: Commands.parallel will ensure procedures' reservations are disjoint.
runSync(new WPILibCommandProcedure(Commands.parallel(contexts)));
}

@Override
public void runParallelRace(Procedure... procedures) {
var contexts = new ContextImpl[procedures.length];
var contexts = new Command[procedures.length];
for (int i = 0; i < contexts.length; ++i) {
var procedure = procedures[i];
checkProcedureReservationsSubset(procedure);
contexts[i] = new ContextImpl(procedure);
contexts[i] = procedure.createCommand();
}
// NOTE: Commands.race will ensure procedures' reservations are disjoint.
runSync(new WPILibCommandProcedure(Commands.race(contexts)));
Expand Down
Original file line number Diff line number Diff line change
@@ -1,12 +1,11 @@
package com.team766.framework3;

import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.Set;

public final class FunctionalInstantProcedure extends InstantProcedure {
private final Runnable runnable;

public FunctionalInstantProcedure(Set<Subsystem> reservations, Runnable runnable) {
public FunctionalInstantProcedure(Set<Mechanism<?>> reservations, Runnable runnable) {
super(runnable.toString(), reservations);
this.runnable = runnable;
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,13 +1,12 @@
package com.team766.framework3;

import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.Set;
import java.util.function.Consumer;

public final class FunctionalProcedure extends Procedure {
private final Consumer<Context> runnable;

public FunctionalProcedure(Set<Subsystem> reservations, Consumer<Context> runnable) {
public FunctionalProcedure(Set<Mechanism<?>> reservations, Consumer<Context> runnable) {
super(runnable.toString(), reservations);
this.runnable = runnable;
}
Expand Down
3 changes: 1 addition & 2 deletions src/main/java/com/team766/framework3/InstantProcedure.java
Original file line number Diff line number Diff line change
@@ -1,15 +1,14 @@
package com.team766.framework3;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.Set;

public abstract class InstantProcedure extends Procedure implements Runnable {
protected InstantProcedure() {
super();
}

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

Expand Down
8 changes: 3 additions & 5 deletions src/main/java/com/team766/framework3/Mechanism.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,21 +13,19 @@ public abstract class Mechanism<R extends Request<?>> extends SubsystemBase impl
private R request = null;
private boolean isRequestNew = false;

protected Category loggerCategory = Category.MECHANISMS;

@Override
public Category getLoggerCategory() {
return loggerCategory;
return Category.MECHANISMS;
}

public final void setRequest(R request) {
checkContextOwnership();
checkContextReservation();
this.request = request;
isRequestNew = true;
log(this.getClass().getName() + " processing request: " + request);
}

protected void checkContextOwnership() {
protected void checkContextReservation() {
var owningCommand = CommandScheduler.getInstance().requiring(this);
if ((owningCommand == null || SchedulerMonitor.currentCommand != owningCommand)
&& m_runningPeriodic == null) {
Expand Down
18 changes: 8 additions & 10 deletions src/main/java/com/team766/framework3/Procedure.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@
import com.google.common.collect.Sets;
import com.team766.logging.Category;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.Collection;
import java.util.Set;

Expand All @@ -23,22 +22,21 @@ private static synchronized int createNewId() {
}

private final String name;
private final Set<Subsystem> reservations;
protected Category loggerCategory = Category.PROCEDURES;
private final Set<Mechanism<?>> reservations;

protected Procedure() {
this.name = this.getClass().getName() + "/" + createNewId();
this.reservations = Sets.newHashSet();
}

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

public abstract void run(Context context);

Command createCommand() {
/* package */ Command createCommand() {
return new ContextImpl(this);
}

Expand All @@ -49,25 +47,25 @@ public final String getName() {

@Override
public Category getLoggerCategory() {
return loggerCategory;
return Category.PROCEDURES;
}

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

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

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

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

Expand Down
16 changes: 8 additions & 8 deletions src/main/java/com/team766/framework3/Rule.java
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package com.team766.framework3;

import com.google.common.collect.Maps;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.Collections;
import java.util.Map;
import java.util.Set;
Expand Down Expand Up @@ -37,7 +36,7 @@ public class Rule {
* Functional interface for creating new {@link Procedure}s.
*/
@FunctionalInterface
private interface ProcedureCreator {
public interface ProcedureCreator {
Procedure create();
}

Expand Down Expand Up @@ -81,7 +80,8 @@ public Builder withNewlyTriggeringProcedure(ProcedureCreator action) {
return this;
}

public Builder withNewlyTriggeringProcedure(Set<Subsystem> reservations, Runnable action) {
public Builder withNewlyTriggeringProcedure(
Set<Mechanism<?>> reservations, Runnable action) {
this.newlyTriggeringProcedure =
() -> new FunctionalInstantProcedure(reservations, action);
return this;
Expand All @@ -94,7 +94,7 @@ public Builder withContinuingTriggeringProcedure(ProcedureCreator action) {
}

public Builder withContinuingTriggeringProcedure(
Set<Subsystem> reservations, Runnable action) {
Set<Mechanism<?>> reservations, Runnable action) {
this.continuingTriggeringProcedure =
() -> new FunctionalInstantProcedure(reservations, action);
return this;
Expand All @@ -107,7 +107,7 @@ public Builder withFinishedTriggeringProcedure(ProcedureCreator action) {
}

public Builder withFinishedTriggeringProcedure(
Set<Subsystem> reservations, Runnable action) {
Set<Mechanism<?>> reservations, Runnable action) {
this.finishedTriggeringProcedure =
() -> new FunctionalInstantProcedure(reservations, action);
return this;
Expand All @@ -128,7 +128,7 @@ public Builder withFinishedTriggeringProcedure(
private final BooleanSupplier predicate;
private final Map<TriggerType, ProcedureCreator> triggerProcedures =
Maps.newEnumMap(TriggerType.class);
private final Map<TriggerType, Set<Subsystem>> triggerReservations =
private final Map<TriggerType, Set<Mechanism<?>>> triggerReservations =
Maps.newEnumMap(TriggerType.class);

private TriggerType currentTriggerType = TriggerType.NONE;
Expand Down Expand Up @@ -173,7 +173,7 @@ private Rule(
}
}

private Set<Subsystem> getReservationsForProcedure(ProcedureCreator creator) {
private Set<Mechanism<?>> getReservationsForProcedure(ProcedureCreator creator) {
if (creator != null) {
Procedure procedure = creator.create();
if (procedure != null) {
Expand Down Expand Up @@ -211,7 +211,7 @@ public String getName() {
}
}

/* package */ Set<Subsystem> getMechanismsToReserve() {
/* package */ Set<Mechanism<?>> getMechanismsToReserve() {
if (triggerReservations.containsKey(currentTriggerType)) {
return triggerReservations.get(currentTriggerType);
}
Expand Down
44 changes: 25 additions & 19 deletions src/main/java/com/team766/framework3/RuleEngine.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,11 +3,11 @@
import com.google.common.collect.BiMap;
import com.google.common.collect.HashBiMap;
import com.team766.logging.Category;
import com.team766.logging.Logger;
import com.team766.logging.LoggerExceptionUtils;
import com.team766.logging.Severity;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;
import edu.wpi.first.wpilibj2.command.Subsystem;
import java.util.HashMap;
import java.util.HashSet;
import java.util.LinkedList;
Expand All @@ -27,8 +27,7 @@ protected RuleEngine() {}

@Override
public Category getLoggerCategory() {
// TODO: Is this the right default for RuleEngine?
return Category.OPERATOR_INTERFACE;
return Category.RULES;
}

protected void addRule(Rule.Builder builder) {
Expand All @@ -44,7 +43,7 @@ protected Rule getRuleForTriggeredProcedure(Command command) {
}

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

// TODO: when creating a Procedure, check that the reservations are the same as
// what the Rule pre-computed.
Expand All @@ -57,22 +56,27 @@ public final void run() {
// see if the rule is triggering/just finished triggering
Rule.TriggerType triggerType = rule.getCurrentTriggerType();
if (triggerType != Rule.TriggerType.NONE) {
log("Rule " + rule.getName() + " triggering: " + triggerType);
Logger.get(Category.FRAMEWORK)
.logRaw(
Severity.DEBUG,
"Rule " + rule.getName() + " triggering: " + triggerType);

int priority = rulePriorities.get(rule);

// see if there are mechanisms a potential procedure would want to reserve
Set<Subsystem> reservations = rule.getMechanismsToReserve();
for (Subsystem mechanism : reservations) {
Set<Mechanism<?>> reservations = rule.getMechanismsToReserve();
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)) {
log(
"RULE CONFLICT! Ignoring rule: "
+ rule.getName()
+ "; mechanism "
+ mechanism.getName()
+ " already reserved by higher priority rule.");
Logger.get(Category.FRAMEWORK)
.logRaw(
Severity.DEBUG,
"RULE CONFLICT! Ignoring rule: "
+ rule.getName()
+ "; mechanism "
+ mechanism.getName()
+ " already reserved by higher priority rule.");
continue;
}
// see if a previously triggered rule is still using the mechanism
Expand All @@ -87,12 +91,14 @@ public final void run() {
if (existingPriority < priority /* less is more */) {
// existing rule takes priority.
// don't proceed with this new rule.
log(
"RULE CONFLICT! Ignoring rule: "
+ rule
+ "; mechanism "
+ mechanism.getName()
+ " already reserved by higher priority rule.");
Logger.get(Category.FRAMEWORK)
.logRaw(
Severity.DEBUG,
"RULE CONFLICT! Ignoring rule: "
+ rule
+ "; mechanism "
+ mechanism.getName()
+ " already reserved by higher priority rule.");
continue;
}
}
Expand Down
Loading

0 comments on commit ede56f7

Please sign in to comment.