Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Doc Expansion #890

Merged
merged 45 commits into from
Nov 22, 2024
Merged
Show file tree
Hide file tree
Changes from 16 commits
Commits
Show all changes
45 commits
Select commit Hold shift + click to select a range
3695f5b
Fixed `done` trigger method
oh-yes-0-fps Oct 19, 2024
c3ee254
fixed java docs
oh-yes-0-fps Oct 19, 2024
1e1dfbb
fixed formatting
oh-yes-0-fps Oct 20, 2024
a7313c1
ran fmt fr this time
oh-yes-0-fps Oct 20, 2024
738333f
tmp commit
oh-yes-0-fps Oct 21, 2024
df2eb39
oopsie
oh-yes-0-fps Oct 21, 2024
eb3f6d4
ran fmt
oh-yes-0-fps Oct 21, 2024
adcab05
reverted `done` logic change to make this pr just `AutoLoop` -> `Auto…
oh-yes-0-fps Oct 21, 2024
7078349
Revert "reverted `done` logic change to make this pr just `AutoLoop` …
oh-yes-0-fps Oct 21, 2024
260cf63
Merge branch 'main' into isdone-fr
oh-yes-0-fps Oct 25, 2024
54fd151
Merge branch 'main' into doc-expandsio
oh-yes-0-fps Oct 25, 2024
bcc0a4b
Merge branch 'isdone-fr' into doc-expandsio
oh-yes-0-fps Oct 25, 2024
55bac0f
Fixed ascii symbol error in docs
oh-yes-0-fps Oct 25, 2024
f4fbea8
fixed external links in docs
oh-yes-0-fps Oct 25, 2024
284a773
fixed empty paragraph in java doc
oh-yes-0-fps Oct 25, 2024
c5cb66f
bleh
oh-yes-0-fps Oct 25, 2024
bb8d919
[choreolib] Cleaned up `AutoTrajectory` and `Trajectory` slightly
oh-yes-0-fps Oct 31, 2024
f2e32b0
rn fmt
oh-yes-0-fps Oct 31, 2024
453a0c8
fixe javadoc
oh-yes-0-fps Oct 31, 2024
214776b
oopsie
oh-yes-0-fps Oct 31, 2024
9395c0f
updated docs
oh-yes-0-fps Oct 31, 2024
1684355
fmtmaybe
oh-yes-0-fps Nov 7, 2024
43c8367
Merge branch 'main' into doc-expandsio
oh-yes-0-fps Nov 7, 2024
c095a7c
Update docs/choreolib/auto-routines.md
oh-yes-0-fps Nov 7, 2024
3fbb9d0
Update docs/choreolib/auto-routines.md
oh-yes-0-fps Nov 12, 2024
89e6db2
Update docs/choreolib/auto-routines.md
shueja Nov 13, 2024
24ab4c1
Update docs/choreolib/auto-routines.md
shueja Nov 13, 2024
8cb2369
Fix AutoChooser docs
shueja Nov 13, 2024
b83308d
refactor to spread out information a little better
oh-yes-0-fps Nov 15, 2024
4c9e3ae
ran fmt
oh-yes-0-fps Nov 15, 2024
48ca5f7
fix wording
GrahamSH-LLK Nov 16, 2024
a63213f
add tabs to basic usage and more cleanup
GrahamSH-LLK Nov 16, 2024
9c1a9ad
clean up auto routines
GrahamSH-LLK Nov 16, 2024
772106a
literally just remove a newline
GrahamSH-LLK Nov 16, 2024
5bc971a
simplify learning path
GrahamSH-LLK Nov 16, 2024
e0a3e5e
Merge pull request #1 from GrahamSH-LLK/ohyes-doc-pr-fixups
oh-yes-0-fps Nov 17, 2024
87546cd
Merge branch 'main' into doc-expandsio
oh-yes-0-fps Nov 17, 2024
22ce841
ran fmt
oh-yes-0-fps Nov 17, 2024
c522409
Update docs/choreolib/basic-usage.md
oh-yes-0-fps Nov 17, 2024
73712b6
Update choreolib/src/main/java/choreo/auto/AutoChooser.java
oh-yes-0-fps Nov 17, 2024
f681388
Merge branch 'main' into doc-expandsio
calcmogul Nov 21, 2024
7fdb51d
Merge branch 'main' into doc-expandsio
calcmogul Nov 22, 2024
14320b2
Rename rController
calcmogul Nov 22, 2024
b266b55
Link to auto controller examples
calcmogul Nov 22, 2024
b6e6eb2
Move localizer into drivetrain subsystem
calcmogul Nov 22, 2024
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
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
86 changes: 71 additions & 15 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,16 @@ 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
oh-yes-0-fps marked this conversation as resolved.
Show resolved Hide resolved
* string will put this chooser at the root of the network tables.
* 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 = "";
oh-yes-0-fps marked this conversation as resolved.
Show resolved Hide resolved
String path = NetworkTable.normalizeKey(tableName, true) + "/AutoChooser";
NetworkTable table = NetworkTableInstance.getDefault().getTable(path);

Expand All @@ -73,9 +77,13 @@ public AutoChooser(AutoFactory factory, String tableName) {
*
* <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.
*
* <p>The auto routine 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 @@ -92,12 +100,29 @@ public void update() {
/**
* Add an auto routine to the chooser.
*
* <p>An auto routine is a function that takes an AutoFactory and returns a Command. These
* functions can be static, a lambda or belong to a local variable.
* <p>An auto routine is a function that takes an {@link AutoFactory} and returns a {@link
shueja marked this conversation as resolved.
Show resolved Hide resolved
* AutoRoutine}. These functions can be static, a lambda or belong to a local variable.
*
* <p>A good paradigm is making an `Autos` class that all of your subsystems/resources are
* <a href="https://en.wikipedia.org/wiki/Dependency_injection">dependency injected</a> into.
* Then you crate methods inside that class that take an {@link AutoFactory} and return a {@link
* AutoRoutine}. You can also have the `Autos` class extend an `AutoHelpers` class that has helper
* methods that don't clutter your routines.
*
* <h3>Example:</h3>
*
* <pre><code>
* AutoChooser chooser;
*
* <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`.
* Robot() {
* chooser = new AutoChooser(Choreo.createAutoFactory(...), "/Choosers");
* Autos autos = new Autos(swerve, shooter, intake, feeder);
* 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 +133,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>
shueja marked this conversation as resolved.
Show resolved Hide resolved
* 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
69 changes: 20 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>
shueja marked this conversation as resolved.
Show resolved Hide resolved
*/
public class AutoFactory {
static final AutoRoutine VOID_ROUTINE =
Expand All @@ -83,6 +50,11 @@ public void poll() {}
@Override
public void reset() {}

@Override
public boolean isMostRecentTrajectory(AutoTrajectory trajectory) {
return false;
}

@Override
public Trigger enabled() {
return new Trigger(loop, () -> false);
Expand Down Expand Up @@ -166,7 +138,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 +161,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 +181,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 +203,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 +232,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 +243,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 +262,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 +281,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
12 changes: 12 additions & 0 deletions choreolib/src/main/java/choreo/auto/AutoRoutine.java
Original file line number Diff line number Diff line change
Expand Up @@ -108,6 +108,18 @@ public void kill() {
isKilled = true;
}

/**
* Returns if the the given trajectory is the most recently run trajectory.
*
* <p>This will return true if the given trajectory is currently running aswell.
*
* @param trajectory The trajectory to check
* @return If the given trajectory is the most recently run trajectory
*/
public boolean isMostRecentTrajectory(AutoTrajectory trajectory) {
return recentTrajectory.equals(trajectory);
}

/**
* Creates a command that will poll this event loop and reset it when it is cancelled.
*
Expand Down
Loading
Loading