Skip to content

Commit b3c199f

Browse files
committed
Correct trajectoryCmd docs and fix bug leftover from SleipnirGroup#1110
1 parent 8d6dbfd commit b3c199f

File tree

1 file changed

+19
-13
lines changed

1 file changed

+19
-13
lines changed

choreolib/src/main/java/choreo/auto/AutoFactory.java

Lines changed: 19 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -267,14 +267,15 @@ <ST extends TrajectorySample<ST>> AutoTrajectory trajectory(
267267
*
268268
* <p><b>Important </b>
269269
*
270+
* <p>This method sets up an {@link AutoRoutine} and {@link AutoTrajectory} internally, and ends
271+
* when the trajectory completes. Commands bound with {@link #bind} will still run.
272+
*
270273
* <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
271274
* routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
272-
* benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
273-
* does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
274-
* the factory constructor.
275+
* benefits of the {@link #trajectory} method and its {@link Trigger} API.
275276
*
276277
* @param trajectoryName The name of the trajectory to use.
277-
* @return A new {@link AutoTrajectory}.
278+
* @return A new {@link Command}.
278279
*/
279280
public Command trajectoryCmd(String trajectoryName) {
280281
AutoRoutine routine = newRoutine("Routine");
@@ -288,15 +289,16 @@ public Command trajectoryCmd(String trajectoryName) {
288289
*
289290
* <p><b>Important </b>
290291
*
292+
* <p>This method sets up an {@link AutoRoutine} and {@link AutoTrajectory} internally, and ends
293+
* when the trajectory completes. Commands bound with {@link #bind} will still run.
294+
*
291295
* <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
292296
* routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
293-
* benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
294-
* does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
295-
* the factory constructor.
297+
* benefits of the {@link #trajectory} method and its {@link Trigger} API.
296298
*
297299
* @param trajectoryName The name of the trajectory to use.
298300
* @param splitIndex The index of the split trajectory to use.
299-
* @return A new {@link AutoTrajectory}.
301+
* @return A new {@link Command}.
300302
*/
301303
public Command trajectoryCmd(String trajectoryName, final int splitIndex) {
302304
AutoRoutine routine = newRoutine("Routine");
@@ -310,19 +312,23 @@ public Command trajectoryCmd(String trajectoryName, final int splitIndex) {
310312
*
311313
* <p><b>Important </b>
312314
*
315+
* <p>This method sets up an {@link AutoRoutine} and {@link AutoTrajectory} internally, and ends
316+
* when the trajectory completes. Commands bound with {@link #bind} will still run.
317+
*
313318
* <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
314319
* routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
315-
* benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
316-
* does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
317-
* the factory constructor.
320+
* benefits of the {@link #trajectory} method and its {@link Trigger} API.
318321
*
319322
* @param <ST> {@link choreo.trajectory.DifferentialSample} or {@link
320323
* choreo.trajectory.SwerveSample}
321324
* @param trajectory The trajectory to use.
322-
* @return A new {@link AutoTrajectory}.
325+
* @return A new {@link Command}.
323326
*/
324327
public <ST extends TrajectorySample<ST>> Command trajectoryCmd(Trajectory<ST> trajectory) {
325-
return trajectory(trajectory, voidRoutine).cmd();
328+
AutoRoutine routine = newRoutine("Routine");
329+
AutoTrajectory autoTrajectory = routine.trajectory(trajectory);
330+
routine.active().onTrue(autoTrajectory.cmd());
331+
return routine.cmd().until(autoTrajectory.done());
326332
}
327333

328334
/**

0 commit comments

Comments
 (0)