Class PathPlannerTrajectory

java.lang.Object
com.pathplanner.lib.trajectory.PathPlannerTrajectory

public class PathPlannerTrajectory extends Object
Trajectory generated for a PathPlanner path
  • Constructor Details

    • PathPlannerTrajectory

      public PathPlannerTrajectory(List<PathPlannerTrajectoryState> states, List<Event> events)
      Create a trajectory with pre-generated states and list of events
      Parameters:
      states - Pre-generated states
      events - Events for this trajectory
    • PathPlannerTrajectory

      public PathPlannerTrajectory(List<PathPlannerTrajectoryState> states)
      Create a trajectory with pre-generated states
      Parameters:
      states - Pre-generated states
    • PathPlannerTrajectory

      public PathPlannerTrajectory(PathPlannerPath path, ChassisSpeeds startingSpeeds, Rotation2d startingRotation, RobotConfig config)
      Generate a new trajectory for a given path
      Parameters:
      path - The path to generate a trajectory for
      startingSpeeds - The starting robot-relative chassis speeds of the robot
      startingRotation - The starting field-relative rotation of the robot
      config - The RobotConfig describing the robot
  • Method Details

    • getEvents

      public List<Event> getEvents()
      Get all the events to run while following this trajectory
      Returns:
      Events in this trajectory
    • getStates

      public List<PathPlannerTrajectoryState> getStates()
      Get all the pre-generated states in the trajectory
      Returns:
      List of all states
    • getState

      public PathPlannerTrajectoryState getState(int index)
      Get the goal state at the given index
      Parameters:
      index - Index of the state to get
      Returns:
      The state at the given index
    • getInitialState

      public PathPlannerTrajectoryState getInitialState()
      Get the initial state of the trajectory
      Returns:
      The initial state
    • getEndState

      public PathPlannerTrajectoryState getEndState()
      Get the end state of the trajectory
      Returns:
      The end state
    • getTotalTimeSeconds

      public double getTotalTimeSeconds()
      Get the total run time of the trajectory
      Returns:
      Total run time in seconds
    • getTotalTime

      public edu.wpi.first.units.measure.Time getTotalTime()
      Get the total run time of the trajectory
      Returns:
      Total run time
    • getInitialPose

      public Pose2d getInitialPose()
      Get the initial robot pose at the start of the trajectory
      Returns:
      Pose of the robot at the initial state
    • sample

      public PathPlannerTrajectoryState sample(double time)
      Get the target state at the given point in time along the trajectory
      Parameters:
      time - The time to sample the trajectory at in seconds
      Returns:
      The target state
    • sample

      public PathPlannerTrajectoryState sample(edu.wpi.first.units.measure.Time time)
      Get the target state at the given point in time along the trajectory
      Parameters:
      time - The time to sample the trajectory at
      Returns:
      The target state
    • flip

      public PathPlannerTrajectory flip()
      Flip this trajectory for the other side of the field, maintaining a blue alliance origin
      Returns:
      This trajectory with all states flipped to the other side of the field