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

Public Member Functions

bool isNewPathAvailable () override
 
std::shared_ptr< PathPlannerPathgetCurrentPath (PathConstraints constraints, GoalEndState goalEndState) override
 
void setStartPosition (const frc::Translation2d &start) override
 
void setGoalPosition (const frc::Translation2d &goal) override
 
void setDynamicObstacles (const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &obs, const frc::Translation2d &currentRobotPos) override
 
GridPosition getGridPos (const frc::Translation2d &pos)
 
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()

std::shared_ptr< PathPlannerPath > LocalADStar::getCurrentPath ( PathConstraints  constraints,
GoalEndState  goalEndState 
)
overridevirtual

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

Implements pathplanner::Pathfinder.

◆ isNewPathAvailable()

bool pathplanner::LocalADStar::isNewPathAvailable ( )
inlineoverridevirtual

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

Returns
True if a new path is available

Implements pathplanner::Pathfinder.

◆ setDynamicObstacles()

void LocalADStar::setDynamicObstacles ( const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &  obs,
const frc::Translation2d &  currentRobotPos 
)
overridevirtual

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

Implements pathplanner::Pathfinder.

◆ setGoalPosition()

void LocalADStar::setGoalPosition ( const frc::Translation2d &  goalPosition)
overridevirtual

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.

Implements pathplanner::Pathfinder.

◆ setStartPosition()

void LocalADStar::setStartPosition ( const frc::Translation2d &  startPosition)
overridevirtual

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.

Implements pathplanner::Pathfinder.


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