PathPlannerTrajectory¶
- class pathplannerlib.PathPlannerTrajectory¶
Bases:
pybind11_object
- class PathPlannerState¶
Bases:
pybind11_object
- property acceleration¶
- property angularVelocity¶
- asWPILibState() wpimath._controls._controls.trajectory.Trajectory.State ¶
Get this state as a WPILib trajectory state
- Returns:
The WPILib state
- property holonomicAngularVelocity¶
- property holonomicRotation¶
- property pose¶
- property time¶
- property velocity¶
- class StopEvent(*args, **kwargs)¶
Bases:
pybind11_object
Overloaded function.
__init__(self: pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent, names: List[str], executionBehavior: pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent.ExecutionBehavior, waitBehavior: pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent.WaitBehavior, waitTime: seconds) -> None
__init__(self: pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent) -> None
- class ExecutionBehavior(value: int)¶
Bases:
pybind11_object
Members:
PARALLEL
SEQUENTIAL
PARALLEL_DEADLINE
- PARALLEL = <ExecutionBehavior.PARALLEL: 0>¶
- PARALLEL_DEADLINE = <ExecutionBehavior.PARALLEL_DEADLINE: 2>¶
- SEQUENTIAL = <ExecutionBehavior.SEQUENTIAL: 1>¶
- property name¶
- property value¶
- class WaitBehavior(value: int)¶
Bases:
pybind11_object
Members:
NONE
BEFORE
AFTER
DEADLINE
MINIMUM
- AFTER = <WaitBehavior.AFTER: 2>¶
- BEFORE = <WaitBehavior.BEFORE: 1>¶
- DEADLINE = <WaitBehavior.DEADLINE: 3>¶
- MINIMUM = <WaitBehavior.MINIMUM: 4>¶
- NONE = <WaitBehavior.NONE: 0>¶
- property name¶
- property value¶
- property executionBehavior¶
- property names¶
- property waitBehavior¶
- property waitTime¶
- asWPILibTrajectory() wpimath._controls._controls.trajectory.Trajectory ¶
Convert this path to a WPILib compatible trajectory
- Returns:
The path as a WPILib trajectory
- property fromGUI¶
- getEndState() pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState ¶
Get the end state of the path
- Returns:
Reference to the last state in the path
- getEndStopEvent() pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent ¶
Get the “stop event” for the end of the path
- Returns:
The end stop event
- getInitialHolonomicPose() wpimath.geometry._geometry.Pose2d ¶
Get the inital pose of a holonomic drive robot in the path
- Returns:
The initial pose
- getInitialPose() wpimath.geometry._geometry.Pose2d ¶
Get the inital pose of a differential drive robot in the path
- Returns:
The initial pose
- getInitialState() pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState ¶
Get the initial state of the path
- Returns:
Reference to the first state of the path
- getMarkers() List[pathplannerlib._pathplannerlib.PathPlannerTrajectory.EventMarker] ¶
Get all of the markers in the path
- Returns:
Reference to a vector of all markers
- getStartStopEvent() pathplannerlib._pathplannerlib.PathPlannerTrajectory.StopEvent ¶
Get the “stop event” for the beginning of the path
- Returns:
The start stop event
- getState(i: int) pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState ¶
Get a state in the path based on its index. In most cases, using sample() is a better method.
- Parameters:
i – The index of the state
- Returns:
Reference to the state at the given index
- getStates() List[pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState] ¶
Get all of the states in the path
- Returns:
Reference to a vector of all states
- getTotalTime() seconds ¶
Get the total runtime of the path
- Returns:
The path runtime
- numStates() int ¶
Get the total number of states in the path
- Returns:
The number of states
- sample(time: seconds) pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState ¶
Sample the path at a point in time
- Parameters:
time – The time to sample
- Returns:
The state at the given point in time
- static transformStateForAlliance(state: pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState, alliance: wpilib._wpilib.DriverStation.Alliance) pathplannerlib._pathplannerlib.PathPlannerTrajectory.PathPlannerState ¶
- static transformTrajectoryForAlliance(trajectory: pathplannerlib._pathplannerlib.PathPlannerTrajectory, alliance: wpilib._wpilib.DriverStation.Alliance) pathplannerlib._pathplannerlib.PathPlannerTrajectory ¶