001// Copyright (c) Choreo contributors
002
003package choreo.auto;
004
005import static edu.wpi.first.wpilibj.Alert.AlertType.kWarning;
006
007import choreo.auto.AutoFactory.AllianceContext;
008import choreo.trajectory.Trajectory;
009import choreo.trajectory.TrajectorySample;
010import choreo.util.ChoreoAlert;
011import edu.wpi.first.wpilibj.DriverStation;
012import edu.wpi.first.wpilibj.Timer;
013import edu.wpi.first.wpilibj.event.EventLoop;
014import edu.wpi.first.wpilibj2.command.Command;
015import edu.wpi.first.wpilibj2.command.CommandScheduler;
016import edu.wpi.first.wpilibj2.command.Commands;
017import edu.wpi.first.wpilibj2.command.button.Trigger;
018import java.util.function.BooleanSupplier;
019
020/**
021 * An object that represents an autonomous routine.
022 *
023 * <p>This object is used to handle autonomous trigger logic and schedule commands for a single
024 * autonomous routine. This object should **not** be shared across multiple autonomous routines.
025 *
026 * @see AutoFactory#newRoutine Creating a routine from a AutoFactory
027 */
028public class AutoRoutine {
029  /**
030   * The factory that created this loop. This is used to create commands that are associated with
031   * this loop.
032   */
033  private final AutoFactory factory;
034
035  /** The underlying {@link EventLoop} that triggers are bound to and polled */
036  private final EventLoop loop = new EventLoop();
037
038  /** The name of the auto routine this loop is associated with */
039  private final String name;
040
041  /** The alliance helper that is used to determine flipping logic */
042  final AllianceContext allianceCtx;
043
044  /** A boolean utilized in {@link #active()} to resolve trueness */
045  private boolean isActive = false;
046
047  private final Trigger isActiveTrigger =
048      new Trigger(loop, () -> isActive && DriverStation.isEnabled());
049
050  /** A boolean indicating if a trajectory is running on the routine right now */
051  private boolean isIdle = true;
052
053  private final Trigger isIdleTrigger = new Trigger(loop, () -> isIdle);
054
055  /** A boolean that is true when the loop is killed */
056  boolean isKilled = false;
057
058  /** The amount of times the routine has been polled */
059  private int pollCount = 0;
060
061  /** The timestamp of the current cycle */
062  private double cycleTimestamp = 0;
063
064  /**
065   * Creates a new loop with a specific name and a custom alliance supplier.
066   *
067   * @param factory The factory that created this loop
068   * @param name The name of the loop
069   * @param allianceHelper The alliance helper that is used to determine flipping logic
070   * @see AutoFactory#newRoutine Creating a loop from a AutoFactory
071   */
072  AutoRoutine(AutoFactory factory, String name, AllianceContext allianceHelper) {
073    this.factory = factory;
074    this.name = name;
075    this.allianceCtx = allianceHelper;
076  }
077
078  /**
079   * Returns a {@link Trigger} that is true while this autonomous routine is being polled.
080   *
081   * <p>Using a {@link Trigger#onFalse(Command)} will do nothing as when this is false the routine
082   * is not being polled anymore.
083   *
084   * @return A {@link Trigger} that is true while this autonomous routine is being polled.
085   */
086  public Trigger active() {
087    return isActiveTrigger;
088  }
089
090  /** Polls the routine. Should be called in the autonomous periodic method. */
091  public void poll() {
092    if (DriverStation.isDisabled() || !allianceCtx.allianceKnownOrIgnored() || isKilled) {
093      isActive = false;
094      return;
095    }
096    pollCount++;
097    cycleTimestamp = Timer.getFPGATimestamp();
098    loop.poll();
099    isActive = true;
100  }
101
102  /**
103   * Gets the event loop that this routine is using.
104   *
105   * @return The event loop that this routine is using.
106   */
107  public EventLoop loop() {
108    return loop;
109  }
110
111  /**
112   * Creates a {@link Trigger} that is bound to the routine's {@link EventLoop}.
113   *
114   * @param condition The condition represented by the trigger.
115   * @return A {@link Trigger} that mirrors the state of the provided {@code condition}
116   */
117  public Trigger observe(BooleanSupplier condition) {
118    return new Trigger(loop, condition);
119  }
120
121  int pollCount() {
122    return pollCount;
123  }
124
125  double cycleTimestamp() {
126    return cycleTimestamp;
127  }
128
129  /**
130   * Updates the idle state of the routine.
131   *
132   * @param isIdle The new idle state of the routine.
133   */
134  void updateIdle(boolean isIdle) {
135    this.isIdle = isIdle;
136  }
137
138  /**
139   * Resets the routine. This can either be called on auto init or auto end to reset the routine
140   * incase you run it again. If this is called on a routine that doesn't need to be reset it will
141   * do nothing.
142   */
143  public void reset() {
144    pollCount = 0;
145    cycleTimestamp = 0;
146    isActive = false;
147  }
148
149  /** Kills the loop and prevents it from running again. */
150  public void kill() {
151    CommandScheduler.getInstance().cancelAll();
152    if (isKilled) {
153      return;
154    }
155    reset();
156    ChoreoAlert.alert("Killed an auto loop", kWarning).set(true);
157    isKilled = true;
158  }
159
160  /**
161   * Creates a trigger that is true when the routine is idle.
162   *
163   * <p>Idle is defined as no trajectories made by the routine are running.
164   *
165   * @return A trigger that is true when the routine is idle.
166   */
167  public Trigger idle() {
168    return isIdleTrigger;
169  }
170
171  /**
172   * Creates a new {@link AutoTrajectory} to be used in an auto routine.
173   *
174   * @param trajectoryName The name of the trajectory to use.
175   * @return A new {@link AutoTrajectory}.
176   */
177  public AutoTrajectory trajectory(String trajectoryName) {
178    return factory.trajectory(trajectoryName, this, true);
179  }
180
181  /**
182   * Creates a new {@link AutoTrajectory} to be used in an auto routine.
183   *
184   * @param trajectoryName The name of the trajectory to use.
185   * @param splitIndex The index of the split trajectory to use.
186   * @return A new {@link AutoTrajectory}.
187   */
188  public AutoTrajectory trajectory(String trajectoryName, final int splitIndex) {
189    return factory.trajectory(trajectoryName, splitIndex, this, true);
190  }
191
192  /**
193   * Creates a new {@link AutoTrajectory} to be used in an auto routine.
194   *
195   * @param <SampleType> The type of the trajectory samples.
196   * @param trajectory The trajectory to use.
197   * @return A new {@link AutoTrajectory}.
198   */
199  public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajectory(
200      Trajectory<SampleType> trajectory) {
201    return factory.trajectory(trajectory, this, true);
202  }
203
204  /**
205   * Creates a trigger that produces a rising edge when any of the trajectories are finished.
206   *
207   * @param trajectory The first trajectory to watch.
208   * @param trajectories The other trajectories to watch
209   * @return a trigger that determines if any of the trajectories are finished
210   * @see #anyDone(int, AutoTrajectory, AutoTrajectory...) A version of this method that takes a
211   *     delay in cycles before the trigger is true.
212   */
213  public Trigger anyDone(AutoTrajectory trajectory, AutoTrajectory... trajectories) {
214    return anyDone(0, trajectory, trajectories);
215  }
216
217  /**
218   * Creates a trigger that produces a rising edge when any of the trajectories are finished.
219   *
220   * @param cyclesToDelay The number of cycles to delay.
221   * @param trajectory The first trajectory to watch.
222   * @param trajectories The other trajectories to watch
223   * @return a trigger that goes true for one cycle whenever any of the trajectories finishes,
224   *     delayed by the given number of cycles.
225   * @see AutoTrajectory#doneDelayed(int)
226   */
227  public Trigger anyDoneDelayed(
228      int cyclesToDelay, AutoTrajectory trajectory, AutoTrajectory... trajectories) {
229    var trigger = trajectory.doneDelayed(cyclesToDelay);
230    for (int i = 0; i < trajectories.length; i++) {
231      trigger = trigger.or(trajectories[i].doneDelayed(cyclesToDelay));
232    }
233    return trigger.and(this.active());
234  }
235
236  /**
237   * Creates a trigger that produces a rising edge when any of the trajectories are finished.
238   *
239   * @param cyclesToDelay The number of cycles to delay.
240   * @param trajectory The first trajectory to watch.
241   * @param trajectories The other trajectories to watch
242   * @return a trigger that determines if any of the trajectories are finished
243   * @see AutoTrajectory#doneDelayed(int)
244   * @see AutoRoutine#anyDoneDelayed
245   * @deprecated This method is deprecated and will be removed in 2025. Use {@link #anyDoneDelayed}
246   */
247  @Deprecated(forRemoval = true, since = "2025")
248  public Trigger anyDone(
249      int cyclesToDelay, AutoTrajectory trajectory, AutoTrajectory... trajectories) {
250    return anyDoneDelayed(cyclesToDelay, trajectory, trajectories);
251  }
252
253  /**
254   * Creates a trigger that returns true when any of the trajectories given are active.
255   *
256   * @param trajectory The first trajectory to watch.
257   * @param trajectories The other trajectories to watch
258   * @return a trigger that determines if any of the trajectories are active
259   */
260  public Trigger anyActive(AutoTrajectory trajectory, AutoTrajectory... trajectories) {
261    var trigger = trajectory.active();
262    for (int i = 0; i < trajectories.length; i++) {
263      trigger = trigger.or(trajectories[i].active());
264    }
265    return trigger.and(this.active());
266  }
267
268  /**
269   * Creates a trigger that returns true when any of the trajectories given are inactive.
270   *
271   * <p>This trigger will only return true if the routine is active.
272   *
273   * @param trajectory The first trajectory to watch.
274   * @param trajectories The other trajectories to watch
275   * @return a trigger that determines if any of the trajectories are inactive
276   */
277  public Trigger allInactive(AutoTrajectory trajectory, AutoTrajectory... trajectories) {
278    var trigger = trajectory.inactive();
279    for (int i = 0; i < trajectories.length; i++) {
280      trigger = trigger.and(trajectories[i].inactive());
281    }
282    return trigger.and(this.active());
283  }
284
285  /**
286   * Creates a command that will poll this event loop and reset it when it is cancelled.
287   *
288   * <p>The command will end instantly and kill the routine if the alliance supplier returns an
289   * empty optional when the command is scheduled.
290   *
291   * @return A command that will poll this event loop and reset it when it is cancelled.
292   * @see #cmd(BooleanSupplier) A version of this method that takes a condition to finish the loop.
293   */
294  public Command cmd() {
295    return cmd(() -> false);
296  }
297
298  /**
299   * Creates a command that will poll this event loop and reset it when it is finished or canceled.
300   *
301   * <p>The command will end instantly and kill the routine if the alliance supplier returns an
302   * empty optional when the command is scheduled.
303   *
304   * @param finishCondition A condition that will finish the loop when it is true.
305   * @return A command that will poll this event loop and reset it when it is finished or canceled.
306   * @see #cmd() A version of this method that doesn't take a condition and never finishes except if
307   *     the alliance supplier returns an empty optional when scheduled.
308   */
309  public Command cmd(BooleanSupplier finishCondition) {
310    return Commands.either(
311        Commands.run(this::poll)
312            .finallyDo(this::reset)
313            .until(() -> DriverStation.isDisabled() || finishCondition.getAsBoolean())
314            .withName(name),
315        Commands.runOnce(
316            () -> {
317              ChoreoAlert.alert("Alliance not known when starting routine", kWarning).set(true);
318              kill();
319            }),
320        allianceCtx::allianceKnownOrIgnored);
321  }
322}