Path
pathplannerlib Index / Pathplannerlib / Path
Auto-generated documentation for pathplannerlib.path module.
ConstraintsZone
A zone on a path with different kinematic constraints
Arguments
minWaypointPos
float - Starting position of the zonemaxWaypointPos
float - End position of the zoneconstraints
PathConstraints - PathConstraints to apply within the zone
Signature
ConstraintsZone.fromJson
Signature
EventMarker
Position along the path that will trigger a command when reached
Arguments
triggerName
str - The name of the trigger this event marker will controlwaypointRelativePos
float - The waypoint relative position of the markerendWaypointRelativePos
float - The end waypoint relative position of the event's zone. A value of -1.0 indicates that this event is not zoned.command
Command - The command that should be triggered at this marker. Can be None
Signature
EventMarker.fromJson
Signature
GoalEndState
Describes the goal end state of the robot when finishing a path
Arguments
velocity
float - The goal end velocity (M/S)rotation
Rotation2d - The goal rotation
Signature
GoalEndState.fromJson
Signature
IdealStartingState
Describes the ideal starting state of the robot when finishing a path
Arguments
velocity
float - The ideal starting velocity (M/S)rotation
Rotation2d - The ideal starting rotation
Signature
IdealStartingState.fromJson
Signature
PathConstraints
Kinematic path following constraints
Arguments
maxVelocityMps
float - Max linear velocity (M/S)maxAccelerationMpsSq
float - Max linear acceleration (M/S^2)maxAngularVelocityRps
float - Max angular velocity (Rad/S)maxAngularAccelerationRpsSq
float - Max angular acceleration (Rad/S^2)nominalVoltage
float - Nominal battery voltage (Volts)unlimited
bool - Should the constraints be unlimited
Signature
PathConstraints.fromJson
Signature
PathConstraints.unlimitedConstraints
Signature
PathPlannerPath
Signature
class PathPlannerPath:
def __init__(
self,
waypoints: List[Waypoint],
constraints: PathConstraints,
ideal_starting_state: Union[IdealStartingState, None],
goal_end_state: GoalEndState,
holonomic_rotations: List[RotationTarget] = None,
point_towards_zones: List[PointTowardsZone] = None,
constraint_zones: List[ConstraintsZone] = None,
event_markers: List[EventMarker] = None,
is_reversed: bool = False,
): ...
See also
- ConstraintsZone
- EventMarker
- GoalEndState
- IdealStartingState
- PathConstraints
- PointTowardsZone
- RotationTarget
- Waypoint
PathPlannerPath.clearPathCache
Clear the cache of previously loaded paths.
Signature
PathPlannerPath().flipPath
Flip a path to the other side of the field, maintaining a global blue alliance origin
Returns
The flipped path
Signature
PathPlannerPath.fromChoreoTrajectory
Load a Choreo trajectory as a PathPlannerPath
Arguments
trajectory_name
- The name of the Choreo trajectory to load. This should be just the name of the trajectory. The trajectories must be located in the "deploy/choreo" directory.splitIndex
- The index of the split to use
Returns
PathPlannerPath created from the given Choreo trajectory file
Signature
@staticmethod
def fromChoreoTrajectory(
trajectory_name: str, splitIndex: int = None
) -> PathPlannerPath: ...
PathPlannerPath.fromPathFile
Load a path from a path file in storage
Arguments
path_name
- The name of the path to load
Returns
PathPlannerPath created from the given file name
Signature
PathPlannerPath.fromPathPoints
Create a path with pre-generated points. This should already be a smooth path.
Arguments
path_points
- Path points along the smooth curve of the pathconstraints
- The global constraints of the pathgoal_end_state
- The goal end state of the path
Returns
A PathPlannerPath following the given pathpoints
Signature
@staticmethod
def fromPathPoints(
path_points: List[PathPoint],
constraints: PathConstraints,
goal_end_state: GoalEndState,
) -> PathPlannerPath: ...
See also
PathPlannerPath().generateTrajectory
Generate a trajectory for this path.
Arguments
starting_speeds
- The robot-relative starting speeds.starting_rotation
- The starting rotation of the robot.config
- The robot configuration
Returns
The generated trajectory.
Signature
def generateTrajectory(
self,
starting_speeds: ChassisSpeeds,
starting_rotation: Rotation2d,
config: RobotConfig,
) -> PathPlannerTrajectory: ...
PathPlannerPath().getAllPathPoints
Get all the path points in this path
Returns
Path points in the path
Signature
See also
PathPlannerPath().getConstraintZones
Get the constraint zones for this path
Returns
List of this path's constraint zones
Signature
See also
PathPlannerPath().getEventMarkers
Get all the event markers for this path
Returns
The event markers for this path
Signature
See also
PathPlannerPath().getGlobalConstraints
Get the global constraints for this path
Returns
Global constraints that apply to this path
Signature
See also
PathPlannerPath().getGoalEndState
Get the goal end state of this path
Returns
The goal end state
Signature
See also
PathPlannerPath().getIdealStartingState
Get the ideal starting state of this path
Returns
The ideal starting state
Signature
See also
PathPlannerPath().getIdealTrajectory
If possible, get the ideal trajectory for this path. This trajectory can be used if the robot is currently near the start of the path and at the ideal starting state. If there is no ideal starting state, there can be no ideal trajectory.
Arguments
robotConfig
- The config to generate the ideal trajectory with if it has not already been generated
Returns
The ideal trajectory if it exists, None otherwise
Signature
PathPlannerPath().getInitialHeading
Get the initial heading, or direction of travel, at the start of the path.
Returns
Initial heading
Signature
PathPlannerPath().getPathPoses
Get a list of poses representing every point in this path. This can be used to display a path on a field 2d widget, for example.
Returns
List of poses for each point in this path
Signature
PathPlannerPath().getPoint
Get a specific point along this path
Arguments
index
- Index of the point to get
Returns
The point at the given index
Signature
See also
PathPlannerPath().getPointTowardsZones
Get the point towards zones for this path
Returns
List of this path's point towards zones
Signature
See also
PathPlannerPath().getRotationTargets
Get the rotation targets for this path
Returns
List of this path's rotation targets
Signature
See also
PathPlannerPath().getStartingDifferentialPose
Get the differential pose for the start point of this path
Returns
Pose at the path's starting point
Signature
PathPlannerPath().getStartingHolonomicPose
Get the holonomic pose for the start point of this path. If the path does not have an ideal starting state, this will return None.
Returns
The ideal starting pose if an ideal starting state is present, None otherwise
Signature
PathPlannerPath().getWaypoints
Get the waypoints for this path
Returns
List of this path's waypoints
Signature
See also
PathPlannerPath().isChoreoPath
Check if this path is loaded from a Choreo trajectory
Returns
True if this path is from choreo, false otherwise
Signature
PathPlannerPath().isReversed
Should the path be followed reversed (differential drive only)
Returns
True if reversed
Signature
PathPlannerPath().numPoints
Get the number of points in this path
Returns
Number of points in the path
Signature
PathPlannerPath.waypointsFromPoses
Create the bezier waypoints necessary to create a path using a list of poses
Arguments
poses
- List of poses. Each pose represents one waypoint.
Returns
Bézier curve waypoints
Signature
See also
PathPoint
A point along a pathplanner path
Arguments
position
Translation2d - Position of the pointrotationTarget
RotationTarget - Rotation target at this pointconstraints
PathConstraints - The constraints at this point
Signature
PathPoint().flip
Signature
PointTowardsZone
A zone on a path that will force the robot to point towards a position on the field
Arguments
name
str - The name of this zone. Used for point towards zone triggerstargetPosition
Translation2d - The target field position in metersminWaypointRelativePos
float - Starting position of the zonemaxWaypointRelativePos
float - End position of the zonerotationOffset
Rotation2d - A rotation offset to add on top of the angle to the target position. For example, if you want the robot to point away from the target position, use a rotation offset of 180 degrees
Signature
PointTowardsZone().flip
Flip this point towards zone to the other side of the field, maintaining a blue alliance origin
Returns
The flipped zone
Signature
PointTowardsZone.fromJson
Signature
RotationTarget
A target holonomic rotation at a position along a path
Arguments
waypointRelativePosition
float - Waypoint relative position of this targettarget
Rotation2d - Target rotation
Signature
RotationTarget.fromJson
Signature
Waypoint
Signature
Waypoint.autoControlPoints
Create a waypoint with auto calculated control points based on the positions of adjacent waypoints. This is used internally, and you probably shouldn't use this.
Arguments
- anchor - The anchor point of the waypoint to create
heading
- The heading of this waypointprevAnchor
- The position of the previous anchor point. This can be None for the start pointnextAnchor
- The position of the next anchor point. This can be None for the end point
Returns
Waypoint with auto calculated control points
Signature
@staticmethod
def autoControlPoints(
anchor: Translation2d,
heading: Rotation2d,
prevAnchor: Union[Translation2d, None],
nextAnchor: Union[Translation2d, None],
) -> Waypoint: ...
Waypoint().flip
Flip this waypoint to the other side of the field, maintaining a blue alliance origin
Returns
The flipped waypoint
Signature
Waypoint.fromJson
Create a waypoint from JSON
Arguments
waypointJson
- JSON object representing a waypoint
Returns
The waypoint created from JSON