Class PathPlannerTrajectoryState

java.lang.Object
com.pathplanner.lib.trajectory.PathPlannerTrajectoryState
All Implemented Interfaces:
Interpolatable<PathPlannerTrajectoryState>

public class PathPlannerTrajectoryState extends Object implements Interpolatable<PathPlannerTrajectoryState>
A state along the a PathPlannerTrajectory
  • Field Details

    • timeSeconds

      public double timeSeconds
      The time at this state in seconds
    • fieldSpeeds

      public ChassisSpeeds fieldSpeeds
      Field-relative chassis speeds at this state
    • pose

      public Pose2d pose
      Field-relative robot pose at this state
    • linearVelocity

      public double linearVelocity
      The linear velocity at this state in m/s
    • feedforwards

      public DriveFeedforwards feedforwards
      The feedforwards for each module
    • heading

      protected Rotation2d heading
      The field-relative heading, or direction of travel, at this state
    • deltaPos

      protected double deltaPos
      The distance between this state and the previous state
    • deltaRot

      protected Rotation2d deltaRot
      The difference in rotation between this state and the previous state
    • moduleStates

      protected SwerveModuleTrajectoryState[] moduleStates
      The SwerveModuleTrajectoryState states for this state
    • constraints

      protected PathConstraints constraints
      The PathConstraints for this state
    • waypointRelativePos

      protected double waypointRelativePos
      The waypoint relative position of this state. Used to determine proper event marker timing
  • Constructor Details

    • PathPlannerTrajectoryState

      public PathPlannerTrajectoryState()
  • Method Details

    • interpolate

      public PathPlannerTrajectoryState interpolate(PathPlannerTrajectoryState endVal, double t)
      Interpolate between this state and the given state
      Specified by:
      interpolate in interface Interpolatable<PathPlannerTrajectoryState>
      Parameters:
      endVal - State to interpolate with
      t - Interpolation factor (0.0-1.0)
      Returns:
      Interpolated state
    • reverse

      public PathPlannerTrajectoryState reverse()
      Get the state reversed, used for following a trajectory reversed with a differential drivetrain
      Returns:
      The reversed state
    • flip

      Flip this trajectory state for the other side of the field, maintaining a blue alliance origin
      Returns:
      This trajectory state flipped to the other side of the field
    • copyWithTime

      public PathPlannerTrajectoryState copyWithTime(double time)
      Copy this state and change the timestamp
      Parameters:
      time - The new time to use
      Returns:
      Copied state with the given time