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

Commit

Permalink
Revert "Status handles"
Browse files Browse the repository at this point in the history
  • Loading branch information
rcahoon committed Dec 27, 2024
1 parent 0d5e659 commit ac04ccc
Show file tree
Hide file tree
Showing 21 changed files with 83 additions and 115 deletions.
5 changes: 2 additions & 3 deletions src/main/java/com/team766/framework3/Mechanism.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,7 +13,7 @@
import java.util.Set;

public abstract class Mechanism<S extends Record & Status>
implements Reservable, StatusSource<S>, LoggingBase {
implements Reservable, LoggingBase {
@FunctionalInterface
public interface Directive {
/**
Expand Down Expand Up @@ -205,7 +205,6 @@ public final Set<Subsystem> getReservableSubsystems() {
return Set.of(subsystem);
}

@Override
public final S getStatus() {
if (status == null) {
throw new NoSuchElementException(getName() + " has not published a status yet");
Expand All @@ -216,7 +215,7 @@ public final S getStatus() {
/* package */ void periodicInternal() {
try {
status = reportStatus();
publishStatus(status);
StatusBus.getInstance().publishStatus(status);

isRunningPeriodic = true;
request.runDirective();
Expand Down
12 changes: 10 additions & 2 deletions src/main/java/com/team766/framework3/MultiFacetedMechanism.java
Original file line number Diff line number Diff line change
@@ -1,6 +1,7 @@
package com.team766.framework3;

import java.util.HashSet;
import java.util.NoSuchElementException;
import java.util.Objects;
import java.util.Set;
import com.team766.framework.StackTraceUtils;
Expand All @@ -12,7 +13,7 @@
import edu.wpi.first.wpilibj2.command.SubsystemBase;

public abstract class MultiFacetedMechanism<S extends Record & Status>
implements StatusSource<S>, Reservable, LoggingBase {
implements Reservable, LoggingBase {
@SuppressWarnings("unused")
private SubsystemBase outerSubsystem =
new SubsystemBase() {
Expand Down Expand Up @@ -61,6 +62,13 @@ public void checkContextReservation() {
}
}

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

@Override
public Set<Subsystem> getReservableSubsystems() {
return facetSubsystems;
Expand All @@ -74,7 +82,7 @@ public Category getLoggerCategory() {
/* package */ void periodicInternal() {
try {
status = reportStatus();
publishStatus(status);
StatusBus.getInstance().publishStatus(status);

run();
} catch (Exception ex) {
Expand Down
26 changes: 12 additions & 14 deletions src/main/java/com/team766/framework3/StatusBus.java
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
public class StatusBus {

private static StatusBus s_instance = new StatusBus();
private final Map<Class<? extends StatusHandle<?>>, Entry<?>> statuses = new LinkedHashMap<>();
private final Map<Class<?>, Entry<?>> statuses = new LinkedHashMap<>();

/**
* Get the Singleton instance of the {@link StatusBus}.
Expand Down Expand Up @@ -51,10 +51,9 @@ public void clear() {
*
* This method also logs the Status to diagnostic logs.
*/
public <H extends StatusHandle<S>, S extends Record & Status> Entry<S> publishStatus(
Class<H> handle, S status) {
public <S extends Record & Status> Entry<S> publishStatus(S status) {
var entry = new Entry<>(status, RobotProvider.instance.getClock().getTime());
statuses.put(handle, entry);
statuses.put(status.getClass(), entry);
// TODO(MF3): also publish to data logs
Logger.get(Category.FRAMEWORK)
.logRaw(
Expand All @@ -79,9 +78,8 @@ public <H extends StatusHandle<S>, S extends Record & Status> Entry<S> publishSt
* Optional if the {@link Status} hasn't been published.
*/
@SuppressWarnings("unchecked")
public <H extends StatusHandle<S>, S extends Status> Optional<Entry<S>> getStatusEntry(
Class<H> handle) {
return Optional.ofNullable((Entry<S>) statuses.get(handle));
public <S extends Status> Optional<Entry<S>> getStatusEntry(Class<S> statusClass) {
return Optional.ofNullable((Entry<S>) statuses.get(statusClass));
}

/**
Expand All @@ -96,8 +94,8 @@ public <H extends StatusHandle<S>, S extends Status> Optional<Entry<S>> getStatu
* The latest published {@link Status} or an empty Optional if the {@link Status} hasn't
* been published.
*/
public <H extends StatusHandle<S>, S extends Status> Optional<S> getStatus(Class<H> handle) {
return getStatusEntry(handle).map(Entry<S>::status);
public <S extends Status> Optional<S> getStatus(Class<S> statusClass) {
return getStatusEntry(statusClass).map(Entry<S>::status);
}

/**
Expand All @@ -111,8 +109,8 @@ public <H extends StatusHandle<S>, S extends Status> Optional<S> getStatus(Class
* @return The latest published {@link Status}
* @throws NoSuchElementException if the {@link Status} hasn't been published
*/
public <H extends StatusHandle<S>, S extends Status> S getStatusOrThrow(Class<H> handle) {
return getStatus(handle).orElseThrow();
public <S extends Status> S getStatusOrThrow(Class<S> statusClass) {
return getStatus(statusClass).orElseThrow();
}

/**
Expand All @@ -128,8 +126,8 @@ public <H extends StatusHandle<S>, S extends Status> S getStatusOrThrow(Class<H>
* The result of the Function applied to the latest published {@link Status} or an empty
* Optional if the {@link Status} hasn't been published.
*/
public <H extends StatusHandle<S>, S extends Status, V> Optional<V> getStatusValue(
Class<H> handle, Function<S, V> getter) {
return getStatusEntry(handle).map(s -> getter.apply(s.status()));
public <S extends Status, V> Optional<V> getStatusValue(
Class<S> statusClass, Function<S, V> getter) {
return getStatusEntry(statusClass).map(s -> getter.apply(s.status()));
}
}
3 changes: 0 additions & 3 deletions src/main/java/com/team766/framework3/StatusHandle.java

This file was deleted.

13 changes: 0 additions & 13 deletions src/main/java/com/team766/framework3/StatusSource.java

This file was deleted.

68 changes: 34 additions & 34 deletions src/main/java/com/team766/framework3/StatusesMixin.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,96 +6,96 @@
import java.util.Optional;
import java.util.function.Function;
import java.util.function.Predicate;
import com.team766.library.ReflectionUtils;

public interface StatusesMixin {
default <SH extends Record & Status & StatusHandle<SH>>
StatusBus.Entry<SH> publishStatus(SH status) {
return StatusBus.getInstance().publishStatus(ReflectionUtils.getClass(status), status);
/**
* @see StatusBus#publishStatus(Record)
*/
default <S extends Record & Status> StatusBus.Entry<S> publishStatus(S status) {
return StatusBus.getInstance().publishStatus(status);
}

/**
* @see StatusBus#getStatusEntry(Class)
*/
default <H extends StatusHandle<S>, S extends Status>
Optional<StatusBus.Entry<S>> getStatusEntry(Class<H> handle) {
return StatusBus.getInstance().getStatusEntry(handle);
default <S extends Status> Optional<StatusBus.Entry<S>> getStatusEntry(Class<S> statusClass) {
return StatusBus.getInstance().getStatusEntry(statusClass);
}

/**
* @see StatusBus#getStatus(Class)
*/
default <H extends StatusHandle<S>, S extends Status> Optional<S> getStatus(Class<H> handle) {
return StatusBus.getInstance().getStatus(handle);
default <S extends Status> Optional<S> getStatus(Class<S> statusClass) {
return StatusBus.getInstance().getStatus(statusClass);
}

/**
* @see StatusBus#getStatusOrThrow(Class)
*/
default <H extends StatusHandle<S>, S extends Status> S getStatusOrThrow(Class<H> handle) {
return StatusBus.getInstance().getStatusOrThrow(handle);
default <S extends Status> S getStatusOrThrow(Class<S> statusClass) {
return StatusBus.getInstance().getStatusOrThrow(statusClass);
}

/**
* @see StatusBus#getStatusValue(Class, Function)
*/
default <H extends StatusHandle<S>, S extends Status, V> Optional<V> getStatusValue(
Class<H> handle, Function<S, V> getter) {
return StatusBus.getInstance().getStatusValue(handle, getter);
default <S extends Status, V> Optional<V> getStatusValue(
Class<S> statusClass, Function<S, V> getter) {
return StatusBus.getInstance().getStatusValue(statusClass, getter);
}

/**
* Predicate that checks whether or not a {@link Status} with the given class has been published
*/
default <H extends StatusHandle<S>, S extends Status> boolean checkForStatus(Class<H> handle) {
return getStatusEntry(handle).isPresent();
default <S extends Status> boolean checkForStatus(Class<S> statusClass) {
return getStatusEntry(statusClass).isPresent();
}

/**
* Predicate that checks whether or not the latest {@link Status} with the given class passes
* the check provided by {@code predicate}.
*/
default <H extends StatusHandle<S>, S extends Status> boolean checkForStatusWith(
Class<H> handle, Predicate<S> predicate) {
return getStatusValue(handle, predicate::test).orElse(false);
default <S extends Status> boolean checkForStatusWith(
Class<S> statusClass, Predicate<S> predicate) {
return getStatusValue(statusClass, predicate::test).orElse(false);
}

/**
* Predicate that checks whether or not the latest {@link Status} with the given class passes
* the check provided by {@code predicate}, including additional metadata about how the Status
* was published.
*/
default <H extends StatusHandle<S>, S extends Status> boolean checkForStatusEntryWith(
Class<H> handle, Predicate<StatusBus.Entry<S>> predicate) {
return getStatusEntry(handle).map(predicate::test).orElse(false);
default <S extends Status> boolean checkForStatusEntryWith(
Class<S> statusClass, Predicate<StatusBus.Entry<S>> predicate) {
return getStatusEntry(statusClass).map(predicate::test).orElse(false);
}

/**
* Suspend the Procedure until a {@link Status} with the given class has been published, then
* return that Status.
*/
default <H extends StatusHandle<S>, S extends Status> S waitForStatus(
Context context, Class<H> handle) {
return waitForValue(context, () -> getStatus(handle));
default <S extends Status> S waitForStatus(
Context context, Class<S> statusClass) {
return waitForValue(context, () -> getStatus(statusClass));
}

/**
* Suspend the Procedure until a {@link Status} with the given class has been published, or
* we've waited for at least {@code timeoutSeconds}. Returns an Optional containing the Status
* if one was published, or return an empty Optional if the timeout was reached.
*/
default <H extends StatusHandle<S>, S extends Status> Optional<S> waitForStatusOrTimeout(
Context context, Class<H> handle, double timeoutSeconds) {
return waitForValueOrTimeout(context, () -> getStatus(handle), timeoutSeconds);
default <S extends Status> Optional<S> waitForStatusOrTimeout(
Context context, Class<S> statusClass, double timeoutSeconds) {
return waitForValueOrTimeout(context, () -> getStatus(statusClass), timeoutSeconds);
}

/**
* Suspend the Procedure until a {@link Status} with the given class has been published that
* passes the check provided by {@code predicate}, then return that Status.
*/
default <H extends StatusHandle<S>, S extends Status> S waitForStatusWith(
Context context, Class<H> handle, Predicate<S> predicate) {
return waitForValue(context, () -> getStatus(handle).filter(predicate));
default <S extends Status> S waitForStatusWith(
Context context, Class<S> statusClass, Predicate<S> predicate) {
return waitForValue(context, () -> getStatus(statusClass).filter(predicate));
}

/**
Expand All @@ -104,9 +104,9 @@ default <H extends StatusHandle<S>, S extends Status> S waitForStatusWith(
* {@code timeoutSeconds}. Returns an Optional containing the Status if one was published, or
* return an empty Optional if the timeout was reached.
*/
default <H extends StatusHandle<S>, S extends Status> Optional<S> waitForStatusWithOrTimeout(
Context context, Class<H> handle, Predicate<S> predicate, double timeoutSeconds) {
default <S extends Status> Optional<S> waitForStatusWithOrTimeout(
Context context, Class<S> statusClass, Predicate<S> predicate, double timeoutSeconds) {
return waitForValueOrTimeout(
context, () -> getStatus(handle).filter(predicate), timeoutSeconds);
context, () -> getStatus(statusClass).filter(predicate), timeoutSeconds);
}
}
17 changes: 0 additions & 17 deletions src/main/java/com/team766/library/ReflectionUtils.java

This file was deleted.

4 changes: 2 additions & 2 deletions src/main/java/com/team766/robot/burro_elevator/Lights.java
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ public Lights() {
"Elevator top",
() ->
checkForStatusWith(
Elevator.class,
Elevator.ElevatorStatus.class,
s -> s.position() >= Elevator.TOP_POSITION))
.withOnTriggeringProcedure(ONCE_AND_HOLD, Set.of(), () -> elevatorAtTop()));

Expand All @@ -40,7 +40,7 @@ public Lights() {
"Elevator bottom",
() ->
checkForStatusWith(
Elevator.class,
Elevator.ElevatorStatus.class,
s -> s.position() <= Elevator.BOTTOM_POSITION))
.withOnTriggeringProcedure(
ONCE_AND_HOLD, Set.of(), () -> elevatorAtBottom()));
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@ public void run(Context context) {

// intitialization

var driveStatus = waitForStatus(context, SwerveDrive.class);
var driveStatus = waitForStatus(context, SwerveDrive.DriveStatus.class);
Pose2d curPose = driveStatus.currentPosition();
ChassisSpeeds currentSpeeds = driveStatus.chassisSpeeds();

Expand All @@ -67,7 +67,7 @@ public void run(Context context) {
while (!timer.hasElapsed(generatedTrajectory.getTotalTimeSeconds())) {
double currentTime = timer.get();
PathPlannerTrajectory.State targetState = generatedTrajectory.sample(currentTime);
driveStatus = waitForStatus(context, SwerveDrive.class);
driveStatus = waitForStatus(context, SwerveDrive.DriveStatus.class);
curPose = driveStatus.currentPosition();
currentSpeeds = driveStatus.chassisSpeeds();

Expand Down
8 changes: 4 additions & 4 deletions src/main/java/com/team766/robot/gatorade/Lights.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,12 +23,12 @@ public Lights() {
addRule(
Rule.create(
"OI State Updated",
() -> checkForStatusEntryWith(OI.class, s -> s.age() < 1.3))
() -> checkForStatusEntryWith(OI.OIStatus.class, s -> s.age() < 1.3))
.withOnTriggeringProcedure(
REPEATEDLY,
Set.of(),
() -> {
final OI.OIStatus status = getStatusOrThrow(OI.class);
final OI.OIStatus status = getStatusOrThrow(OI.OIStatus.class);
setLightsForGamePiece(status.gamePieceType());
setLightsForPlacement(
status.placementPosition(), status.gamePieceType());
Expand All @@ -43,12 +43,12 @@ public Lights() {
.withOnTriggeringProcedure(ONCE_AND_HOLD, Set.of(), () -> rainbow()));

addRule(
Rule.create("Default display", () -> checkForStatus(OI.class))
Rule.create("Default display", () -> checkForStatus(OI.OIStatus.class))
.withOnTriggeringProcedure(
REPEATEDLY,
Set.of(),
() -> {
final OI.OIStatus status = getStatusOrThrow(OI.class);
final OI.OIStatus status = getStatusOrThrow(OI.OIStatus.class);
setLightsForGamePiece(status.gamePieceType());
setLightsForPlacement(
status.placementPosition(), status.gamePieceType());
Expand Down
3 changes: 1 addition & 2 deletions src/main/java/com/team766/robot/gatorade/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,6 @@
import com.team766.framework3.Rule;
import com.team766.framework3.RuleEngine;
import com.team766.framework3.Status;
import com.team766.framework3.StatusSource;
import com.team766.hal.JoystickReader;
import com.team766.hal.RobotProvider;
import com.team766.robot.common.DriverOI;
Expand All @@ -20,7 +19,7 @@
* This class is the glue that binds the controls on the physical operator interface to the code
* that allow control of the robot.
*/
public class OI extends RuleEngine implements StatusSource<OI.OIStatus> {
public class OI extends RuleEngine {

public record OIStatus(GamePieceType gamePieceType, PlacementPosition placementPosition)
implements Status {}
Expand Down
Loading

0 comments on commit ac04ccc

Please sign in to comment.