Skip to content

Path

pathplannerlib Index / Pathplannerlib / Path

Auto-generated documentation for pathplannerlib.path module.

ConstraintsZone

Show source in path.py:135

A zone on a path with different kinematic constraints

Arguments

  • minWaypointPos float - Starting position of the zone
  • maxWaypointPos float - End position of the zone
  • constraints PathConstraints - PathConstraints to apply within the zone

Signature

class ConstraintsZone: ...

ConstraintsZone.fromJson

Show source in path.py:148

Signature

@staticmethod
def fromJson(json_dict: dict) -> ConstraintsZone: ...

EventMarker

Show source in path.py:229

Position along the path that will trigger a command when reached

Arguments

  • triggerName str - The name of the trigger this event marker will control
  • waypointRelativePos float - The waypoint relative position of the marker
  • endWaypointRelativePos 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

class EventMarker: ...

EventMarker.fromJson

Show source in path.py:245

Signature

@staticmethod
def fromJson(json_dict: dict) -> EventMarker: ...

GoalEndState

Show source in path.py:85

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

class GoalEndState: ...

GoalEndState.fromJson

Show source in path.py:96

Signature

@staticmethod
def fromJson(json_dict: dict) -> GoalEndState: ...

IdealStartingState

Show source in path.py:110

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

class IdealStartingState: ...

IdealStartingState.fromJson

Show source in path.py:121

Signature

@staticmethod
def fromJson(json_dict: dict) -> IdealStartingState: ...

PathConstraints

Show source in path.py:27

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

class PathConstraints: ...

PathConstraints.fromJson

Show source in path.py:46

Signature

@staticmethod
def fromJson(json_dict: dict) -> PathConstraints: ...

PathConstraints.unlimitedConstraints

Show source in path.py:63

Signature

@staticmethod
def unlimitedConstraints(nominalVoltage: float) -> PathConstraints: ...

PathPlannerPath

Show source in path.py:362

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

PathPlannerPath.clearPathCache

Show source in path.py:657

Clear the cache of previously loaded paths.

Signature

@staticmethod
def clearPathCache(): ...

PathPlannerPath().flipPath

Show source in path.py:817

Flip a path to the other side of the field, maintaining a global blue alliance origin

Returns

The flipped path

Signature

def flipPath(self) -> PathPlannerPath: ...

PathPlannerPath.fromChoreoTrajectory

Show source in path.py:478

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

Show source in path.py:450

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

@staticmethod
def fromPathFile(path_name: str) -> PathPlannerPath: ...

PathPlannerPath.fromPathPoints

Show source in path.py:433

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 path
  • constraints - The global constraints of the path
  • goal_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

Show source in path.py:802

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

Show source in path.py:700

Get all the path points in this path

Returns

Path points in the path

Signature

def getAllPathPoints(self) -> List[PathPoint]: ...

See also

PathPlannerPath().getConstraintZones

Show source in path.py:909

Get the constraint zones for this path

Returns

List of this path's constraint zones

Signature

def getConstraintZones(self) -> List[ConstraintsZone]: ...

See also

PathPlannerPath().getEventMarkers

Show source in path.py:749

Get all the event markers for this path

Returns

The event markers for this path

Signature

def getEventMarkers(self) -> List[EventMarker]: ...

See also

PathPlannerPath().getGlobalConstraints

Show source in path.py:725

Get the global constraints for this path

Returns

Global constraints that apply to this path

Signature

def getGlobalConstraints(self) -> PathConstraints: ...

See also

PathPlannerPath().getGoalEndState

Show source in path.py:733

Get the goal end state of this path

Returns

The goal end state

Signature

def getGoalEndState(self) -> GoalEndState: ...

See also

PathPlannerPath().getIdealStartingState

Show source in path.py:741

Get the ideal starting state of this path

Returns

The ideal starting state

Signature

def getIdealStartingState(self) -> Union[IdealStartingState, None]: ...

See also

PathPlannerPath().getIdealTrajectory

Show source in path.py:866

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

def getIdealTrajectory(
    self, robotConfig: RobotConfig
) -> Union[PathPlannerTrajectory, None]: ...

PathPlannerPath().getInitialHeading

Show source in path.py:858

Get the initial heading, or direction of travel, at the start of the path.

Returns

Initial heading

Signature

def getInitialHeading(self) -> Rotation2d: ...

PathPlannerPath().getPathPoses

Show source in path.py:849

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

def getPathPoses(self) -> List[Pose2d]: ...

PathPlannerPath().getPoint

Show source in path.py:716

Get a specific point along this path

Arguments

  • index - Index of the point to get

Returns

The point at the given index

Signature

def getPoint(self, index: int) -> PathPoint: ...

See also

PathPlannerPath().getPointTowardsZones

Show source in path.py:901

Get the point towards zones for this path

Returns

List of this path's point towards zones

Signature

def getPointTowardsZones(self) -> List[PointTowardsZone]: ...

See also

PathPlannerPath().getRotationTargets

Show source in path.py:893

Get the rotation targets for this path

Returns

List of this path's rotation targets

Signature

def getRotationTargets(self) -> List[RotationTarget]: ...

See also

PathPlannerPath().getStartingDifferentialPose

Show source in path.py:765

Get the differential pose for the start point of this path

Returns

Pose at the path's starting point

Signature

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

PathPlannerPath().getStartingHolonomicPose

Show source in path.py:779

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

def getStartingHolonomicPose(self) -> Union[Pose2d, None]: ...

PathPlannerPath().getWaypoints

Show source in path.py:885

Get the waypoints for this path

Returns

List of this path's waypoints

Signature

def getWaypoints(self) -> List[Waypoint]: ...

See also

PathPlannerPath().isChoreoPath

Show source in path.py:794

Check if this path is loaded from a Choreo trajectory

Returns

True if this path is from choreo, false otherwise

Signature

def isChoreoPath(self) -> bool: ...

PathPlannerPath().isReversed

Show source in path.py:757

Should the path be followed reversed (differential drive only)

Returns

True if reversed

Signature

def isReversed(self) -> bool: ...

PathPlannerPath().numPoints

Show source in path.py:708

Get the number of points in this path

Returns

Number of points in the path

Signature

def numPoints(self) -> int: ...

PathPlannerPath.waypointsFromPoses

Show source in path.py:666

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

@staticmethod
def waypointsFromPoses(poses: List[Pose2d]) -> List[Waypoint]: ...

See also

PathPoint

Show source in path.py:268

A point along a pathplanner path

Arguments

  • position Translation2d - Position of the point
  • rotationTarget RotationTarget - Rotation target at this point
  • constraints PathConstraints - The constraints at this point

Signature

class PathPoint: ...

PathPoint().flip

Show source in path.py:284

Signature

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

PointTowardsZone

Show source in path.py:189

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 triggers
  • targetPosition Translation2d - The target field position in meters
  • minWaypointRelativePos float - Starting position of the zone
  • maxWaypointRelativePos float - End position of the zone
  • rotationOffset 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

class PointTowardsZone: ...

PointTowardsZone().flip

Show source in path.py:217

Flip this point towards zone to the other side of the field, maintaining a blue alliance origin

Returns

The flipped zone

Signature

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

PointTowardsZone.fromJson

Show source in path.py:207

Signature

@staticmethod
def fromJson(json_dict: dict) -> PointTowardsZone: ...

RotationTarget

Show source in path.py:164

A target holonomic rotation at a position along a path

Arguments

  • waypointRelativePosition float - Waypoint relative position of this target
  • target Rotation2d - Target rotation

Signature

class RotationTarget: ...

RotationTarget.fromJson

Show source in path.py:175

Signature

@staticmethod
def fromJson(json_dict: dict) -> RotationTarget: ...

Waypoint

Show source in path.py:305

Signature

class Waypoint: ...

Waypoint.autoControlPoints

Show source in path.py:321

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 waypoint
  • prevAnchor - The position of the previous anchor point. This can be None for the start point
  • nextAnchor - 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

Show source in path.py:310

Flip this waypoint to the other side of the field, maintaining a blue alliance origin

Returns

The flipped waypoint

Signature

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

Waypoint.fromJson

Show source in path.py:346

Create a waypoint from JSON

Arguments

  • waypointJson - JSON object representing a waypoint

Returns

The waypoint created from JSON

Signature

@staticmethod
def fromJson(waypointJson: dict) -> Waypoint: ...