001// Copyright (c) Choreo contributors
002
003package choreo.auto;
004
005import static edu.wpi.first.util.ErrorMessages.requireNonNullParam;
006
007import choreo.Choreo.TrajectoryCache;
008import choreo.Choreo.TrajectoryLogger;
009import choreo.trajectory.SwerveSample;
010import choreo.trajectory.Trajectory;
011import choreo.trajectory.TrajectorySample;
012import choreo.util.ChoreoAllianceFlipUtil;
013import edu.wpi.first.hal.FRCNetComm.tResourceType;
014import edu.wpi.first.hal.HAL;
015import edu.wpi.first.math.geometry.Pose2d;
016import edu.wpi.first.wpilibj.DriverStation;
017import edu.wpi.first.wpilibj.DriverStation.Alliance;
018import edu.wpi.first.wpilibj.RobotBase;
019import edu.wpi.first.wpilibj2.command.Command;
020import edu.wpi.first.wpilibj2.command.Commands;
021import edu.wpi.first.wpilibj2.command.Subsystem;
022import edu.wpi.first.wpilibj2.command.button.Trigger;
023import java.util.HashMap;
024import java.util.List;
025import java.util.Optional;
026import java.util.function.BooleanSupplier;
027import java.util.function.Consumer;
028import java.util.function.Supplier;
029
030/**
031 * A factory used to create {@link AutoRoutine}s and {@link AutoTrajectory}s.
032 *
033 * @see <a href="https://choreo.autos/choreolib/auto-routines">Auto Routine Docs</a>
034 */
035public class AutoFactory {
036  static record AllianceContext(
037      boolean useAllianceFlipping, Supplier<Optional<Alliance>> allianceGetter) {
038    boolean allianceKnownOrIgnored() {
039      return allianceGetter.get().isPresent() || !useAllianceFlipping;
040    }
041
042    boolean doFlip() {
043      return useAllianceFlipping
044          && allianceGetter
045              .get()
046              .orElseThrow(
047                  () -> new RuntimeException("Flip check was called with an unknown alliance"))
048              .equals(Alliance.Red);
049    }
050
051    Optional<Alliance> alliance() {
052      return allianceGetter.get();
053    }
054
055    Supplier<Optional<Pose2d>> getFlippedPose(Optional<Pose2d> bluePose) {
056      return ChoreoAllianceFlipUtil.optionalFlippedPose2d(
057          bluePose, this::alliance, useAllianceFlipping);
058    }
059  }
060
061  /** A class used to bind commands to events in all trajectories created by this factory. */
062  static class AutoBindings {
063    private HashMap<String, Command> bindings = new HashMap<>();
064
065    /** Default constructor. */
066    public AutoBindings() {}
067
068    /**
069     * Binds a command to an event in all trajectories created by the factory using this bindings.
070     *
071     * @param name The name of the event to bind the command to.
072     * @param cmd The command to bind to the event.
073     * @return The bindings object for chaining.
074     */
075    public AutoBindings bind(String name, Command cmd) {
076      bindings.put(name, cmd);
077      return this;
078    }
079
080    /**
081     * Gets the bindings map.
082     *
083     * @return The bindings map.
084     */
085    HashMap<String, Command> getBindings() {
086      return bindings;
087    }
088  }
089
090  private final TrajectoryCache trajectoryCache = new TrajectoryCache();
091  private final Supplier<Pose2d> poseSupplier;
092  private final Consumer<Pose2d> resetOdometry;
093  private final Consumer<? extends TrajectorySample<?>> controller;
094  private final AllianceContext allianceCtx;
095  private final Subsystem driveSubsystem;
096  private final AutoBindings bindings = new AutoBindings();
097  private final TrajectoryLogger<? extends TrajectorySample<?>> trajectoryLogger;
098  private final AutoRoutine voidRoutine;
099
100  /**
101   * Create a factory that can be used to create {@link AutoRoutine} and {@link AutoTrajectory}.
102   *
103   * @param <SampleType> The type of samples in the trajectory.
104   * @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
105   *     robot.
106   * @param resetOdometry A function that receives a field-relative {@link Pose2d} to reset the
107   *     robot's odometry to.
108   * @param controller A function that receives the current {@link SampleType} and controls the
109   *     robot.
110   * @param useAllianceFlipping If this is true, when on the red alliance, the path will be mirrored
111   *     to the opposite side, while keeping the same coordinate system origin.
112   * @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
113   *     Command}s.
114   * @param trajectoryLogger A {@link TrajectoryLogger} to log {@link Trajectory} as they start and
115   *     finish.
116   * @see AutoChooser using this factory with AutoChooser to generate auto routines.
117   */
118  public <SampleType extends TrajectorySample<SampleType>> AutoFactory(
119      Supplier<Pose2d> poseSupplier,
120      Consumer<Pose2d> resetOdometry,
121      Consumer<SampleType> controller,
122      boolean useAllianceFlipping,
123      Subsystem driveSubsystem,
124      TrajectoryLogger<SampleType> trajectoryLogger) {
125    requireNonNullParam(poseSupplier, "poseSupplier", "AutoFactory");
126    requireNonNullParam(resetOdometry, "resetOdometry", "AutoFactory");
127    requireNonNullParam(controller, "controller", "AutoFactory");
128    requireNonNullParam(driveSubsystem, "driveSubsystem", "AutoFactory");
129    requireNonNullParam(useAllianceFlipping, "useAllianceFlipping", "AutoFactory");
130
131    this.poseSupplier = poseSupplier;
132    this.resetOdometry = resetOdometry;
133    this.controller = controller;
134    this.driveSubsystem = driveSubsystem;
135    this.allianceCtx = new AllianceContext(useAllianceFlipping, DriverStation::getAlliance);
136    this.trajectoryLogger = trajectoryLogger;
137    HAL.report(tResourceType.kResourceType_ChoreoTrigger, 1);
138
139    voidRoutine =
140        new AutoRoutine(this, "VOID-ROUTINE", allianceCtx) {
141          @Override
142          public Command cmd() {
143            return Commands.none().withName("VoidAutoRoutine");
144          }
145
146          @Override
147          public Command cmd(BooleanSupplier _finishCondition) {
148            return cmd();
149          }
150
151          @Override
152          public void poll() {}
153
154          @Override
155          public void reset() {}
156
157          @Override
158          public Trigger active() {
159            return new Trigger(this.loop(), () -> true);
160          }
161        };
162  }
163
164  /**
165   * Create a factory that can be used to create {@link AutoRoutine} and {@link AutoTrajectory}.
166   *
167   * @param <ST> {@link choreo.trajectory.DifferentialSample} or {@link
168   *     choreo.trajectory.SwerveSample}
169   * @param poseSupplier A function that returns the current field-relative {@link Pose2d} of the
170   *     robot.
171   * @param resetOdometry A function that receives a field-relative {@link Pose2d} to reset the
172   *     robot's odometry to.
173   * @param controller A function that receives the current {@link ST} and controls the robot.
174   * @param useAllianceFlipping If this returns true, when on the red alliance, the path will be
175   *     mirrored to the opposite side, while keeping the same coordinate system origin.
176   * @param driveSubsystem The drive {@link Subsystem} to require for {@link AutoTrajectory} {@link
177   *     Command}s.
178   * @see AutoChooser using this factory with AutoChooser to generate auto routines.
179   */
180  public <ST extends TrajectorySample<ST>> AutoFactory(
181      Supplier<Pose2d> poseSupplier,
182      Consumer<Pose2d> resetOdometry,
183      Consumer<ST> controller,
184      boolean useAllianceFlipping,
185      Subsystem driveSubsystem) {
186    this(
187        poseSupplier,
188        resetOdometry,
189        controller,
190        useAllianceFlipping,
191        driveSubsystem,
192        (sample, isStart) -> {});
193  }
194
195  /**
196   * Creates a new {@link AutoRoutine}.
197   *
198   * @param name The name of the {@link AutoRoutine}.
199   * @return A new {@link AutoRoutine}.
200   */
201  public AutoRoutine newRoutine(String name) {
202    // Clear cache in simulation to allow a form of "hot-reloading" trajectories
203    if (RobotBase.isSimulation()) {
204      trajectoryCache.clear();
205    }
206
207    return new AutoRoutine(this, name, allianceCtx);
208  }
209
210  /**
211   * A package protected method to create a new {@link AutoTrajectory} to be used in an {@link
212   * AutoRoutine}.
213   *
214   * @see AutoRoutine#trajectory(String)
215   */
216  AutoTrajectory trajectory(String trajectoryName, AutoRoutine routine, boolean useBindings) {
217    Optional<? extends Trajectory<?>> optTrajectory =
218        trajectoryCache.loadTrajectory(trajectoryName);
219    Trajectory<?> trajectory;
220    if (optTrajectory.isPresent()) {
221      trajectory = optTrajectory.get();
222    } else {
223      trajectory = new Trajectory<SwerveSample>(trajectoryName, List.of(), List.of(), List.of());
224    }
225    return trajectory(trajectory, routine, useBindings);
226  }
227
228  /**
229   * A package protected method to create a new {@link AutoTrajectory} to be used in an {@link
230   * AutoRoutine}.
231   *
232   * @see AutoRoutine#trajectory(String, int)
233   */
234  AutoTrajectory trajectory(
235      String trajectoryName, final int splitIndex, AutoRoutine routine, boolean useBindings) {
236    Optional<? extends Trajectory<?>> optTrajectory =
237        trajectoryCache.loadTrajectory(trajectoryName, splitIndex);
238    Trajectory<?> trajectory;
239    if (optTrajectory.isPresent()) {
240      trajectory = optTrajectory.get();
241    } else {
242      trajectory = new Trajectory<SwerveSample>(trajectoryName, List.of(), List.of(), List.of());
243    }
244    return trajectory(trajectory, routine, useBindings);
245  }
246
247  /**
248   * A package protected method to create a new {@link AutoTrajectory} to be used in an {@link
249   * AutoRoutine}.
250   *
251   * @see AutoRoutine#trajectory(Trajectory)
252   */
253  @SuppressWarnings("unchecked")
254  <ST extends TrajectorySample<ST>> AutoTrajectory trajectory(
255      Trajectory<ST> trajectory, AutoRoutine routine, boolean useBindings) {
256    // type solidify everything
257    final Trajectory<ST> solidTrajectory = trajectory;
258    final Consumer<ST> solidController = (Consumer<ST>) this.controller;
259    return new AutoTrajectory(
260        trajectory.name(),
261        solidTrajectory,
262        poseSupplier,
263        resetOdometry,
264        solidController,
265        allianceCtx,
266        (TrajectoryLogger<ST>) trajectoryLogger,
267        driveSubsystem,
268        routine,
269        useBindings ? bindings : new AutoBindings());
270  }
271
272  /**
273   * Creates a new {@link AutoTrajectory} command to be used in an auto routine.
274   *
275   * <p><b>Important </b>
276   *
277   * <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
278   * routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
279   * benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
280   * does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
281   * the factory constructor.
282   *
283   * @param trajectoryName The name of the trajectory to use.
284   * @return A new {@link AutoTrajectory}.
285   */
286  public Command trajectoryCmd(String trajectoryName) {
287    return trajectory(trajectoryName, voidRoutine, false).cmd();
288  }
289
290  /**
291   * Creates a new {@link AutoTrajectory} command to be used in an auto routine.
292   *
293   * <p><b>Important </b>
294   *
295   * <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
296   * routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
297   * benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
298   * does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
299   * the factory constructor.
300   *
301   * @param trajectoryName The name of the trajectory to use.
302   * @param splitIndex The index of the split trajectory to use.
303   * @return A new {@link AutoTrajectory}.
304   */
305  public Command trajectoryCmd(String trajectoryName, final int splitIndex) {
306    return trajectory(trajectoryName, splitIndex, voidRoutine, false).cmd();
307  }
308
309  /**
310   * Creates a new {@link AutoTrajectory} command to be used in an auto routine.
311   *
312   * <p><b>Important </b>
313   *
314   * <p>{@link #trajectoryCmd} and {@link #trajectory} methods should not be mixed in the same auto
315   * routine. {@link #trajectoryCmd} is used as an escape hatch for teams that don't need the
316   * benefits of the {@link #trajectory} method and its {@link Trigger} API. {@link #trajectoryCmd}
317   * does not invoke bindings added via calling {@link #bind} or {@link AutoBindings} passed into
318   * the factory constructor.
319   *
320   * @param <ST> {@link choreo.trajectory.DifferentialSample} or {@link
321   *     choreo.trajectory.SwerveSample}
322   * @param trajectory The trajectory to use.
323   * @return A new {@link AutoTrajectory}.
324   */
325  public <ST extends TrajectorySample<ST>> Command trajectoryCmd(Trajectory<ST> trajectory) {
326    return trajectory(trajectory, voidRoutine, false).cmd();
327  }
328
329  /**
330   * Creates a command that resets the robot's odometry to the start of a trajectory.
331   *
332   * @param trajectoryName The name of the trajectory to use.
333   * @return A command that resets the robot's odometry.
334   */
335  public Command resetOdometry(String trajectoryName) {
336    return trajectory(trajectoryName, voidRoutine, false).resetOdometry();
337  }
338
339  /**
340   * Creates a command that resets the robot's odometry to the start of a trajectory.
341   *
342   * @param trajectoryName The name of the trajectory to use.
343   * @param splitIndex The index of the split trajectory to use.
344   * @return A command that resets the robot's odometry.
345   */
346  public Command resetOdometry(String trajectoryName, final int splitIndex) {
347    return trajectory(trajectoryName, splitIndex, voidRoutine, false).resetOdometry();
348  }
349
350  /**
351   * Creates a command that resets the robot's odometry to the start of a trajectory.
352   *
353   * @param <ST> {@link choreo.trajectory.DifferentialSample} or {@link
354   *     choreo.trajectory.SwerveSample}
355   * @param trajectory The trajectory to use.
356   * @return A command that resets the robot's odometry.
357   */
358  public <ST extends TrajectorySample<ST>> Command resetOdometry(Trajectory<ST> trajectory) {
359    return trajectory(trajectory, voidRoutine, false).resetOdometry();
360  }
361
362  /**
363   * Creates a command that resets the robot's odometry to the supplied pose
364   *
365   * @param pose A function that is called when the command is run. It returns an <code>
366   *     Optional&lt;Pose2d&gt;</code> of the robot's desired odometry position.
367   * @return A command that resets the robot's odometry to the supplied pose, or does nothing if the
368   *     supplied Optional is empty.
369   */
370  public Command resetOdometry(Supplier<Optional<Pose2d>> pose) {
371    return driveSubsystem.runOnce(() -> pose.get().ifPresent(resetOdometry));
372  }
373
374  /**
375   * Creates a command that resets the robot's odometry to the given pose
376   *
377   * @param pose An <code>Optional&lt;Pose2d&gt;</code> of the robot's desired odometry position.
378   * @param doFlipForAlliance True if the given pose still needs to be flipped according to the
379   *     alliance (usually true). False if it is an absolute field position.
380   * @return A command that resets the robot's odometry to the given pose (flipped as directed), or
381   *     does nothing if the supplied Optional is empty.
382   */
383  public Command resetOdometry(Optional<Pose2d> pose, boolean doFlipForAlliance) {
384    if (pose.isEmpty()) {
385      return driveSubsystem.runOnce(
386          () -> {}); // equivalent to Commands.none() requiring driveSubsystem.
387    }
388    Supplier<Optional<Pose2d>> supplier =
389        doFlipForAlliance ? allianceCtx.getFlippedPose(pose) : (() -> pose);
390    return resetOdometry(supplier);
391  }
392
393  /**
394   * Binds a command to an event in all trajectories created after this point.
395   *
396   * @param name The name of the trajectory to bind the command to.
397   * @param cmd The command to bind to the trajectory.
398   * @return The AutoFactory the method was called from.
399   */
400  public AutoFactory bind(String name, Command cmd) {
401    bindings.bind(name, cmd);
402    return this;
403  }
404
405  /**
406   * The {@link AutoFactory} caches trajectories with a {@link TrajectoryCache} to avoid reloading
407   * the same trajectory multiple times.
408   *
409   * @return The trajectory cache.
410   */
411  public TrajectoryCache cache() {
412    return trajectoryCache;
413  }
414}