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