Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.pathfinding.Pathfinding Class Reference

Static Public Member Functions

static void setPathfinder (Pathfinder pathfinder)
 
static void ensureInitialized ()
 
static boolean isNewPathAvailable ()
 
static PathPlannerPath getCurrentPath (PathConstraints constraints, GoalEndState goalEndState)
 
static void setStartPosition (Translation2d startPosition)
 
static void setGoalPosition (Translation2d goalPosition)
 
static void setDynamicObstacles (List< Pair< Translation2d, Translation2d > > obs, Translation2d currentRobotPos)
 

Detailed Description

Static class for interacting with the chosen pathfinding implementation from the pathfinding commands

Member Function Documentation

◆ ensureInitialized()

static void com.pathplanner.lib.pathfinding.Pathfinding.ensureInitialized ( )
static

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

◆ getCurrentPath()

static PathPlannerPath com.pathplanner.lib.pathfinding.Pathfinding.getCurrentPath ( PathConstraints constraints,
GoalEndState goalEndState )
static

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 boolean com.pathplanner.lib.pathfinding.Pathfinding.isNewPathAvailable ( )
static

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 com.pathplanner.lib.pathfinding.Pathfinding.setDynamicObstacles ( List< Pair< Translation2d, Translation2d > > obs,
Translation2d currentRobotPos )
static

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 com.pathplanner.lib.pathfinding.Pathfinding.setGoalPosition ( Translation2d goalPosition)
static

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 com.pathplanner.lib.pathfinding.Pathfinding.setPathfinder ( Pathfinder pathfinder)
static

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

Parameters
pathfinderThe pathfinder to use

◆ setStartPosition()

static void com.pathplanner.lib.pathfinding.Pathfinding.setStartPosition ( Translation2d startPosition)
static

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 file: