PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::Pathfinder Class Referenceabstract
Inheritance diagram for pathplanner::Pathfinder:
pathplanner::LocalADStar

Public Member Functions

virtual bool isNewPathAvailable ()=0
 
virtual std::shared_ptr< PathPlannerPathgetCurrentPath (PathConstraints constraints, GoalEndState goalEndState)=0
 
virtual void setStartPosition (const frc::Translation2d &startPosition)=0
 
virtual void setGoalPosition (const frc::Translation2d &goalPosition)=0
 
virtual void setDynamicObstacles (const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &obs, const frc::Translation2d &currentRobotPos)=0
 

Member Function Documentation

◆ getCurrentPath()

virtual std::shared_ptr< PathPlannerPath > pathplanner::Pathfinder::getCurrentPath ( PathConstraints  constraints,
GoalEndState  goalEndState 
)
pure virtual

Get the most recently calculated path

Parameters
constraintsThe path constraints to use when creating the path
goalEndStateThe goal end state to use when creating the path
Returns
The PathPlannerPath created from the points calculated by the pathfinder

Implemented in pathplanner::LocalADStar.

◆ isNewPathAvailable()

virtual bool pathplanner::Pathfinder::isNewPathAvailable ( )
pure virtual

Get if a new path has been calculated since the last time a path was retrieved

Returns
True if a new path is available

Implemented in pathplanner::LocalADStar.

◆ setDynamicObstacles()

virtual void pathplanner::Pathfinder::setDynamicObstacles ( const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &  obs,
const frc::Translation2d &  currentRobotPos 
)
pure virtual

Set the dynamic obstacles that should be avoided while pathfinding.

Parameters
obsA List of Translation2d pairs representing obstacles. Each Translation2d represents opposite corners of a bounding box.
currentRobotPosThe current position of the robot. This is needed to change the start position of the path to properly avoid obstacles

Implemented in pathplanner::LocalADStar.

◆ setGoalPosition()

virtual void pathplanner::Pathfinder::setGoalPosition ( const frc::Translation2d &  goalPosition)
pure virtual

Set the goal position to pathfind to

Parameters
goalPositionGoal position on the field. f this is within an obstacle it will be moved to the nearest non-obstacle node.

Implemented in pathplanner::LocalADStar.

◆ setStartPosition()

virtual void pathplanner::Pathfinder::setStartPosition ( const frc::Translation2d &  startPosition)
pure virtual

Set the start position to pathfind from

Parameters
startPositionStart position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.

Implemented in pathplanner::LocalADStar.


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