Trajectory
pathplannerlib Index / Pathplannerlib / Trajectory
Auto-generated documentation for pathplannerlib.trajectory module.
PathPlannerTrajectory
Show source in trajectory.py:108
Signature
class PathPlannerTrajectory:
def __init__(
self,
path: Union[PathPlannerPath, None],
starting_speeds: Union[ChassisSpeeds, None],
starting_rotation: Union[Rotation2d, None],
states: List[State] = None,
event_commands: List[Tuple[float, Command]] = None,
): ...
See also
PathPlannerTrajectory().getEndState
Show source in trajectory.py:195
Get the end state of the trajectory
Returns
The end state
Signature
See also
PathPlannerTrajectory().getEventCommands
Show source in trajectory.py:154
Get all of the pairs of timestamps + commands to run at those timestamps
Returns
Pairs of timestamps and event commands
Signature
PathPlannerTrajectory().getInitialDifferentialPose
Show source in trajectory.py:187
Get this initial pose for a differential drivetrain
Returns
The initial pose
Signature
PathPlannerTrajectory().getInitialState
Show source in trajectory.py:171
Get the initial state of the trajectory
Returns
The initial state
Signature
See also
PathPlannerTrajectory().getInitialTargetHolonomicPose
Show source in trajectory.py:179
Get the initial target pose for a holonomic drivetrain NOTE: This is a "target" pose, meaning the rotation will be the value of the next rotation target along the path, not what the rotation should be at the start of the path
Returns
The initial target pose
Signature
PathPlannerTrajectory().getState
Show source in trajectory.py:162
Get the goal state at the given index
Arguments
index
- Index of the state to get
Returns
The state at the given index
Signature
See also
PathPlannerTrajectory().getStates
Show source in trajectory.py:146
Get all of the pre-generated states in the trajectory
Returns
List of all states
Signature
See also
PathPlannerTrajectory().getTotalTimeSeconds
Show source in trajectory.py:203
Get the total run time of the trajectory
Returns
Total run time in seconds
Signature
PathPlannerTrajectory().sample
Show source in trajectory.py:211
Get the target state at the given point in time along the trajectory
Arguments
time
- The time to sample the trajectory at in seconds
Returns
The target state
Signature
See also
State
Show source in trajectory.py:17
Signature
State().getDifferentialPose
Show source in trajectory.py:77
Get this pose for a differential drivetrain
Returns
The pose
Signature
State().getTargetHolonomicPose
Show source in trajectory.py:69
Get the target pose for a holonomic drivetrain NOTE: This is a "target" pose, meaning the rotation will be the value of the next rotation target along the path, not what the rotation should be at the start of the path
Returns
The target pose
Signature
State().interpolate
Show source in trajectory.py:30
Interpolate between this state and the given state
Arguments
end_val
- State to interpolate witht
- Interpolation factor (0.0-1.0)
Returns
Interpolated state
Signature
State().reverse
Show source in trajectory.py:85
Get the state reversed, used for following a trajectory reversed with a differential drivetrain
Returns
The reversed state