Package com.pathplanner.lib.trajectory
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 Summary
FieldsModifier and TypeFieldDescriptionprotected PathConstraintsThePathConstraintsfor this stateprotected doubleThe distance between this state and the previous stateprotected Rotation2dThe difference in rotation between this state and the previous stateThe feedforwards for each moduleField-relative chassis speeds at this stateThe field-relative heading, or direction of travel, at this statedoubleThe linear velocity at this state in m/sprotected SwerveModuleTrajectoryState[]TheSwerveModuleTrajectoryStatestates for this stateField-relative robot pose at this statedoubleThe time at this state in secondsprotected doubleThe waypoint relative position of this state. -
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptioncopyWithTime(double time) Copy this state and change the timestampflip()Flip this trajectory state for the other side of the field, maintaining a blue alliance origininterpolate(PathPlannerTrajectoryState endVal, double t) Interpolate between this state and the given statereverse()Get the state reversed, used for following a trajectory reversed with a differential drivetrain
-
Field Details
-
timeSeconds
public double timeSecondsThe time at this state in seconds -
fieldSpeeds
Field-relative chassis speeds at this state -
pose
Field-relative robot pose at this state -
linearVelocity
public double linearVelocityThe linear velocity at this state in m/s -
heading
The field-relative heading, or direction of travel, at this state -
feedforwards
The feedforwards for each module -
deltaPos
protected double deltaPosThe distance between this state and the previous state -
deltaRot
The difference in rotation between this state and the previous state -
moduleStates
TheSwerveModuleTrajectoryStatestates for this state -
constraints
ThePathConstraintsfor this state -
waypointRelativePos
protected double waypointRelativePosThe waypoint relative position of this state. Used to determine proper event marker timing
-
-
Constructor Details
-
PathPlannerTrajectoryState
public PathPlannerTrajectoryState()
-
-
Method Details
-
interpolate
Interpolate between this state and the given state- Specified by:
interpolatein interfaceInterpolatable<PathPlannerTrajectoryState>- Parameters:
endVal- State to interpolate witht- Interpolation factor (0.0-1.0)- Returns:
- Interpolated state
-
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
Copy this state and change the timestamp- Parameters:
time- The new time to use- Returns:
- Copied state with the given time
-