PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::PathPlannerPath Class Reference
Inheritance diagram for pathplanner::PathPlannerPath:

Public Member Functions

 PathPlannerPath (std::vector< Waypoint > waypoints, std::vector< RotationTarget > rotationTargets, std::vector< PointTowardsZone > pointTowardsZones, std::vector< ConstraintsZone > constraintZones, std::vector< EventMarker > eventMarkers, PathConstraints globalConstraints, std::optional< IdealStartingState > idealStartingState, GoalEndState goalEndState, bool reversed)
 
 PathPlannerPath (std::vector< Waypoint > waypoints, PathConstraints constraints, std::optional< IdealStartingState > idealStartingState, GoalEndState goalEndState, bool reversed=false)
 
 PathPlannerPath (PathConstraints constraints, GoalEndState goalEndState)
 
void hotReload (const wpi::json &json)
 
frc::Pose2d getStartingDifferentialPose ()
 
std::optional< frc::Pose2d > getStartingHolonomicPose ()
 
constexpr const std::vector< PathPoint > & getAllPathPoints () const
 
size_t numPoints () const
 
const PathPointgetPoint (size_t index) const
 
std::optional< PathPlannerTrajectorygetIdealTrajectory (RobotConfig robotConfig)
 
frc::Rotation2d getInitialHeading () const
 
constexpr std::vector< Waypoint > & getWaypoints ()
 
constexpr std::vector< RotationTarget > & getRotationTargets ()
 
constexpr std::vector< PointTowardsZone > & getPointTowardsZones ()
 
constexpr std::vector< ConstraintsZone > & getConstraintZones ()
 
constexpr const PathConstraintsgetGlobalConstraints () const
 
constexpr const GoalEndStategetGoalEndState () const
 
constexpr const std::optional< IdealStartingState > & getIdealStartingState () const
 
constexpr std::vector< EventMarker > & getEventMarkers ()
 
constexpr bool isReversed () const
 
constexpr bool isChoreoPath () const
 
PathPlannerTrajectory generateTrajectory (frc::ChassisSpeeds startingSpeeds, frc::Rotation2d startingRotation, const RobotConfig &config)
 
std::shared_ptr< PathPlannerPathflipPath ()
 
std::shared_ptr< PathPlannerPathmirrorPath ()
 
std::vector< frc::Pose2d > getPathPoses () const
 

Static Public Member Functions

static std::vector< WaypointwaypointsFromPoses (std::vector< frc::Pose2d > poses)
 
static std::vector< WaypointbezierFromPoses (std::vector< frc::Pose2d > poses)
 
static std::shared_ptr< PathPlannerPathfromPathFile (std::string pathName)
 
static std::shared_ptr< PathPlannerPathfromChoreoTrajectory (std::string trajectoryName)
 
static std::shared_ptr< PathPlannerPathfromChoreoTrajectory (std::string trajectoryName, size_t splitIndex)
 
static std::shared_ptr< PathPlannerPathfromPathPoints (std::vector< PathPoint > pathPoints, PathConstraints globalConstraints, GoalEndState goalEndState)
 
static void clearPathCache ()
 

Public Attributes

std::string name
 
bool preventFlipping = false
 

Constructor & Destructor Documentation

◆ PathPlannerPath() [1/3]

PathPlannerPath::PathPlannerPath ( std::vector< Waypoint waypoints,
std::vector< RotationTarget rotationTargets,
std::vector< PointTowardsZone pointTowardsZones,
std::vector< ConstraintsZone constraintZones,
std::vector< EventMarker eventMarkers,
PathConstraints  globalConstraints,
std::optional< IdealStartingState idealStartingState,
GoalEndState  goalEndState,
bool  reversed 
)

Create a new path planner path

Parameters
waypointsList of waypoints representing the path. For on-the-fly paths, you likely want to use waypointsFromPoses to create these.
holonomicRotationsList of rotation targets along the path
pointTowardsZonesList of point towards zones along the path
constraintZonesList of constraint zones along the path
eventMarkersList of event markers along the path
globalConstraintsThe global constraints of the path
idealStartingStateThe ideal starting state of the path. Can be nullopt if unknown
goalEndStateThe goal end state of the path
reversedShould the robot follow the path reversed (differential drive only)

◆ PathPlannerPath() [2/3]

pathplanner::PathPlannerPath::PathPlannerPath ( std::vector< Waypoint waypoints,
PathConstraints  constraints,
std::optional< IdealStartingState idealStartingState,
GoalEndState  goalEndState,
bool  reversed = false 
)
inline

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

Parameters
waypointsList of waypoints representing the path. For on-the-fly paths, you likely want to use waypointsFromPoses to create these.
constraintsThe global constraints of the path
idealStartingStateThe ideal starting state of the path. Can be nullopt if unknown
goalEndStateThe goal end state of the path
reversedShould the robot follow the path reversed (differential drive only)

◆ PathPlannerPath() [3/3]

PathPlannerPath::PathPlannerPath ( PathConstraints  constraints,
GoalEndState  goalEndState 
)

USED INTERNALLY. DO NOT USE!

Member Function Documentation

◆ bezierFromPoses()

static std::vector< Waypoint > pathplanner::PathPlannerPath::bezierFromPoses ( std::vector< frc::Pose2d >  poses)
inlinestatic

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

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

◆ clearPathCache()

static void pathplanner::PathPlannerPath::clearPathCache ( )
inlinestatic

Clear the cache of previously loaded paths.

◆ flipPath()

std::shared_ptr< PathPlannerPath > PathPlannerPath::flipPath ( )

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

Returns
The flipped path

◆ fromChoreoTrajectory() [1/2]

std::shared_ptr< PathPlannerPath > PathPlannerPath::fromChoreoTrajectory ( std::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

◆ fromChoreoTrajectory() [2/2]

static std::shared_ptr< PathPlannerPath > pathplanner::PathPlannerPath::fromChoreoTrajectory ( std::string  trajectoryName,
size_t  splitIndex 
)
inlinestatic

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.
splitIndexThe index of the split to use
Returns
PathPlannerPath created from the given Choreo trajectory and split index

◆ fromPathFile()

std::shared_ptr< PathPlannerPath > PathPlannerPath::fromPathFile ( std::string  pathName)
static

Load a path from a path file in storage

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

◆ fromPathPoints()

std::shared_ptr< PathPlannerPath > PathPlannerPath::fromPathPoints ( std::vector< PathPoint pathPoints,
PathConstraints  globalConstraints,
GoalEndState  goalEndState 
)
static

Create a path planner path from pre-generated path points. This is used internally, and you likely should not use this

◆ getAllPathPoints()

constexpr const std::vector< PathPoint > & pathplanner::PathPlannerPath::getAllPathPoints ( ) const
inlineconstexpr

Get all the path points in this path

Returns
Path points in the path

◆ getConstraintZones()

constexpr std::vector< ConstraintsZone > & pathplanner::PathPlannerPath::getConstraintZones ( )
inlineconstexpr

Get the constraint zones for this path

Returns
vector of this path's constraint zones

◆ getEventMarkers()

constexpr std::vector< EventMarker > & pathplanner::PathPlannerPath::getEventMarkers ( )
inlineconstexpr

Get all the event markers for this path

Returns
The event markers for this path

◆ getGlobalConstraints()

constexpr const PathConstraints & pathplanner::PathPlannerPath::getGlobalConstraints ( ) const
inlineconstexpr

Get the global constraints for this path

Returns
Global constraints that apply to this path

◆ getGoalEndState()

constexpr const GoalEndState & pathplanner::PathPlannerPath::getGoalEndState ( ) const
inlineconstexpr

Get the goal end state of this path

Returns
The goal end state

◆ getIdealStartingState()

constexpr const std::optional< IdealStartingState > & pathplanner::PathPlannerPath::getIdealStartingState ( ) const
inlineconstexpr

Get the ideal starting state of this path

Returns
The ideal starting state

◆ getIdealTrajectory()

std::optional< PathPlannerTrajectory > PathPlannerPath::getIdealTrajectory ( RobotConfig  robotConfig)

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.

Parameters
robotConfigThe config to generate the ideal trajectory with if it has not already been generated
Returns
An optional containing the ideal trajectory if it exists, an empty optional otherwise

◆ getInitialHeading()

frc::Rotation2d pathplanner::PathPlannerPath::getInitialHeading ( ) const
inline

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

Returns
Initial heading

◆ getPathPoses()

std::vector< frc::Pose2d > pathplanner::PathPlannerPath::getPathPoses ( ) const
inline

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

const PathPoint & pathplanner::PathPlannerPath::getPoint ( size_t  index) const
inline

Get a specific point along this path

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

◆ getPointTowardsZones()

constexpr std::vector< PointTowardsZone > & pathplanner::PathPlannerPath::getPointTowardsZones ( )
inlineconstexpr

Get the point towards zones for this path

Returns
vector of this path's point towards zones

◆ getRotationTargets()

constexpr std::vector< RotationTarget > & pathplanner::PathPlannerPath::getRotationTargets ( )
inlineconstexpr

Get the rotation targets for this path

Returns
vector of this path's rotation targets

◆ getStartingDifferentialPose()

frc::Pose2d PathPlannerPath::getStartingDifferentialPose ( )

Get the differential pose for the start point of this path

Returns
Pose at the path's starting point

◆ getStartingHolonomicPose()

std::optional< frc::Pose2d > 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 nullopt.

Returns
The ideal starting pose if an ideal starting state is present, nullopt otherwise

◆ getWaypoints()

constexpr std::vector< Waypoint > & pathplanner::PathPlannerPath::getWaypoints ( )
inlineconstexpr

Get the waypoints for this path

Returns
vector of this path's waypoints

◆ isChoreoPath()

constexpr bool pathplanner::PathPlannerPath::isChoreoPath ( ) const
inlineconstexpr

Check if this path is loaded from a Choreo trajectory

Returns
True if this path is from choreo, false otherwise

◆ isReversed()

constexpr bool pathplanner::PathPlannerPath::isReversed ( ) const
inlineconstexpr

Should the path be followed reversed (differential drive only)

Returns
True if reversed

◆ mirrorPath()

std::shared_ptr< PathPlannerPath > PathPlannerPath::mirrorPath ( )

Mirror a path to the other side of the current alliance. For example, if this path is on the right of the blue alliance side of the field, it will be mirrored to the left of the blue alliance side of the field.

Returns
The mirrored path

◆ numPoints()

size_t pathplanner::PathPlannerPath::numPoints ( ) const
inline

Get the number of points in this path

Returns
Number of points in the path

◆ waypointsFromPoses()

std::vector< Waypoint > PathPlannerPath::waypointsFromPoses ( std::vector< frc::Pose2d >  poses)
static

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

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

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