PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::Pathfinding Class Reference

Static Public Member Functions

static void setPathfinder (std::unique_ptr< Pathfinder > pathfinder)
 
static void ensureInitialized ()
 
static bool isNewPathAvailable ()
 
static std::shared_ptr< PathPlannerPathgetCurrentPath (PathConstraints constraints, GoalEndState goalEndState)
 
static void setStartPosition (const frc::Translation2d &startPosition)
 
static void setGoalPosition (const frc::Translation2d &goalPosition)
 
static void setDynamicObstacles (const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &obs, const frc::Translation2d &currentRobotPos)
 

Member Function Documentation

◆ ensureInitialized()

void Pathfinding::ensureInitialized ( )
static

Ensure that a pathfinding implementation has been chosen. If not, set it to the default.

◆ getCurrentPath()

static std::shared_ptr< PathPlannerPath > pathplanner::Pathfinding::getCurrentPath ( PathConstraints  constraints,
GoalEndState  goalEndState 
)
inlinestatic

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

◆ isNewPathAvailable()

static bool pathplanner::Pathfinding::isNewPathAvailable ( )
inlinestatic

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

Returns
True if a new path is available

◆ setDynamicObstacles()

static void pathplanner::Pathfinding::setDynamicObstacles ( const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > &  obs,
const frc::Translation2d &  currentRobotPos 
)
inlinestatic

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 if the robot is now within an obstacle.

◆ setGoalPosition()

static void pathplanner::Pathfinding::setGoalPosition ( const frc::Translation2d &  goalPosition)
inlinestatic

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.

◆ setPathfinder()

static void pathplanner::Pathfinding::setPathfinder ( std::unique_ptr< Pathfinder pathfinder)
inlinestatic

Set the pathfinder that should be used by the path following commands

Parameters
pathfinderThe pathfinder to use

◆ setStartPosition()

static void pathplanner::Pathfinding::setStartPosition ( const frc::Translation2d &  startPosition)
inlinestatic

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.

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