Skip to content

Commit

Permalink
Add event Trigger API
Browse files Browse the repository at this point in the history
idk why but my ide is acting up so there are probably errors that ill fix later. Anyway, I added a static field in Choreo.java which stores the current trajectory that the robot is on. Calling choreoSwerveCommand() will update this to the trajectory it is given, and then, when finished, put it back to an empty trajectory. There is also now a new static event() method in Choreo.java which returns a trigger for if the robot is currently on a trajectory given as an argument.

holy guacamole i forgot a semicolon

imported trigger

i mightve jumped the gun but i was bored so heres another event function. is this good

more methodsgit add .! more

le fixes

Add list of keyboard shortcuts to document settings (SleipnirGroup#447)

Co-authored-by: Jacob Trentini <[email protected]>

Feature: Context Menu (SleipnirGroup#448)

* add context menu with popover

* format

* silence error with conflicting mouseevent

* format

* works but only if you hot reload (fixing with next commit)

* step 1 out of predicted 2: migrate local state to uiState

* step 2/2: move d3 callback to overlaywaypoint

* format

* format and refactorings

* address @calcmogul's concerns

Upgrade TrajoptLib to use larger solver tolerance (SleipnirGroup#451)

organization and comments

renaming

cleanup java impl

fix docs

format
  • Loading branch information
Chotch13 authored and spacey-sooty committed Jun 23, 2024
1 parent 5d15493 commit 24724fa
Show file tree
Hide file tree
Showing 2 changed files with 193 additions and 96 deletions.
102 changes: 99 additions & 3 deletions choreolib/src/main/java/com/choreo/lib/Choreo.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.FunctionalCommand;
import edu.wpi.first.wpilibj2.command.Subsystem;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import java.io.BufferedReader;
import java.io.File;
import java.io.FileReader;
Expand All @@ -24,6 +25,10 @@
public class Choreo {
private static final Gson gson = new Gson();

private static ChoreoTrajectory emptyTraj = new ChoreoTrajectory();
private static ChoreoTrajectory currentTraj = emptyTraj;
private static boolean started = false;

/** Default constructor. */
public Choreo() {}

Expand All @@ -48,8 +53,8 @@ public static ChoreoTrajectory getTrajectory(String trajName) {
*
* <p>This method determines the number of parts to load by counting the files that match the
* pattern "trajName.X.traj", where X is a string of digits. Let this count be N. It then attempts
* to load "trajName.1.traj" through "trajName.N.traj", consecutively counting up. If any of these
* files cannot be loaded, the method returns null.
* // * to load "trajName.1.traj" through "trajName.N.traj", consecutively counting up. If any of
* these files cannot be loaded, the method returns null.
*
* @param trajName The path name in Choreo for this trajectory.
* @return The ArrayList of segments, in order, or null.
Expand Down Expand Up @@ -155,7 +160,10 @@ public static Command choreoSwerveCommand(
Subsystem... requirements) {
var timer = new Timer();
return new FunctionalCommand(
timer::restart,
() -> {
timer.restart();
currentTraj = trajectory;
},
() -> {
;
outputChassisSpeeds.accept(
Expand All @@ -165,6 +173,8 @@ public static Command choreoSwerveCommand(
},
(interrupted) -> {
timer.stop();
currentTraj = emptyTraj;

if (interrupted) {
outputChassisSpeeds.accept(new ChassisSpeeds());
} else {
Expand Down Expand Up @@ -205,4 +215,90 @@ public static ChoreoControlFunction choreoSwerveController(
xFF + xFeedback, yFF + yFeedback, rotationFF + rotationFeedback, pose.getRotation());
};
}

private static boolean onTrajectory(String trajName) {
return currentTraj == getTrajectory(trajName);
}

/**
* Returns a Trigger which fires if the robot is currently on a given ChoreoTrajectory.
*
* @param trajName The file name (without the .traj) of the given trajectory.
* @return A Trigger which activates if the robot is on the trajectory trajName.
*/
public static Trigger trajTrigger(String trajName) {
return new Trigger(() -> Choreo.onTrajectory(trajName));
}

/**
* Returns a Trigger which fires when the robot hits an event marker, then stops when the robot
* starts on a different trajectory.
*
* @param trajName The file name (without the .traj) of the given trajectory.
* @param offset The time between when the inputted trajectory is started and when the event
* trigger should fire.
* @return A Trigger which activates when the robot hits an event marker.
*/
public static Trigger pointTrigger(String trajName, double offset) {
var timer = new Timer();
return new Trigger(
() -> {
if (onTrajectory(trajName) && !started) {
started = true;
timer.restart();
}
return started && timer.hasElapsed(offset) && onTrajectory(trajName);
});
}

/**
* Returns a Trigger which activates at a certain time since starting on a ChoreoTrajectory, then
* deactivates at a point in time after that. The generated Triggers will not stop firing even
* when the robot starts on another ChoreoTrajectory.
*
* @param trajName The file name (without the .traj) of the given trajectory.
* @param risingEdge The time since the robot has started on the trajectory trajName, in seconds,
* that the trigger should begin to fire.
* @param fallingEdge The time since the robot has started on the trajectory trajName, in seconds,
* that the trigger should stop firing. fallingEdge should be a greater number than
* risingEdge, or the Trigger will not fire.
* @return A Trigger which activates if the robot is on the trajectory trajName.
*/
public static Trigger spanTrigger(String trajName, double risingEdge, double fallingEdge) {
var timer = new Timer();
return new Trigger(
() -> {
if (onTrajectory(trajName) && !started) {
started = true;
timer.restart();
}
return started && timer.hasElapsed(risingEdge) && !timer.hasElapsed(fallingEdge);
});
}

/**
* Returns a Trigger which activates for a certain period of time after the robot hits an event
* marker. The created Triggers will not stop firing even when the robot starts on another
* ChoreoTrajectory.
*
* @param trajName The file name (without the .traj) of the given trajectory.
* @param offset The time in seconds between when the inputted trajectory is started and when the
* event trigger should fire.
* @param length The duration of the trigger in seconds, from start to finish.
* @return A Trigger which activates if the robot is on the trajectory trajName.
*/
public static Trigger spotTrigger(String trajName, double offset, double length) {
var timer = new Timer();
return new Trigger(
() -> {
if (onTrajectory(trajName) && !started) {
started = true;
timer.restart();
}
return started
&& timer.hasElapsed(offset)
&& onTrajectory(trajName)
&& !timer.hasElapsed(offset + length);
});
}
}
Loading

0 comments on commit 24724fa

Please sign in to comment.