Skip to content

Trajectory

pathplannerlib Index / Pathplannerlib / Trajectory

Auto-generated documentation for pathplannerlib.trajectory module.

PathPlannerTrajectory

Show source in trajectory.py:151

Signature

class PathPlannerTrajectory:
    def __init__(
        self,
        path: Union[PathPlannerPath, None],
        starting_speeds: Union[ChassisSpeeds, None],
        starting_rotation: Union[Rotation2d, None],
        config: Union[RobotConfig, None],
        states: List[PathPlannerTrajectoryState] = None,
        events: List[Event] = None,
    ): ...

See also

PathPlannerTrajectory().flip

Show source in trajectory.py:380

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

Signature

def flip(self) -> PathPlannerTrajectory: ...

PathPlannerTrajectory().getEndState

Show source in trajectory.py:325

Get the end state of the trajectory

Returns

The end state

Signature

def getEndState(self) -> PathPlannerTrajectoryState: ...

See also

PathPlannerTrajectory().getEvents

Show source in trajectory.py:292

Get all the events to run while following this trajectory

Returns

Events in this trajectory

Signature

def getEvents(self) -> List[Event]: ...

PathPlannerTrajectory().getInitialPose

Show source in trajectory.py:341

Get the initial robot pose at the start of the trajectory

Returns

Pose of the robot at the initial state

Signature

def getInitialPose(self) -> Pose2d: ...

PathPlannerTrajectory().getInitialState

Show source in trajectory.py:317

Get the initial state of the trajectory

Returns

The initial state

Signature

def getInitialState(self) -> PathPlannerTrajectoryState: ...

See also

PathPlannerTrajectory().getState

Show source in trajectory.py:308

Get the goal state at the given index

Arguments

  • index - Index of the state to get

Returns

The state at the given index

Signature

def getState(self, index: int) -> PathPlannerTrajectoryState: ...

See also

PathPlannerTrajectory().getStates

Show source in trajectory.py:300

Get all of the pre-generated states in the trajectory

Returns

List of all states

Signature

def getStates(self) -> List[PathPlannerTrajectoryState]: ...

See also

PathPlannerTrajectory().getTotalTimeSeconds

Show source in trajectory.py:333

Get the total run time of the trajectory

Returns

Total run time in seconds

Signature

def getTotalTimeSeconds(self) -> float: ...

PathPlannerTrajectory().sample

Show source in trajectory.py:349

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

def sample(self, time: float) -> PathPlannerTrajectoryState: ...

See also

PathPlannerTrajectoryState

Show source in trajectory.py:28

Signature

class PathPlannerTrajectoryState: ...

PathPlannerTrajectoryState().copyWithTime

Show source in trajectory.py:128

Copy this state and change the timestamp

Arguments

  • time - The new time to use

Returns

Copied state with the given time

Signature

def copyWithTime(self, time: float) -> PathPlannerTrajectoryState: ...

PathPlannerTrajectoryState().flip

Show source in trajectory.py:112

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

Signature

def flip(self) -> PathPlannerTrajectoryState: ...

PathPlannerTrajectoryState().interpolate

Show source in trajectory.py:42

Interpolate between this state and the given state

Arguments

  • end_val - PathPlannerTrajectoryState to interpolate with
  • t - Interpolation factor (0.0-1.0)

Returns

Interpolated state

Signature

def interpolate(
    self, end_val: PathPlannerTrajectoryState, t: float
) -> PathPlannerTrajectoryState: ...

PathPlannerTrajectoryState().reverse

Show source in trajectory.py:95

Get the state reversed, used for following a trajectory reversed with a differential drivetrain

Returns

The reversed state

Signature

def reverse(self) -> PathPlannerTrajectoryState: ...

SwerveModuleTrajectoryState

Show source in trajectory.py:17

Signature

class SwerveModuleTrajectoryState(SwerveModuleState):
    def __init__(self): ...