Skip to content

Path

pathplannerlib Index / Pathplannerlib / Path

Auto-generated documentation for pathplannerlib.path module.

ConstraintsZone

Show source in path.py:91

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().forSegmentIndex

Show source in path.py:131

Transform the positions of this zone for a given segment number.

For example, a zone from [1.5, 2.0] for the segment 1 will have the positions [0.5, 1.0]

Arguments

  • segment_index - The segment index to transform positions for

Returns

The transformed zone

Signature

def forSegmentIndex(self, segment_index: int) -> ConstraintsZone: ...

ConstraintsZone.fromJson

Show source in path.py:104

Signature

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

ConstraintsZone().isWithinZone

Show source in path.py:112

Get if a given waypoint relative position is within this zone

Arguments

  • t - Waypoint relative position

Returns

True if given position is within this zone

Signature

def isWithinZone(self, t: float) -> bool: ...

ConstraintsZone().overlapsRange

Show source in path.py:121

Get if this zone overlaps a given range

Arguments

  • min_pos - The minimum waypoint relative position of the range
  • max_pos - The maximum waypoint relative position of the range

Returns

True if any part of this zone is within the given range

Signature

def overlapsRange(self, min_pos: float, max_pos: float) -> bool: ...

EventMarker

Show source in path.py:194

Position along the path that will trigger a command when reached

Arguments

  • waypointRelativePos float - The waypoint relative position of the marker
  • command Command - The command that should be triggered at this marker

Signature

class EventMarker: ...

EventMarker.fromJson

Show source in path.py:205

Signature

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

GoalEndState

Show source in path.py:59

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
  • rotateFast bool - Should the robot reach the rotation as fast as possible

Signature

class GoalEndState: ...

GoalEndState.fromJson

Show source in path.py:72

Signature

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

PathConstraints

Show source in path.py:22

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)

Signature

class PathConstraints: ...

PathConstraints.fromJson

Show source in path.py:37

Signature

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

PathPlannerPath

Show source in path.py:293

Signature

class PathPlannerPath:
    def __init__(
        self,
        bezier_points: List[Translation2d],
        constraints: PathConstraints,
        goal_end_state: GoalEndState,
        holonomic_rotations: List[RotationTarget] = [],
        constraint_zones: List[ConstraintsZone] = [],
        event_markers: List[EventMarker] = [],
        is_reversed: bool = False,
        preview_starting_rotation: Rotation2d = Rotation2d(),
    ): ...

See also

PathPlannerPath.bezierFromPoses

Show source in path.py:447

Create the bezier points necessary to create a path using a list of poses

Arguments

  • poses - List of poses. Each pose represents one waypoint.

Returns

Bezier points

Signature

@staticmethod
def bezierFromPoses(poses: List[Pose2d]) -> List[Translation2d]: ...

PathPlannerPath().flipPath

Show source in path.py:801

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:373

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.

Returns

PathPlannerPath created from the given Choreo trajectory file

Signature

@staticmethod
def fromChoreoTrajectory(trajectory_name: str) -> PathPlannerPath: ...

PathPlannerPath.fromPathFile

Show source in path.py:359

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:342

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().getAllPathPoints

Show source in path.py:484

Get all the path points in this path

Returns

Path points in the path

Signature

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

See also

PathPlannerPath().getEventMarkers

Show source in path.py:525

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:509

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:517

Get the goal end state of this path

Returns

The goal end state

Signature

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

See also

PathPlannerPath().getPathPoses

Show source in path.py:855

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:500

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().getPreviewStartingHolonomicPose

Show source in path.py:555

Get the starting pose for the holomonic path based on the preview settings. NOTE: This should only be used for the first path you are running, and only if you are not using an auto mode file. Using this pose to reset the robots pose between sequential paths will cause a loss of accuracy.

Returns

Pose at the path's starting point

Signature

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

PathPlannerPath().getStartingDifferentialPose

Show source in path.py:541

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().getTrajectory

Show source in path.py:788

Generate a trajectory for this path.

Arguments

  • starting_speeds - The robot-relative starting speeds.
  • starting_rotation - The starting rotation of the robot.

Returns

The generated trajectory.

Signature

def getTrajectory(
    self, starting_speeds: ChassisSpeeds, starting_rotation: Rotation2d
) -> PathPlannerTrajectory: ...

PathPlannerPath().isChoreoPath

Show source in path.py:780

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:533

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:492

Get the number of points in this path

Returns

Number of points in the path

Signature

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

PathPlannerPath().replan

Show source in path.py:565

Replan this path based on the current robot position and speeds

Arguments

  • starting_pose - New starting pose for the replanned path
  • current_speeds - Current chassis speeds of the robot

Returns

The replanned path

Signature

def replan(
    self, starting_pose: Pose2d, current_speeds: ChassisSpeeds
) -> PathPlannerPath: ...

PathPoint

Show source in path.py:219

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: ...

PathSegment

Show source in path.py:245

Signature

class PathSegment:
    def __init__(
        self,
        p1: Translation2d,
        p2: Translation2d,
        p3: Translation2d,
        p4: Translation2d,
        target_holonomic_rotations: List[RotationTarget] = [],
        constraint_zones: List[ConstraintsZone] = [],
        end_segment: bool = False,
    ): ...

See also

RotationTarget

Show source in path.py:151

A target holonomic rotation at a position along a path

Arguments

  • waypointRelativePosition float - Waypoint relative position of this target
  • target Rotation2d - Target rotation
  • rotateFast bool - Should the robot reach the rotation as fast as possible

Signature

class RotationTarget: ...

RotationTarget().forSegmentIndex

Show source in path.py:175

Transform the position of this target for a given segment number.

For example, a target with position 1.5 for the segment 1 will have the position 0.5

Arguments

  • segment_index - The segment index to transform position for

Returns

The transformed target

Signature

def forSegmentIndex(self, segment_index: int) -> RotationTarget: ...

RotationTarget.fromJson

Show source in path.py:164

Signature

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