Robot Core Documentation
|
Static Public Member Functions | |
static PathPlannerPath | fromPathPoints (List< PathPoint > pathPoints, PathConstraints constraints, GoalEndState goalEndState) |
static List< Translation2d > | bezierFromPoses (List< Pose2d > poses) |
static List< Translation2d > | bezierFromPoses (Pose2d... poses) |
static PathPlannerPath | fromPathFile (String pathName) |
static PathPlannerPath | fromChoreoTrajectory (String trajectoryName) |
Public Attributes | |
boolean | preventFlipping = false |
A PathPlanner path. NOTE: This is not a trajectory and isn't directly followed.
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
bezierPoints | List of points representing the cubic Bezier curve of the path |
holonomicRotations | List of rotation targets along the path |
constraintZones | List of constraint zones along the path |
eventMarkers | List of event markers along the path |
globalConstraints | The global constraints of the path |
goalEndState | The goal end state of the path |
reversed | Should the robot follow the path reversed (differential drive only) |
previewStartingRotation | The settings used for previews in the UI |
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
bezierPoints | List of points representing the cubic Bezier curve of the path |
holonomicRotations | List of rotation targets along the path |
constraintZones | List of constraint zones along the path |
eventMarkers | List of event markers along the path |
globalConstraints | The global constraints of the path |
goalEndState | The goal end state of the path |
reversed | Should the robot follow the path reversed (differential drive only) |
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.
bezierPoints | List of points representing the cubic Bezier curve of the path |
constraints | The global constraints of the path |
goalEndState | The goal end state of the path |
reversed | Should the robot follow the path reversed (differential drive only) |
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.
bezierPoints | List of points representing the cubic Bezier curve of the path |
constraints | The global constraints of the path |
goalEndState | The goal end state of the path |
|
static |
Create the bezier points necessary to create a path using a list of poses
poses | List of poses. Each pose represents one waypoint. |
|
static |
Create the bezier points necessary to create a path using a list of poses
poses | List of poses. Each pose represents one waypoint. |
PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.flipPath | ( | ) |
Flip a path to the other side of the field, maintaining a global blue alliance origin
|
static |
Load a Choreo trajectory as a PathPlannerPath
trajectoryName | 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. |
|
static |
Load a path from a path file in storage
pathName | The name of the path to load |
|
static |
Create a path with pre-generated points. This should already be a smooth path.
pathPoints | Path points along the smooth curve of the path |
constraints | The global constraints of the path |
goalEndState | The goal end state of the path |
List< PathPoint > com.pathplanner.lib.path.PathPlannerPath.getAllPathPoints | ( | ) |
Get all the path points in this path
PathConstraints com.pathplanner.lib.path.PathPlannerPath.getConstraintsForPoint | ( | int | idx | ) |
Get the constraints for a point along the path
idx | Index of the point to get constraints for |
List< EventMarker > com.pathplanner.lib.path.PathPlannerPath.getEventMarkers | ( | ) |
Get all the event markers for this path
PathConstraints com.pathplanner.lib.path.PathPlannerPath.getGlobalConstraints | ( | ) |
Get the global constraints for this path
GoalEndState com.pathplanner.lib.path.PathPlannerPath.getGoalEndState | ( | ) |
Get the goal end state of this path
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.
PathPoint com.pathplanner.lib.path.PathPlannerPath.getPoint | ( | int | index | ) |
Get a specific point along this path
index | Index of the point to get |
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.
Pose2d com.pathplanner.lib.path.PathPlannerPath.getStartingDifferentialPose | ( | ) |
Get the differential pose for the start point of this path
PathPlannerTrajectory com.pathplanner.lib.path.PathPlannerPath.getTrajectory | ( | ChassisSpeeds | startingSpeeds, |
Rotation2d | startingRotation ) |
Generate a trajectory for this path.
startingSpeeds | The robot-relative starting speeds. |
startingRotation | The starting rotation of the robot. |
void com.pathplanner.lib.path.PathPlannerPath.hotReload | ( | JSONObject | pathJson | ) |
Hot reload the path. This is used internally.
pathJson | Updated JSONObject for the path |
boolean com.pathplanner.lib.path.PathPlannerPath.isChoreoPath | ( | ) |
Check if this path is loaded from a Choreo trajectory
boolean com.pathplanner.lib.path.PathPlannerPath.isReversed | ( | ) |
Should the path be followed reversed (differential drive only)
int com.pathplanner.lib.path.PathPlannerPath.numPoints | ( | ) |
Get the number of points in this path
PathPlannerPath com.pathplanner.lib.path.PathPlannerPath.replan | ( | Pose2d | startingPose, |
ChassisSpeeds | currentSpeeds ) |
Replan this path based on the current robot position and speeds
startingPose | New starting pose for the replanned path |
currentSpeeds | Current chassis speeds of the robot |
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)