Skip to content

Commit

Permalink
Doc Expansion (#890)
Browse files Browse the repository at this point in the history
Co-authored-by: shueja <[email protected]>
Co-authored-by: GrahamSH <[email protected]>
Co-authored-by: Tyler Veness <[email protected]>
  • Loading branch information
4 people authored Nov 22, 2024
1 parent 329a14c commit b849eec
Show file tree
Hide file tree
Showing 11 changed files with 425 additions and 176 deletions.
2 changes: 1 addition & 1 deletion choreolib/src/main/java/choreo/Choreo.java
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ public static ProjectFile getProjectFile() {
} catch (FileNotFoundException ex) {
throw new RuntimeException("Could not find project file", ex);
} catch (IOException ex) {
throw new RuntimeException("Could not find project file", ex);
throw new RuntimeException("Could not close the project file", ex);
}
return LAZY_PROJECT_FILE.get();
}
Expand Down
98 changes: 79 additions & 19 deletions choreolib/src/main/java/choreo/auto/AutoChooser.java
Original file line number Diff line number Diff line change
Expand Up @@ -13,13 +13,16 @@
import java.util.function.Function;

/**
* An auto chooser that allows for the selection of auto routines at runtime.
* An Choreo specific {@code SendableChooser} that allows for the selection of {@link AutoRoutine}s
* at runtime via a <a
* href="https://docs.wpilib.org/en/stable/docs/software/dashboards/index.html#dashboards">Dashboard</a>.
*
* <p>This chooser takes a lazy loading approach to auto routines, only generating the auto routine
* when it is selected. This approach has the benefit of not loading all autos on startup, but also
* not loading the auto during auto start causing a delay.
* <p>This chooser takes a <a href="https://en.wikipedia.org/wiki/Lazy_loading">lazy loading</a>
* approach to {@link AutoRoutine}s, only generating the {@link AutoRoutine} when it is selected.
* This approach has the benefit of not loading all autos on startup, but also not loading the auto
* during auto start causing a delay.
*
* <p>Once the {@link AutoChooser} is made you can add auto routines to it using the {@link
* <p>Once the {@link AutoChooser} is made you can add {@link AutoRoutine}s to it using the {@link
* #addAutoRoutine(String, AutoRoutineGenerator)} method. Unlike {@code SendableChooser} this
* chooser has to be updated every cycle by calling the {@link #update()} method in your {@link
* IterativeRobotBase#robotPeriodic()}.
Expand Down Expand Up @@ -48,15 +51,18 @@ public static interface AutoRoutineGenerator extends Function<AutoFactory, AutoR
private AutoRoutine lastAutoRoutine = AutoRoutineGenerator.NONE.apply(null);

/**
* Create a new auto chooser.
* Constructs a new {@link AutoChooser}.
*
* @param factory The auto factory to use for auto routine generation.
* @param tableName The name of the network table to use for the chooser, passing in an empty
* string will put this chooser at the root of the network tables.
* @param factory The auto factory to use for AutoRoutine creation.
* @param tableName The name of the network table to use for the chooser. Passing in an empty
* string or null will put this chooser at the root of the network tables.
*/
public AutoChooser(AutoFactory factory, String tableName) {
this.factory = factory;

if (tableName == null) {
tableName = "";
}
String path = NetworkTable.normalizeKey(tableName, true) + "/AutoChooser";
NetworkTable table = NetworkTableInstance.getDefault().getTable(path);

Expand All @@ -72,10 +78,14 @@ public AutoChooser(AutoFactory factory, String tableName) {
* Update the auto chooser.
*
* <p>This method should be called every cycle in the {@link IterativeRobotBase#robotPeriodic()}.
* It will check if the selected auto routine has changed and update the active auto routine.
* It will check if the selected auto routine has changed and update the active AutoRoutine.
*
* <p>The AutoRoutine can only be updated when the robot is disabled. If the chooser in your
* dashboard says {@code BAD} the {@link AutoChooser} has not responded to the selection yet and
* you need to disable the robot to update it.
*/
public void update() {
if (DriverStation.isDisabled() || IterativeRobotBase.isSimulation()) {
if (DriverStation.isDisabled()) {
String selectStr = selected.get();
if (selectStr.equals(lastAutoRoutineName)) return;
if (!autoRoutines.containsKey(selectStr)) {
Expand All @@ -90,14 +100,33 @@ public void update() {
}

/**
* Add an auto routine to the chooser.
* Add an AutoRoutine to the chooser.
*
* <p>The options of the chooser are actually of type {@link AutoRoutineGenerator}. This is a
* function that takes an {@link AutoFactory} and returns a {@link AutoRoutine}. These functions
* can be static, a lambda or belong to a local variable.
*
* <p>This is done to load AutoRoutines when and only when they are selected, in order to save
* memory and file loading time for unused AutoRoutines.
*
* <p>An auto routine is a function that takes an AutoFactory and returns a AutoRoutine. These
* functions can be static, a lambda or belong to a local variable.
* <p>One way to keep this clean is to make an `Autos` class that all of your subsystems/resources
* are <a href="https://en.wikipedia.org/wiki/Dependency_injection">dependency injected</a> into.
* Then create methods inside that class that take an {@link AutoFactory} and return an {@link
* AutoRoutine}.
*
* <p>A good paradigm is making an `AutoRoutines` class that has a reference to all your
* subsystems and has helper methods for auto commands inside it. Then you crate methods inside
* that class that take an `AutoFactory` and return a `Command`.
* <h3>Example:</h3>
*
* <pre><code>
* AutoChooser chooser;
* Autos autos = new Autos(swerve, shooter, intake, feeder);
* Robot() {
* chooser = new AutoChooser(Choreo.createAutoFactory(...), "/Choosers");
* chooser.addAutoRoutine("4 Piece right", autos::fourPieceRight);
* chooser.addAutoRoutine("4 Piece Left", autos::fourPieceLeft);
* chooser.addAutoRoutine("3 Piece Close", autos::threePieceClose);
* chooser.addAutoRoutine("Just Shoot", factory -> factory.commandAsAutoRoutine(shooter.shoot()));
* }
* </code></pre>
*
* @param name The name of the auto routine.
* @param generator The function that generates the auto routine.
Expand All @@ -108,9 +137,40 @@ public void addAutoRoutine(String name, AutoRoutineGenerator generator) {
}

/**
* Get the currently selected auto routine.
* Get the currently selected {@link AutoRoutine}.
*
* <h3>Recommended Usage</h3>
*
* Scheduling it as a command.
*
* <pre><code>
* AutoChooser chooser = ...;
*
* public void autonomousInit() {
* CommandScheduler.getInstance().schedule(chooser.getSelectedAutoRoutine().cmd());
* }
* </code></pre>
*
* Polling it yourself.
*
* <pre><code>
* AutoChooser chooser = ...;
* AutoRoutine routine = chooser.getSelectedAutoRoutine();
*
* public void autonomousInit() {
* routine = chooser.getSelectedAutoRoutine();
* }
*
* public void autonomousPeriodic() {
* routine.poll();
* }
*
* public void autonomousExit() {
* routine.reset();
* }
* </code></pre>
*
* @return The currently selected auto routine.
* @return The currently selected {@link AutoRoutine}.
*/
public AutoRoutine getSelectedAutoRoutine() {
return lastAutoRoutine;
Expand Down
64 changes: 15 additions & 49 deletions choreolib/src/main/java/choreo/auto/AutoFactory.java
Original file line number Diff line number Diff line change
Expand Up @@ -24,43 +24,10 @@
import java.util.function.Supplier;

/**
* A factory used to create autonomous routines.
* A factory used to create {@link AutoRoutine}s and {@link AutoTrajectory}s.
*
* <p>Here is an example of how to use this class to create an auto routine:
*
* <h2>Example using <code>Trigger</code>s</h2>
*
* <pre><code>
* public AutoRoutine shootThenMove(AutoFactory factory) {
* // Create a new auto routine to return
* var routine = factory.newRoutine();
*
* // Create a trajectory that moves the robot 2 meters
* AutoTrajectory trajectory = factory.trajectory("move2meters", routine);
*
* // Will automatically run the shoot command when the auto routine is first polled
* routine.enabled().onTrue(shooter.shoot());
*
* // Gets a trigger from the shooter to if the shooter has a note, and will run the trajectory
* // command when the shooter does not have a note
* routine.enabled().and(shooter.hasNote()).onFalse(trajectory.cmd());
*
* return routine;
* }
* </code></pre>
*
* <h2>Example using <code>CommandGroup</code>s</h2>
*
* <pre><code>
* public Command shootThenMove(AutoFactory factory) {
* // Create a trajectory that moves the robot 2 meters
* Command trajectory = factory.trajectoryCommand("move2meters");
*
* return shooter.shoot()
* .andThen(trajectory)
* .withName("ShootThenMove");
* }
* </code></pre>
* @see <a href="https://sleipnirgroup.github.io/Choreo/choreolib/auto-routines">Auto Routine
* Docs</a>
*/
public class AutoFactory {
static final AutoRoutine VOID_ROUTINE =
Expand Down Expand Up @@ -166,7 +133,6 @@ public <SampleType extends TrajectorySample<SampleType>> AutoFactory(
*
* @param name The name of the {@link AutoRoutine}.
* @return A new {@link AutoRoutine}.
* @see AutoRoutine
* @see #voidRoutine
*/
public AutoRoutine newRoutine(String name) {
Expand All @@ -190,11 +156,11 @@ public AutoRoutine voidRoutine() {
}

/**
* Creates a new auto trajectory to be used in an auto routine.
* Creates a new {@link AutoTrajectory} to be used in an auto routine.
*
* @param trajectoryName The name of the trajectory to use.
* @param routine The {@link AutoRoutine} to register this trajectory under.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
public AutoTrajectory trajectory(String trajectoryName, AutoRoutine routine) {
Optional<? extends Trajectory<?>> optTrajectory =
Expand All @@ -210,12 +176,12 @@ public AutoTrajectory trajectory(String trajectoryName, AutoRoutine routine) {
}

/**
* Creates a new auto trajectory to be used in an auto routine.
* Creates a new {@link AutoTrajectory} to be used in an auto routine.
*
* @param trajectoryName The name of the trajectory to use.
* @param splitIndex The index of the split trajectory to use.
* @param routine The {@link AutoRoutine} to register this trajectory under.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
public AutoTrajectory trajectory(
String trajectoryName, final int splitIndex, AutoRoutine routine) {
Expand All @@ -232,12 +198,12 @@ public AutoTrajectory trajectory(
}

/**
* Creates a new auto trajectory to be used in an auto routine.
* Creates a new {@link AutoTrajectory} to be used in an auto routine.
*
* @param <SampleType> The type of the trajectory samples.
* @param trajectory The trajectory to use.
* @param routine The {@link AutoRoutine} to register this trajectory under.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
@SuppressWarnings("unchecked")
public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajectory(
Expand All @@ -261,7 +227,7 @@ public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajecto
}

/**
* Creates a new auto trajectory command to be used in an auto routine.
* Creates a new {@link AutoTrajectory} command to be used in an auto routine.
*
* <p><b>Important </b>
*
Expand All @@ -272,14 +238,14 @@ public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajecto
* AutoBindings} passed into the factory constructor.
*
* @param trajectoryName The name of the trajectory to use.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
public Command trajectoryCommand(String trajectoryName) {
return trajectory(trajectoryName, VOID_ROUTINE).cmd();
}

/**
* Creates a new auto trajectory command to be used in an auto routine.
* Creates a new {@link AutoTrajectory} command to be used in an auto routine.
*
* <p><b>Important </b>
*
Expand All @@ -291,14 +257,14 @@ public Command trajectoryCommand(String trajectoryName) {
*
* @param trajectoryName The name of the trajectory to use.
* @param splitIndex The index of the split trajectory to use.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
public Command trajectoryCommand(String trajectoryName, final int splitIndex) {
return trajectory(trajectoryName, splitIndex, VOID_ROUTINE).cmd();
}

/**
* Creates a new auto trajectory command to be used in an auto routine.
* Creates a new {@link AutoTrajectory} command to be used in an auto routine.
*
* <p><b>Important </b>
*
Expand All @@ -310,7 +276,7 @@ public Command trajectoryCommand(String trajectoryName, final int splitIndex) {
*
* @param <SampleType> The type of the trajectory samples.
* @param trajectory The trajectory to use.
* @return A new auto trajectory.
* @return A new {@link AutoTrajectory}.
*/
public <SampleType extends TrajectorySample<SampleType>> Command trajectoryCommand(
Trajectory<SampleType> trajectory) {
Expand Down
Loading

0 comments on commit b849eec

Please sign in to comment.