Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.path.PathPlannerPath Class Reference

Public Member Functions

 PathPlannerPath (List< Translation2d > bezierPoints, List< RotationTarget > holonomicRotations, List< ConstraintsZone > constraintZones, List< EventMarker > eventMarkers, PathConstraints globalConstraints, GoalEndState goalEndState, boolean reversed, Rotation2d previewStartingRotation)
 
 PathPlannerPath (List< Translation2d > bezierPoints, List< RotationTarget > holonomicRotations, List< ConstraintsZone > constraintZones, List< EventMarker > eventMarkers, PathConstraints globalConstraints, GoalEndState goalEndState, boolean reversed)
 
 PathPlannerPath (List< Translation2d > bezierPoints, PathConstraints constraints, GoalEndState goalEndState, boolean reversed)
 
 PathPlannerPath (List< Translation2d > bezierPoints, PathConstraints constraints, GoalEndState goalEndState)
 
void hotReload (JSONObject pathJson)
 
Pose2d getStartingDifferentialPose ()
 
Pose2d getPreviewStartingHolonomicPose ()
 
PathConstraints getConstraintsForPoint (int idx)
 
List< PathPointgetAllPathPoints ()
 
int numPoints ()
 
PathPoint getPoint (int index)
 
PathConstraints getGlobalConstraints ()
 
GoalEndState getGoalEndState ()
 
List< EventMarkergetEventMarkers ()
 
boolean isReversed ()
 
PathPlannerPath replan (Pose2d startingPose, ChassisSpeeds currentSpeeds)
 
boolean isChoreoPath ()
 
PathPlannerTrajectory getTrajectory (ChassisSpeeds startingSpeeds, Rotation2d startingRotation)
 
PathPlannerPath flipPath ()
 
List< Pose2dgetPathPoses ()
 

Static Public Member Functions

static PathPlannerPath fromPathPoints (List< PathPoint > pathPoints, PathConstraints constraints, GoalEndState goalEndState)
 
static List< Translation2dbezierFromPoses (List< Pose2d > poses)
 
static List< Translation2dbezierFromPoses (Pose2d... poses)
 
static PathPlannerPath fromPathFile (String pathName)
 
static PathPlannerPath fromChoreoTrajectory (String trajectoryName)
 

Public Attributes

boolean preventFlipping = false
 

Detailed Description

A PathPlanner path. NOTE: This is not a trajectory and isn't directly followed.

Constructor & Destructor Documentation

◆ PathPlannerPath() [1/4]

com.pathplanner.lib.path.PathPlannerPath.PathPlannerPath ( List< Translation2d > bezierPoints,
List< RotationTarget > holonomicRotations,
List< ConstraintsZone > constraintZones,
List< EventMarker > eventMarkers,
PathConstraints globalConstraints,
GoalEndState goalEndState,
boolean reversed,
Rotation2d previewStartingRotation )

Create a new path planner path

Parameters
bezierPointsList of points representing the cubic Bezier curve of the path
holonomicRotationsList of rotation targets along the path
constraintZonesList of constraint zones along the path
eventMarkersList of event markers along the path
globalConstraintsThe global constraints of the path
goalEndStateThe goal end state of the path
reversedShould the robot follow the path reversed (differential drive only)
previewStartingRotationThe settings used for previews in the UI

◆ PathPlannerPath() [2/4]

com.pathplanner.lib.path.PathPlannerPath.PathPlannerPath ( List< Translation2d > bezierPoints,
List< RotationTarget > holonomicRotations,
List< ConstraintsZone > constraintZones,
List< EventMarker > eventMarkers,
PathConstraints globalConstraints,
GoalEndState goalEndState,
boolean reversed )

Create a new path planner path

Parameters
bezierPointsList of points representing the cubic Bezier curve of the path
holonomicRotationsList of rotation targets along the path
constraintZonesList of constraint zones along the path
eventMarkersList of event markers along the path
globalConstraintsThe global constraints of the path
goalEndStateThe goal end state of the path
reversedShould the robot follow the path reversed (differential drive only)

◆ PathPlannerPath() [3/4]

com.pathplanner.lib.path.PathPlannerPath.PathPlannerPath ( List< Translation2d > bezierPoints,
PathConstraints constraints,
GoalEndState goalEndState,
boolean reversed )

Simplified constructor to create a path with no rotation targets, constraint zones, or event markers.

You likely want to use bezierFromPoses to create the bezier points.

Parameters
bezierPointsList of points representing the cubic Bezier curve of the path
constraintsThe global constraints of the path
goalEndStateThe goal end state of the path
reversedShould the robot follow the path reversed (differential drive only)

◆ PathPlannerPath() [4/4]

com.pathplanner.lib.path.PathPlannerPath.PathPlannerPath ( List< Translation2d > bezierPoints,
PathConstraints constraints,
GoalEndState goalEndState )

Simplified constructor to create a path with no rotation targets, constraint zones, or event markers.

You likely want to use bezierFromPoses to create the bezier points.

Parameters
bezierPointsList of points representing the cubic Bezier curve of the path
constraintsThe global constraints of the path
goalEndStateThe goal end state of the path

Member Function Documentation

◆ bezierFromPoses() [1/2]

static List< Translation2d > com.pathplanner.lib.path.PathPlannerPath.bezierFromPoses ( List< Pose2d > poses)
static

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

Parameters
posesList of poses. Each pose represents one waypoint.
Returns
Bezier points

◆ bezierFromPoses() [2/2]

static List< Translation2d > com.pathplanner.lib.path.PathPlannerPath.bezierFromPoses ( Pose2d... poses)
static

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

Parameters
posesList of poses. Each pose represents one waypoint.
Returns
Bezier points

◆ flipPath()

PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.flipPath ( )

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

Returns
The flipped path

◆ fromChoreoTrajectory()

static PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.fromChoreoTrajectory ( String trajectoryName)
static

Load a Choreo trajectory as a PathPlannerPath

Parameters
trajectoryNameThe 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

◆ fromPathFile()

static PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.fromPathFile ( String pathName)
static

Load a path from a path file in storage

Parameters
pathNameThe name of the path to load
Returns
PathPlannerPath created from the given file name

◆ fromPathPoints()

static PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.fromPathPoints ( List< PathPoint > pathPoints,
PathConstraints constraints,
GoalEndState goalEndState )
static

Create a path with pre-generated points. This should already be a smooth path.

Parameters
pathPointsPath points along the smooth curve of the path
constraintsThe global constraints of the path
goalEndStateThe goal end state of the path
Returns
A PathPlannerPath following the given pathpoints

◆ getAllPathPoints()

List< PathPoint > com.pathplanner.lib.path.PathPlannerPath.getAllPathPoints ( )

Get all the path points in this path

Returns
Path points in the path

◆ getConstraintsForPoint()

PathConstraints com.pathplanner.lib.path.PathPlannerPath.getConstraintsForPoint ( int idx)

Get the constraints for a point along the path

Parameters
idxIndex of the point to get constraints for
Returns
The constraints that should apply to the point

◆ getEventMarkers()

List< EventMarker > com.pathplanner.lib.path.PathPlannerPath.getEventMarkers ( )

Get all the event markers for this path

Returns
The event markers for this path

◆ getGlobalConstraints()

PathConstraints com.pathplanner.lib.path.PathPlannerPath.getGlobalConstraints ( )

Get the global constraints for this path

Returns
Global constraints that apply to this path

◆ getGoalEndState()

GoalEndState com.pathplanner.lib.path.PathPlannerPath.getGoalEndState ( )

Get the goal end state of this path

Returns
The goal end state

◆ getPathPoses()

List< Pose2d > com.pathplanner.lib.path.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

◆ getPoint()

PathPoint com.pathplanner.lib.path.PathPlannerPath.getPoint ( int index)

Get a specific point along this path

Parameters
indexIndex of the point to get
Returns
The point at the given index

◆ getPreviewStartingHolonomicPose()

Pose2d com.pathplanner.lib.path.PathPlannerPath.getPreviewStartingHolonomicPose ( )

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

◆ getStartingDifferentialPose()

Pose2d com.pathplanner.lib.path.PathPlannerPath.getStartingDifferentialPose ( )

Get the differential pose for the start point of this path

Returns
Pose at the path's starting point

◆ getTrajectory()

PathPlannerTrajectory com.pathplanner.lib.path.PathPlannerPath.getTrajectory ( ChassisSpeeds startingSpeeds,
Rotation2d startingRotation )

Generate a trajectory for this path.

Parameters
startingSpeedsThe robot-relative starting speeds.
startingRotationThe starting rotation of the robot.
Returns
The generated trajectory.

◆ hotReload()

void com.pathplanner.lib.path.PathPlannerPath.hotReload ( JSONObject pathJson)

Hot reload the path. This is used internally.

Parameters
pathJsonUpdated JSONObject for the path

◆ isChoreoPath()

boolean com.pathplanner.lib.path.PathPlannerPath.isChoreoPath ( )

Check if this path is loaded from a Choreo trajectory

Returns
True if this path is from choreo, false otherwise

◆ isReversed()

boolean com.pathplanner.lib.path.PathPlannerPath.isReversed ( )

Should the path be followed reversed (differential drive only)

Returns
True if reversed

◆ numPoints()

int com.pathplanner.lib.path.PathPlannerPath.numPoints ( )

Get the number of points in this path

Returns
Number of points in the path

◆ replan()

PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.replan ( Pose2d startingPose,
ChassisSpeeds currentSpeeds )

Replan this path based on the current robot position and speeds

Parameters
startingPoseNew starting pose for the replanned path
currentSpeedsCurrent chassis speeds of the robot
Returns
The replanned path

Member Data Documentation

◆ preventFlipping

boolean com.pathplanner.lib.path.PathPlannerPath.preventFlipping = false

Set to true to prevent this path from being flipped (useful for OTF paths that already have the correct coords)


The documentation for this class was generated from the following file: