Package choreo.auto

Class AutoRoutine

java.lang.Object
choreo.auto.AutoRoutine

public class AutoRoutine extends Object
An object that represents an autonomous routine.

This object is used to handle autonomous trigger logic and schedule commands for a single autonomous routine. This object should **not** be shared across multiple autonomous routines.

See Also:
  • Method Details

    • active

      public Trigger active()
      Returns a Trigger that is true while this autonomous routine is being polled.

      Using a Trigger.onFalse(Command) will do nothing as when this is false the routine is not being polled anymore.

      Returns:
      A Trigger that is true while this autonomous routine is being polled.
    • poll

      public void poll()
      Polls the routine. Should be called in the autonomous periodic method.
    • loop

      public EventLoop loop()
      Gets the event loop that this routine is using.
      Returns:
      The event loop that this routine is using.
    • observe

      public Trigger observe(BooleanSupplier condition)
      Creates a Trigger that is bound to the routine's EventLoop.
      Parameters:
      condition - The condition represented by the trigger.
      Returns:
      A Trigger that mirrors the state of the provided condition
    • reset

      public void reset()
      Resets the routine. This can either be called on auto init or auto end to reset the routine incase you run it again. If this is called on a routine that doesn't need to be reset it will do nothing.
    • kill

      public void kill()
      Kills the loop and prevents it from running again.
    • idle

      public Trigger idle()
      Creates a trigger that is true when the routine is idle.

      Idle is defined as no trajectories made by the routine are running.

      Returns:
      A trigger that is true when the routine is idle.
    • trajectory

      public AutoTrajectory trajectory(String trajectoryName)
      Creates a new AutoTrajectory to be used in an auto routine.
      Parameters:
      trajectoryName - The name of the trajectory to use.
      Returns:
      A new AutoTrajectory.
    • trajectory

      public AutoTrajectory trajectory(String trajectoryName, int splitIndex)
      Creates a new AutoTrajectory to be used in an auto routine.
      Parameters:
      trajectoryName - The name of the trajectory to use.
      splitIndex - The index of the split trajectory to use.
      Returns:
      A new AutoTrajectory.
    • trajectory

      public <SampleType extends TrajectorySample<SampleType>> AutoTrajectory trajectory(Trajectory<SampleType> trajectory)
      Creates a new AutoTrajectory to be used in an auto routine.
      Type Parameters:
      SampleType - The type of the trajectory samples.
      Parameters:
      trajectory - The trajectory to use.
      Returns:
      A new AutoTrajectory.
    • anyDone

      public Trigger anyDone(AutoTrajectory trajectory, AutoTrajectory... trajectories)
      Creates a trigger that produces a rising edge when any of the trajectories are finished.
      Parameters:
      trajectory - The first trajectory to watch.
      trajectories - The other trajectories to watch
      Returns:
      a trigger that determines if any of the trajectories are finished
      See Also:
    • anyDoneDelayed

      public Trigger anyDoneDelayed(int cyclesToDelay, AutoTrajectory trajectory, AutoTrajectory... trajectories)
      Creates a trigger that produces a rising edge when any of the trajectories are finished.
      Parameters:
      cyclesToDelay - The number of cycles to delay.
      trajectory - The first trajectory to watch.
      trajectories - The other trajectories to watch
      Returns:
      a trigger that goes true for one cycle whenever any of the trajectories finishes, delayed by the given number of cycles.
      See Also:
    • anyDone

      @Deprecated(forRemoval=true, since="2025") public Trigger anyDone(int cyclesToDelay, AutoTrajectory trajectory, AutoTrajectory... trajectories)
      Deprecated, for removal: This API element is subject to removal in a future version.
      This method is deprecated and will be removed in 2025. Use anyDoneDelayed(int, choreo.auto.AutoTrajectory, choreo.auto.AutoTrajectory...)
      Creates a trigger that produces a rising edge when any of the trajectories are finished.
      Parameters:
      cyclesToDelay - The number of cycles to delay.
      trajectory - The first trajectory to watch.
      trajectories - The other trajectories to watch
      Returns:
      a trigger that determines if any of the trajectories are finished
      See Also:
    • anyActive

      public Trigger anyActive(AutoTrajectory trajectory, AutoTrajectory... trajectories)
      Creates a trigger that returns true when any of the trajectories given are active.
      Parameters:
      trajectory - The first trajectory to watch.
      trajectories - The other trajectories to watch
      Returns:
      a trigger that determines if any of the trajectories are active
    • allInactive

      public Trigger allInactive(AutoTrajectory trajectory, AutoTrajectory... trajectories)
      Creates a trigger that returns true when any of the trajectories given are inactive.

      This trigger will only return true if the routine is active.

      Parameters:
      trajectory - The first trajectory to watch.
      trajectories - The other trajectories to watch
      Returns:
      a trigger that determines if any of the trajectories are inactive
    • cmd

      public Command cmd()
      Creates a command that will poll this event loop and reset it when it is cancelled.

      The command will end instantly and kill the routine if the alliance supplier returns an empty optional when the command is scheduled.

      Returns:
      A command that will poll this event loop and reset it when it is cancelled.
      See Also:
    • cmd

      public Command cmd(BooleanSupplier finishCondition)
      Creates a command that will poll this event loop and reset it when it is finished or canceled.

      The command will end instantly and kill the routine if the alliance supplier returns an empty optional when the command is scheduled.

      Parameters:
      finishCondition - A condition that will finish the loop when it is true.
      Returns:
      A command that will poll this event loop and reset it when it is finished or canceled.
      See Also: