001// Copyright (c) Choreo contributors
002
003package choreo.auto;
004
005import static choreo.util.ChoreoAlert.allianceNotReady;
006import static edu.wpi.first.wpilibj.Alert.AlertType.kError;
007
008import choreo.Choreo.TrajectoryLogger;
009import choreo.auto.AutoFactory.AllianceContext;
010import choreo.auto.AutoFactory.AutoBindings;
011import choreo.trajectory.DifferentialSample;
012import choreo.trajectory.SwerveSample;
013import choreo.trajectory.Trajectory;
014import choreo.trajectory.TrajectorySample;
015import choreo.util.ChoreoAlert;
016import choreo.util.ChoreoAlert.MultiAlert;
017import choreo.util.ChoreoAllianceFlipUtil;
018import edu.wpi.first.math.geometry.Pose2d;
019import edu.wpi.first.math.geometry.Rotation2d;
020import edu.wpi.first.math.geometry.Translation2d;
021import edu.wpi.first.wpilibj.Timer;
022import edu.wpi.first.wpilibj2.command.Command;
023import edu.wpi.first.wpilibj2.command.Commands;
024import edu.wpi.first.wpilibj2.command.FunctionalCommand;
025import edu.wpi.first.wpilibj2.command.ScheduleCommand;
026import edu.wpi.first.wpilibj2.command.Subsystem;
027import edu.wpi.first.wpilibj2.command.button.Trigger;
028import java.util.Optional;
029import java.util.OptionalInt;
030import java.util.function.BooleanSupplier;
031import java.util.function.Consumer;
032import java.util.function.Supplier;
033
034/**
035 * A class that represents a trajectory that can be used in an autonomous routine and have triggers
036 * based off of it.
037 */
038public class AutoTrajectory {
039  // For any devs looking through this class wondering
040  // about all the type casting and `?` for generics it's intentional.
041  // My goal was to make the sample type minimally leak into user code
042  // so you don't have to retype the sample type everywhere in your auto
043  // code. This also makes the places with generics exposed to users few
044  // and far between. This helps with more novice users
045
046  private static final MultiAlert triggerTimeNegative =
047      ChoreoAlert.multiAlert(causes -> "Trigger time cannot be negative for " + causes, kError);
048  private static final MultiAlert triggerTimeAboveMax =
049      ChoreoAlert.multiAlert(
050          causes -> "Trigger time cannot be greater than total trajectory time for " + causes + ".",
051          kError);
052  private static final MultiAlert eventNotFound =
053      ChoreoAlert.multiAlert(causes -> "Event Markers " + causes + " not found.", kError);
054  private static final MultiAlert noSamples =
055      ChoreoAlert.multiAlert(causes -> "Trajectories " + causes + " have no samples.", kError);
056  private static final MultiAlert noInitialPose =
057      ChoreoAlert.multiAlert(
058          causes -> "Unable to get initial pose for trajectories " + causes + ".", kError);
059
060  private final String name;
061  private final Trajectory<? extends TrajectorySample<?>> trajectory;
062  private final TrajectoryLogger<? extends TrajectorySample<?>> trajectoryLogger;
063  private final Supplier<Pose2d> poseSupplier;
064  private final Consumer<Pose2d> resetOdometry;
065  private final Consumer<? extends TrajectorySample<?>> controller;
066  private final AllianceContext allianceCtx;
067  private final Timer activeTimer = new Timer();
068  private final Timer inactiveTimer = new Timer();
069  private final Subsystem driveSubsystem;
070  private final AutoRoutine routine;
071  private final AutoBindings bindings;
072
073  /**
074   * A way to create slightly less triggers for many actions. Not static as to not leak triggers
075   * made here into another static EventLoop.
076   */
077  private final Trigger offTrigger;
078
079  /** If this trajectory us currently running */
080  private boolean isActive = false;
081
082  /** If the trajectory ran to completion */
083  private boolean isCompleted = false;
084
085  /** Whether to suppress warnings for this trajectory. */
086  private boolean warnUser = true;
087
088  /**
089   * Constructs an AutoTrajectory.
090   *
091   * @param name The trajectory name.
092   * @param trajectory The trajectory samples.
093   * @param poseSupplier The pose supplier.
094   * @param controller The controller function.
095   * @param allianceCtx The alliance context.
096   * @param trajectoryLogger Optional trajectory logger.
097   * @param driveSubsystem Drive subsystem.
098   * @param routine Event loop.
099   * @param bindings {@link AutoFactory}
100   */
101  <SampleType extends TrajectorySample<SampleType>> AutoTrajectory(
102      String name,
103      Trajectory<SampleType> trajectory,
104      Supplier<Pose2d> poseSupplier,
105      Consumer<Pose2d> resetOdometry,
106      Consumer<SampleType> controller,
107      AllianceContext allianceCtx,
108      TrajectoryLogger<SampleType> trajectoryLogger,
109      Subsystem driveSubsystem,
110      AutoRoutine routine,
111      AutoBindings bindings) {
112    this.name = name;
113    this.trajectory = trajectory;
114    this.poseSupplier = poseSupplier;
115    this.resetOdometry = resetOdometry;
116    this.controller = controller;
117    this.allianceCtx = allianceCtx;
118    this.driveSubsystem = driveSubsystem;
119    this.routine = routine;
120    this.offTrigger = new Trigger(routine.loop(), () -> false);
121    this.trajectoryLogger = trajectoryLogger;
122    this.bindings = bindings;
123
124    bindings.getBindings().forEach((key, value) -> active().and(atTime(key)).onTrue(value));
125  }
126
127  @SuppressWarnings("unchecked")
128  private void logTrajectory(boolean starting) {
129    var sampleOpt = trajectory.getInitialSample(false);
130    if (sampleOpt.isEmpty()) {
131      return;
132    }
133    var sample = sampleOpt.get();
134    if (sample instanceof SwerveSample) {
135      TrajectoryLogger<SwerveSample> swerveLogger =
136          (TrajectoryLogger<SwerveSample>) trajectoryLogger;
137      Trajectory<SwerveSample> swerveTrajectory = (Trajectory<SwerveSample>) trajectory;
138      swerveLogger.accept(swerveTrajectory, starting);
139    } else if (sample instanceof DifferentialSample) {
140      TrajectoryLogger<DifferentialSample> differentialLogger =
141          (TrajectoryLogger<DifferentialSample>) trajectoryLogger;
142      Trajectory<DifferentialSample> differentialTrajectory =
143          (Trajectory<DifferentialSample>) trajectory;
144      differentialLogger.accept(differentialTrajectory, starting);
145    }
146    ;
147  }
148
149  private void cmdInitialize() {
150    activeTimer.start();
151    inactiveTimer.stop();
152    inactiveTimer.reset();
153    isActive = true;
154    isCompleted = false;
155    logTrajectory(true);
156    routine.updateIdle(false);
157  }
158
159  @SuppressWarnings("unchecked")
160  private void cmdExecute() {
161    if (!allianceCtx.allianceKnownOrIgnored()) {
162      allianceNotReady.set(true);
163      return;
164    }
165    var sampleOpt = trajectory.sampleAt(activeTimer.get(), allianceCtx.doFlip());
166    if (sampleOpt.isEmpty()) {
167      return;
168    }
169    var sample = sampleOpt.get();
170    if (sample instanceof SwerveSample swerveSample) {
171      var swerveController = (Consumer<SwerveSample>) this.controller;
172      swerveController.accept(swerveSample);
173    } else if (sample instanceof DifferentialSample differentialSample) {
174      var differentialController = (Consumer<DifferentialSample>) this.controller;
175      differentialController.accept(differentialSample);
176    }
177  }
178
179  @SuppressWarnings("unchecked")
180  private void cmdEnd(boolean interrupted) {
181    activeTimer.stop();
182    activeTimer.reset();
183    inactiveTimer.start();
184    isActive = false;
185    isCompleted = !interrupted;
186
187    if (!interrupted && allianceCtx.allianceKnownOrIgnored()) {
188      var sampleOpt = trajectory.getFinalSample(allianceCtx.doFlip());
189      if (sampleOpt.isPresent()) {
190        var sample = sampleOpt.get();
191        if (sample instanceof SwerveSample swerveSample) {
192          var swerveController = (Consumer<SwerveSample>) this.controller;
193          swerveController.accept(swerveSample);
194        } else if (sample instanceof DifferentialSample differentialSample) {
195          var differentialController = (Consumer<DifferentialSample>) this.controller;
196          differentialController.accept(differentialSample);
197        }
198      }
199    }
200
201    logTrajectory(false);
202    routine.updateIdle(true);
203  }
204
205  private boolean cmdIsFinished() {
206    return activeTimer.get() > trajectory.getTotalTime()
207        || !routine.active().getAsBoolean()
208        || !allianceCtx.allianceKnownOrIgnored();
209  }
210
211  /** Suppresses warnings for this trajectory. */
212  void suppressWarnings() {
213    warnUser = false;
214  }
215
216  /**
217   * Creates a command that allocates the drive subsystem and follows the trajectory using the
218   * factories control function
219   *
220   * @return The command that will follow the trajectory
221   */
222  public Command cmd() {
223    // if the trajectory is empty, return a command that will print an error
224    if (trajectory.samples().isEmpty() && warnUser) {
225      return driveSubsystem.runOnce(() -> noSamples.addCause(name)).withName("Trajectory_" + name);
226    }
227    return new FunctionalCommand(
228            this::cmdInitialize,
229            this::cmdExecute,
230            this::cmdEnd,
231            this::cmdIsFinished,
232            driveSubsystem)
233        .withName("Trajectory_" + name);
234  }
235
236  /**
237   * Creates a command that will schedule <b>another</b> command that will follow the trajectory.
238   *
239   * <p>This can be useful when putting {@link AutoTrajectory} commands in sequences that require
240   * subsystems also required by in AutoTrajectory-bound subsystems.
241   *
242   * @return The command that will schedule the trajectory following command.
243   */
244  public Command spawnCmd() {
245    return new ScheduleCommand(cmd()).withName("Trajectory_" + name + "_Spawner");
246  }
247
248  /**
249   * Creates a command that resets the robot's odometry to the start of this trajectory.
250   *
251   * @return A command that resets the robot's odometry.
252   */
253  public Command resetOdometry() {
254    return Commands.either(
255            Commands.runOnce(() -> resetOdometry.accept(getInitialPose().get()), driveSubsystem),
256            Commands.runOnce(
257                    () -> {
258                      if (warnUser) {
259                        noInitialPose.addCause(name);
260                      }
261                      routine.kill();
262                    })
263                .andThen(driveSubsystem.run(() -> {})),
264            () -> getInitialPose().isPresent())
265        .withName("Trajectory_ResetOdometry_" + name);
266  }
267
268  /**
269   * Will get the underlying {@link Trajectory} object.
270   *
271   * <p><b>WARNING:</b> This method is not type safe and should be used with caution. The sample
272   * type of the trajectory should be known before calling this method.
273   *
274   * @param <SampleType> The type of the trajectory samples.
275   * @return The underlying {@link Trajectory} object.
276   */
277  @SuppressWarnings("unchecked")
278  public <SampleType extends TrajectorySample<SampleType>>
279      Trajectory<SampleType> getRawTrajectory() {
280    return (Trajectory<SampleType>) trajectory;
281  }
282
283  /**
284   * Returns this auto trajectory, mirrored to the other alliance.
285   *
286   * @param <SampleType> The type of the trajectory samples. Due to Java limitations, you have to
287   *     specify the sample type again here even if it was already specified when creating the
288   *     AutoTrajectory.
289   * @return this auto trajectory, mirrored to the other alliance.
290   */
291  @SuppressWarnings("unchecked")
292  public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory mirrorX() {
293    return new AutoTrajectory(
294        name,
295        (Trajectory<SampleType>) trajectory.mirrorX(),
296        poseSupplier,
297        resetOdometry,
298        (Consumer<SampleType>) controller,
299        allianceCtx,
300        (TrajectoryLogger<SampleType>) trajectoryLogger,
301        driveSubsystem,
302        routine,
303        bindings);
304  }
305
306  /**
307   * Returns this auto trajectory, mirrored left-to-right from the driver's perspective.
308   *
309   * @param <SampleType> The type of the trajectory samples. Due to Java limitations, you have to
310   *     specify the sample type again here even if it was already specified when creating the
311   *     AutoTrajectory.
312   * @return this auto trajectory, mirrored left-to-right from the driver's perspective.
313   */
314  @SuppressWarnings("unchecked")
315  public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory mirrorY() {
316    return new AutoTrajectory(
317        name,
318        (Trajectory<SampleType>) trajectory.mirrorY(),
319        poseSupplier,
320        resetOdometry,
321        (Consumer<SampleType>) controller,
322        allianceCtx,
323        (TrajectoryLogger<SampleType>) trajectoryLogger,
324        driveSubsystem,
325        routine,
326        bindings);
327  }
328
329  /**
330   * Returns this auto trajectory, rotated 180 degrees around the field center.
331   *
332   * @param <SampleType> The type of the trajectory samples. Due to Java limitations, you have to
333   *     specify the sample type again here even if it was already specified when creating the
334   *     AutoTrajectory.
335   * @return this auto trajectory, rotated 180 degrees around the field center.
336   */
337  @SuppressWarnings("unchecked")
338  public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory rotateAround() {
339    return new AutoTrajectory(
340        name,
341        (Trajectory<SampleType>) trajectory.rotateAround(),
342        poseSupplier,
343        resetOdometry,
344        (Consumer<SampleType>) controller,
345        allianceCtx,
346        (TrajectoryLogger<SampleType>) trajectoryLogger,
347        driveSubsystem,
348        routine,
349        bindings);
350  }
351
352  /**
353   * Will get the starting pose of the trajectory.
354   *
355   * <p>This position is flipped if alliance flipping is enabled and the alliance supplier returns
356   * Red.
357   *
358   * <p>This method returns an empty Optional if the trajectory is empty. This method returns an
359   * empty Optional if alliance flipping is enabled and the alliance supplier returns an empty
360   * Optional.
361   *
362   * @return The starting pose
363   */
364  public Optional<Pose2d> getInitialPose() {
365    if (!allianceCtx.allianceKnownOrIgnored()) {
366      allianceNotReady.set(true);
367      return Optional.empty();
368    }
369    return trajectory.getInitialPose(allianceCtx.doFlip());
370  }
371
372  /**
373   * Will get the ending pose of the trajectory.
374   *
375   * <p>This position is flipped if alliance flipping is enabled and the alliance supplier returns
376   * Red.
377   *
378   * <p>This method returns an empty Optional if the trajectory is empty. This method returns an
379   * empty Optional if alliance flipping is enabled and the alliance supplier returns an empty
380   * Optional.
381   *
382   * @return The starting pose
383   */
384  public Optional<Pose2d> getFinalPose() {
385    if (!allianceCtx.allianceKnownOrIgnored()) {
386      allianceNotReady.set(true);
387      return Optional.empty();
388    }
389    return trajectory.getFinalPose(allianceCtx.doFlip());
390  }
391
392  /**
393   * Returns a trigger that is true while the trajectory is scheduled.
394   *
395   * @return A trigger that is true while the trajectory is scheduled.
396   */
397  public Trigger active() {
398    return new Trigger(routine.loop(), () -> this.isActive && routine.active().getAsBoolean());
399  }
400
401  /**
402   * Returns a trigger that is true while the command is not scheduled.
403   *
404   * <p>The same as calling <code>active().negate()</code>.
405   *
406   * @return A trigger that is true while the command is not scheduled.
407   */
408  public Trigger inactive() {
409    return active().negate();
410  }
411
412  private Trigger timeTrigger(double targetTime, Timer timer) {
413    // Make the trigger only be high for 1 cycle when the time has elapsed
414    return new Trigger(
415        routine.loop(),
416        new BooleanSupplier() {
417          double lastTimestamp = -1.0;
418          OptionalInt pollTarget = OptionalInt.empty();
419
420          public boolean getAsBoolean() {
421            if (!timer.isRunning()) {
422              lastTimestamp = -1.0;
423              pollTarget = OptionalInt.empty();
424              return false;
425            }
426            double nowTimestamp = timer.get();
427            try {
428              boolean timeAligns = lastTimestamp < targetTime && nowTimestamp >= targetTime;
429              if (pollTarget.isEmpty() && timeAligns) {
430                // if the time aligns for this cycle and it hasn't aligned previously this cycle
431                pollTarget = OptionalInt.of(routine.pollCount());
432                return true;
433              } else if (pollTarget.isPresent() && routine.pollCount() == pollTarget.getAsInt()) {
434                // if the time aligned previously this cycle
435                return true;
436              } else if (pollTarget.isPresent()) {
437                // if the time aligned last cycle
438                pollTarget = OptionalInt.empty();
439                return false;
440              }
441              return false;
442            } finally {
443              lastTimestamp = nowTimestamp;
444            }
445          }
446        });
447  }
448
449  private Trigger enterExitTrigger(Trigger enter, Trigger exit) {
450    return new Trigger(
451        routine.loop(),
452        new BooleanSupplier() {
453          boolean output = false;
454
455          @Override
456          public boolean getAsBoolean() {
457            if (enter.getAsBoolean()) {
458              output = true;
459            }
460            if (exit.getAsBoolean()) {
461              output = false;
462            }
463            return output;
464          }
465        });
466  }
467
468  /**
469   * Returns a trigger that rises to true a number of cycles after the trajectory ends and falls
470   * after one pulse.
471   *
472   * <p>This is different from inactive() in a few ways.
473   *
474   * <ul>
475   *   <li>This will never be true if the trajectory is interrupted
476   *   <li>This will never be true before the trajectory is run
477   *   <li>This will fall the next cycle after the trajectory ends
478   * </ul>
479   *
480   * <p>Why does the trigger need to fall?
481   *
482   * <pre><code>
483   * //Lets say we had this code segment
484   * Trigger hasGamepiece = ...;
485   * Trigger noGamepiece = hasGamepiece.negate();
486   *
487   * AutoTrajectory rushMidTraj = ...;
488   * AutoTrajectory goShootGamepiece = ...;
489   * AutoTrajectory pickupAnotherGamepiece = ...;
490   *
491   * routine.enabled().onTrue(rushMidTraj.cmd());
492   *
493   * rushMidTraj.doneDelayed(10).and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd());
494   * rushMidTraj.doneDelayed(10).and(hasGamepiece).onTrue(goShootGamepiece.cmd());
495   *
496   * // If done never falls when a new trajectory is scheduled
497   * // then these triggers leak into the next trajectory, causing the next note pickup
498   * // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
499   * </code></pre>
500   *
501   * @param seconds The seconds to delay the trigger from rising to true.
502   * @return A trigger that is true when the trajectory is finished.
503   */
504  public Trigger doneDelayed(double seconds) {
505    return timeTrigger(seconds, inactiveTimer).and(new Trigger(routine.loop(), () -> isCompleted));
506  }
507
508  /**
509   * Returns a trigger that rises to true when the trajectory ends and falls after one pulse.
510   *
511   * <p>This is different from inactive() in a few ways.
512   *
513   * <ul>
514   *   <li>This will never be true if the trajectory is interrupted
515   *   <li>This will never be true before the trajectory is run
516   *   <li>This will fall the next cycle after the trajectory ends
517   * </ul>
518   *
519   * <p>Why does the trigger need to fall?
520   *
521   * <pre><code>
522   * //Lets say we had this code segment
523   * Trigger hasGamepiece = ...;
524   * Trigger noGamepiece = hasGamepiece.negate();
525   *
526   * AutoTrajectory rushMidTraj = ...;
527   * AutoTrajectory goShootGamepiece = ...;
528   * AutoTrajectory pickupAnotherGamepiece = ...;
529   *
530   * routine.enabled().onTrue(rushMidTraj.cmd());
531   *
532   * rushMidTraj.done().and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd());
533   * rushMidTraj.done().and(hasGamepiece).onTrue(goShootGamepiece.cmd());
534   *
535   * // If done never falls when a new trajectory is scheduled
536   * // then these triggers leak into the next trajectory, causing the next note pickup
537   * // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
538   * </code></pre>
539   *
540   * @return A trigger that is true when the trajectory is finished.
541   */
542  public Trigger done() {
543    return doneDelayed(0);
544  }
545
546  /**
547   * Returns a trigger that stays true for a number of cycles after the trajectory ends.
548   *
549   * @param seconds Seconds to stay true after the trajectory ends.
550   * @return A trigger that stays true for a number of cycles after the trajectory ends.
551   */
552  public Trigger doneFor(double seconds) {
553    return enterExitTrigger(doneDelayed(0), doneDelayed(seconds));
554  }
555
556  /**
557   * Returns a trigger that is true when the trajectory was the last one active and is done.
558   *
559   * @return A trigger that is true when the trajectory was the last one active and is done.
560   */
561  public Trigger recentlyDone() {
562    return enterExitTrigger(doneDelayed(0), routine.idle().negate());
563  }
564
565  /**
566   * A shorthand for `.done().onTrue(otherTrajectory.cmd())`
567   *
568   * @param otherTrajectory The other trajectory to run when this one is done.
569   */
570  public void chain(AutoTrajectory otherTrajectory) {
571    done().onTrue(otherTrajectory.cmd());
572  }
573
574  /**
575   * Returns a trigger that will go true for 1 cycle when the desired time has elapsed
576   *
577   * @param timeSinceStart The time since the command started in seconds.
578   * @return A trigger that is true when timeSinceStart has elapsed.
579   */
580  public Trigger atTime(double timeSinceStart) {
581    // The timer should never be negative so report this as a warning
582    if (timeSinceStart < 0) {
583      if (warnUser) {
584        triggerTimeNegative.addCause(name);
585      }
586      return offTrigger;
587    }
588
589    // The timer should never exceed the total trajectory time so report this as a warning
590    if (timeSinceStart > trajectory.getTotalTime()) {
591      if (warnUser) {
592        triggerTimeAboveMax.addCause(name);
593      }
594      return offTrigger;
595    }
596
597    return timeTrigger(timeSinceStart, activeTimer);
598  }
599
600  /**
601   * Returns a trigger that will go true for 1 cycle when the desired before the end of the
602   * trajectory time.
603   *
604   * @param timeBeforeEnd The time before the end of the trajectory.
605   * @return A trigger that is true when timeBeforeEnd has elapsed.
606   */
607  public Trigger atTimeBeforeEnd(double timeBeforeEnd) {
608    return atTime(trajectory.getTotalTime() - timeBeforeEnd);
609  }
610
611  /**
612   * Returns a trigger that is true when the event with the given name has been reached based on
613   * time.
614   *
615   * <p>A warning will be printed to the DriverStation if the event is not found and the trigger
616   * will always be false.
617   *
618   * @param eventName The name of the event.
619   * @return A trigger that is true when the event with the given name has been reached based on
620   *     time.
621   * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the
622   *     GUI</a>
623   */
624  public Trigger atTime(String eventName) {
625    boolean foundEvent = false;
626    Trigger trig = offTrigger;
627
628    for (var event : trajectory.getEvents(eventName)) {
629      // This could create a lot of objects, could be done a more efficient way
630      // with having it all be 1 trigger that just has a list of times and checks each one each
631      // cycle
632      // or something like that. If choreo starts proposing memory issues we can look into this.
633      trig = trig.or(atTime(event.timestamp));
634      foundEvent = true;
635    }
636
637    // The user probably expects an event to exist if they're trying to do something at that event,
638    // report the missing event.
639    if (!foundEvent && warnUser) {
640      eventNotFound.addCause(name);
641    }
642
643    return trig;
644  }
645
646  private boolean withinTolerance(Rotation2d lhs, Rotation2d rhs, double toleranceRadians) {
647    if (Math.abs(toleranceRadians) > Math.PI) {
648      return true;
649    }
650    double dot = lhs.getCos() * rhs.getCos() + lhs.getSin() * rhs.getSin();
651    // cos(θ) >= cos(tolerance) means |θ| <= tolerance, for tolerance in [-pi, pi], as pre-checked
652    // above.
653    return dot > Math.cos(toleranceRadians);
654  }
655
656  /**
657   * Returns a trigger that is true when the robot is within toleranceMeters of the given pose.
658   *
659   * <p>The pose is flipped if alliance flipping is enabled and the alliance supplier returns Red.
660   *
661   * <p>While alliance flipping is enabled and the alliance supplier returns empty, the trigger will
662   * return false.
663   *
664   * @param pose The pose to check against, unflipped.
665   * @param toleranceMeters The tolerance in meters.
666   * @param toleranceRadians The heading tolerance in radians.
667   * @return A trigger that is true when the robot is within toleranceMeters of the given pose.
668   */
669  public Trigger atPose(Pose2d pose, double toleranceMeters, double toleranceRadians) {
670    Pose2d flippedPose = ChoreoAllianceFlipUtil.flip(pose);
671    return new Trigger(
672            routine.loop(),
673            () -> {
674              if (allianceCtx.allianceKnownOrIgnored()) {
675                final Pose2d currentPose = poseSupplier.get();
676                if (allianceCtx.doFlip()) {
677                  boolean transValid =
678                      currentPose.getTranslation().getDistance(flippedPose.getTranslation())
679                          < toleranceMeters;
680                  boolean rotValid =
681                      withinTolerance(
682                          currentPose.getRotation(), flippedPose.getRotation(), toleranceRadians);
683                  return transValid && rotValid;
684                } else {
685                  boolean transValid =
686                      currentPose.getTranslation().getDistance(pose.getTranslation())
687                          < toleranceMeters;
688                  boolean rotValid =
689                      withinTolerance(
690                          currentPose.getRotation(), pose.getRotation(), toleranceRadians);
691                  return transValid && rotValid;
692                }
693              } else {
694                allianceNotReady.set(true);
695                return false;
696              }
697            })
698        .and(active());
699  }
700
701  /**
702   * Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of
703   * the given event's pose.
704   *
705   * <p>A warning will be printed to the DriverStation if the event is not found and the trigger
706   * will always be false.
707   *
708   * @param eventName The name of the event.
709   * @param toleranceMeters The tolerance in meters.
710   * @param toleranceRadians The heading tolerance in radians.
711   * @return A trigger that is true when the robot is within toleranceMeters of the given events
712   *     pose.
713   * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the
714   *     GUI</a>
715   */
716  public Trigger atPose(String eventName, double toleranceMeters, double toleranceRadians) {
717    boolean foundEvent = false;
718    Trigger trig = offTrigger;
719
720    for (var event : trajectory.getEvents(eventName)) {
721      // This could create a lot of objects, could be done a more efficient way
722      // with having it all be 1 trigger that just has a list of possess and checks each one each
723      // cycle or something like that.
724      // If choreo starts showing memory issues we can look into this.
725      Optional<Pose2d> poseOpt =
726          trajectory
727              // don't mirror here because the poses are mirrored themselves
728              // this also lets atPose be called before the alliance is ready
729              .sampleAt(event.timestamp, false)
730              .map(TrajectorySample::getPose);
731      if (poseOpt.isPresent()) {
732        trig = trig.or(atPose(poseOpt.get(), toleranceMeters, toleranceRadians));
733        foundEvent = true;
734      }
735    }
736
737    // The user probably expects an event to exist if they're trying to do something at that event,
738    // report the missing event.
739    if (!foundEvent && warnUser) {
740      eventNotFound.addCause(name);
741    }
742
743    return trig;
744  }
745
746  /**
747   * Returns a trigger that is true when the robot is within toleranceMeters of the given
748   * translation.
749   *
750   * <p>The translation is flipped if alliance flipping is enabled and the alliance supplier returns
751   * Red.
752   *
753   * <p>While alliance flipping is enabled and the alliance supplier returns empty, the trigger will
754   * return false.
755   *
756   * @param translation The translation to check against, unflipped.
757   * @param toleranceMeters The tolerance in meters.
758   * @return A trigger that is true when the robot is within toleranceMeters of the given
759   *     translation.
760   */
761  public Trigger atTranslation(Translation2d translation, double toleranceMeters) {
762    Translation2d flippedTranslation = ChoreoAllianceFlipUtil.flip(translation);
763    return new Trigger(
764            routine.loop(),
765            () -> {
766              if (allianceCtx.allianceKnownOrIgnored()) {
767                final Translation2d currentTrans = poseSupplier.get().getTranslation();
768                if (allianceCtx.doFlip()) {
769                  return currentTrans.getDistance(flippedTranslation) < toleranceMeters;
770                } else {
771                  return currentTrans.getDistance(translation) < toleranceMeters;
772                }
773              } else {
774                allianceNotReady.set(true);
775                return false;
776              }
777            })
778        .and(active());
779  }
780
781  /**
782   * Returns a trigger that is true when the robot is within toleranceMeters and toleranceRadians of
783   * the given event's translation.
784   *
785   * <p>A warning will be printed to the DriverStation if the event is not found and the trigger
786   * will always be false.
787   *
788   * @param eventName The name of the event.
789   * @param toleranceMeters The tolerance in meters.
790   * @return A trigger that is true when the robot is within toleranceMeters of the given events
791   *     translation.
792   * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the
793   *     GUI</a>
794   */
795  public Trigger atTranslation(String eventName, double toleranceMeters) {
796    boolean foundEvent = false;
797    Trigger trig = offTrigger;
798
799    for (var event : trajectory.getEvents(eventName)) {
800      // This could create a lot of objects, could be done a more efficient way
801      // with having it all be 1 trigger that just has a list of poses and checks each one each
802      // cycle or something like that.
803      // If choreo starts showing memory issues we can look into this.
804      Optional<Translation2d> translationOpt =
805          trajectory
806              // don't mirror here because the translations are mirrored themselves
807              // this also lets atTranslation be called before the alliance is ready
808              .sampleAt(event.timestamp, false)
809              .map(TrajectorySample::getPose)
810              .map(Pose2d::getTranslation);
811      if (translationOpt.isPresent()) {
812        trig = trig.or(atTranslation(translationOpt.get(), toleranceMeters));
813        foundEvent = true;
814      }
815    }
816
817    // The user probably expects an event to exist if they're trying to do something at that event,
818    // report the missing event.
819    if (!foundEvent && warnUser) {
820      eventNotFound.addCause(name);
821    }
822
823    return trig;
824  }
825
826  /**
827   * Returns an array of all the timestamps of the events with the given name.
828   *
829   * @param eventName The name of the event.
830   * @return An array of all the timestamps of the events with the given name.
831   * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the
832   *     GUI</a>
833   */
834  public double[] collectEventTimes(String eventName) {
835    double[] times =
836        trajectory.getEvents(eventName).stream()
837            .filter(e -> e.timestamp >= 0 && e.timestamp <= trajectory.getTotalTime())
838            .mapToDouble(e -> e.timestamp)
839            .toArray();
840
841    if (times.length == 0 && warnUser) {
842      eventNotFound.addCause("collectEvents(" + eventName + ")");
843    }
844
845    return times;
846  }
847
848  /**
849   * Returns an array of all the poses of the events with the given name.
850   *
851   * <p>The returned poses are always unflipped. If you use them in a trigger like `atPose` or
852   * `atTranslation`, the library will automatically flip them if necessary. If you intend using
853   * them in a different context, you can use {@link ChoreoAllianceFlipUtil#flip} to flip them.
854   *
855   * @param eventName The name of the event.
856   * @return An array of all the poses of the events with the given name.
857   * @see <a href="https://choreo.autos/usage/editing-paths/#event-markers">Event Markers in the
858   *     GUI</a>
859   */
860  public Pose2d[] collectEventPoses(String eventName) {
861    double[] times = collectEventTimes(eventName);
862    Pose2d[] poses = new Pose2d[times.length];
863    for (int i = 0; i < times.length; i++) {
864      Pose2d pose =
865          trajectory
866              .sampleAt(times[i], false)
867              .map(TrajectorySample::getPose)
868              .get(); // the event times are guaranteed to be valid
869      poses[i] = pose;
870    }
871    return poses;
872  }
873
874  @Override
875  public boolean equals(Object obj) {
876    return obj instanceof AutoTrajectory traj && name.equals(traj.name);
877  }
878}