Package choreo.auto

Class AutoTrajectory

java.lang.Object
choreo.auto.AutoTrajectory

public class AutoTrajectory extends Object
A class that represents a trajectory that can be used in an autonomous routine and have triggers based off of it.
  • Method Summary

    Modifier and Type
    Method
    Description
    Returns a trigger that is true while the trajectory is scheduled.
    atPose(Pose2d pose, double toleranceMeters)
    Returns a trigger that is true when the robot is within toleranceMeters of the given pose.
    atPose(String eventName)
    Returns a trigger that is true when the robot is within 3 inches of the given events pose.
    atPose(String eventName, double toleranceMeters)
    Returns a trigger that is true when the robot is within toleranceMeters of the given events pose.
    atTime(double timeSinceStart)
    Returns a trigger that will go true for 1 cycle when the desired time has elapsed
    atTime(String eventName)
    Returns a trigger that is true when the event with the given name has been reached based on time.
    atTimeAndPose(String eventName)
    Returns a trigger that is true when the event with the given name has been reached based on time and the robot is within 3 inches of the given events pose.
    atTimeAndPose(String eventName, double toleranceMeters)
    Returns a trigger that is true when the event with the given name has been reached based on time and the robot is within toleranceMeters of the given events pose.
    cmd()
    Creates a command that allocates the drive subsystem and follows the trajectory using the factories control function
    Returns an array of all the poses of the events with the given name.
    double[]
    Returns an array of all the timestamps of the events with the given name.
    Returns a trigger that rises to true when the trajectory ends and falls when another trajectory is run.
    done(int cyclesToDelay)
    Returns a trigger that rises to true when the trajectory ends and falls when another trajectory is run.
    boolean
     
    Will get the ending pose of the trajectory.
    Will get the starting pose of the trajectory.
    <SampleType extends TrajectorySample<SampleType>>
    Trajectory<SampleType>
    Will get the underlying Trajectory object.
    Returns a trigger that is true while the command is not scheduled.

    Methods inherited from class java.lang.Object

    clone, finalize, getClass, hashCode, notify, notifyAll, toString, wait, wait, wait
  • Method Details

    • cmd

      public Command cmd()
      Creates a command that allocates the drive subsystem and follows the trajectory using the factories control function
      Returns:
      The command that will follow the trajectory
    • getRawTrajectory

      public <SampleType extends TrajectorySample<SampleType>> Trajectory<SampleType> getRawTrajectory()
      Will get the underlying Trajectory object.

      WARNING: This method is not type safe and should be used with caution. The sample type of the trajectory should be known before calling this method.

      Type Parameters:
      SampleType - The type of the trajectory samples.
      Returns:
      The underlying Trajectory object.
    • getInitialPose

      Will get the starting pose of the trajectory.

      This position is mirrored based on the mirrorTrajectory boolean supplier in the factory used to make this trajectory

      Returns:
      The starting pose
    • getFinalPose

      Will get the ending pose of the trajectory.

      This position is mirrored based on the mirrorTrajectory boolean supplier in the factory used to make this trajectory

      Returns:
      The starting pose
    • active

      public Trigger active()
      Returns a trigger that is true while the trajectory is scheduled.
      Returns:
      A trigger that is true while the trajectory is scheduled.
    • inactive

      public Trigger inactive()
      Returns a trigger that is true while the command is not scheduled.

      The same as calling active().negate().

      Returns:
      A trigger that is true while the command is not scheduled.
    • done

      public Trigger done(int cyclesToDelay)
      Returns a trigger that rises to true when the trajectory ends and falls when another trajectory is run.

      This is different from inactive() in a few ways.

      • This will never be true if the trajectory is interupted
      • This will never be true before the trajectory is run
      • This will fall the next cycle after the trajectory ends

      Why does the trigger need to fall?

      
       //Lets say we had this code segment
       Trigger hasGamepiece = ...;
       Trigger noGamepiece = hasGamepiece.negate();
      
       AutoTrajectory rushMidTraj = ...;
       AutoTrajectory goShootGamepiece = ...;
       AutoTrajectory pickupAnotherGamepiece = ...;
      
       routine.enabled().onTrue(rushMidTraj.cmd());
      
       rushMidTraj.done(10).and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd());
       rushMidTraj.done(10).and(hasGamepiece).onTrue(goShootGamepiece.cmd());
      
       // If done never falls when a new trajectory is scheduled
       // then these triggers leak into the next trajectory, causing the next note pickup
       // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
       
      Parameters:
      cyclesToDelay - The number of cycles to delay the trigger from rising to true.
      Returns:
      A trigger that is true when the trajectoy is finished.
    • done

      public Trigger done()
      Returns a trigger that rises to true when the trajectory ends and falls when another trajectory is run.

      This is different from inactive() in a few ways.

      • This will never be true if the trajectory is interupted
      • This will never be true before the trajectory is run
      • This will fall the next cycle after the trajectory ends

      Why does the trigger need to fall?

      
       //Lets say we had this code segment
       Trigger hasGamepiece = ...;
       Trigger noGamepiece = hasGamepiece.negate();
      
       AutoTrajectory rushMidTraj = ...;
       AutoTrajectory goShootGamepiece = ...;
       AutoTrajectory pickupAnotherGamepiece = ...;
      
       routine.enabled().onTrue(rushMidTraj.cmd());
      
       rushMidTraj.done().and(noGamepiece).onTrue(pickupAnotherGamepiece.cmd());
       rushMidTraj.done().and(hasGamepiece).onTrue(goShootGamepiece.cmd());
      
       // If done never falls when a new trajectory is scheduled
       // then these triggers leak into the next trajectory, causing the next note pickup
       // to trigger goShootGamepiece.cmd() even if we no longer care about these checks
       
      Returns:
      A trigger that is true when the trajectoy is finished.
    • atTime

      public Trigger atTime(double timeSinceStart)
      Returns a trigger that will go true for 1 cycle when the desired time has elapsed
      Parameters:
      timeSinceStart - The time since the command started in seconds.
      Returns:
      A trigger that is true when timeSinceStart has elapsed.
    • atTime

      public Trigger atTime(String eventName)
      Returns a trigger that is true when the event with the given name has been reached based on time.

      A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.

      Parameters:
      eventName - The name of the event.
      Returns:
      A trigger that is true when the event with the given name has been reached based on time.
    • atPose

      public Trigger atPose(Pose2d pose, double toleranceMeters)
      Returns a trigger that is true when the robot is within toleranceMeters of the given pose.

      This position is mirrored based on the mirrorTrajectory boolean supplier in the factory used to make this trajectory.

      Parameters:
      pose - The pose to check against
      toleranceMeters - The tolerance in meters.
      Returns:
      A trigger that is true when the robot is within toleranceMeters of the given pose.
    • atPose

      public Trigger atPose(String eventName, double toleranceMeters)
      Returns a trigger that is true when the robot is within toleranceMeters of the given events pose.

      A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.

      Parameters:
      eventName - The name of the event.
      toleranceMeters - The tolerance in meters.
      Returns:
      A trigger that is true when the robot is within toleranceMeters of the given events pose.
    • atPose

      public Trigger atPose(String eventName)
      Returns a trigger that is true when the robot is within 3 inches of the given events pose.

      A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.

      Parameters:
      eventName - The name of the event.
      Returns:
      A trigger that is true when the robot is within 3 inches of the given events pose.
    • atTimeAndPose

      public Trigger atTimeAndPose(String eventName, double toleranceMeters)
      Returns a trigger that is true when the event with the given name has been reached based on time and the robot is within toleranceMeters of the given events pose.

      A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.

      Parameters:
      eventName - The name of the event.
      toleranceMeters - The tolerance in meters.
      Returns:
      A trigger that is true when the event with the given name has been reached based on time and the robot is within toleranceMeters of the given events pose.
    • atTimeAndPose

      public Trigger atTimeAndPose(String eventName)
      Returns a trigger that is true when the event with the given name has been reached based on time and the robot is within 3 inches of the given events pose.

      A warning will be printed to the DriverStation if the event is not found and the trigger will always be false.

      Parameters:
      eventName - The name of the event.
      Returns:
      A trigger that is true when the event with the given name has been reached based on time and the robot is within 3 inches of the given events pose.
    • collectEventTimes

      public double[] collectEventTimes(String eventName)
      Returns an array of all the timestamps of the events with the given name.
      Parameters:
      eventName - The name of the event.
      Returns:
      An array of all the timestamps of the events with the given name.
    • collectEventPoses

      public Pose2d[] collectEventPoses(String eventName)
      Returns an array of all the poses of the events with the given name.
      Parameters:
      eventName - The name of the event.
      Returns:
      An array of all the poses of the events with the given name.
    • equals

      public boolean equals(Object obj)
      Overrides:
      equals in class Object