Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.pathfinding.Pathfinder Interface Reference
Inheritance diagram for com.pathplanner.lib.pathfinding.Pathfinder:
com.pathplanner.lib.pathfinding.LocalADStar

Public Member Functions

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

Detailed Description

Interface for a pathfinder that can be used by PPLib's pathfinding commands

Member Function Documentation

◆ getCurrentPath()

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

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 com.pathplanner.lib.pathfinding.LocalADStar.

◆ isNewPathAvailable()

boolean com.pathplanner.lib.pathfinding.Pathfinder.isNewPathAvailable ( )

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 com.pathplanner.lib.pathfinding.LocalADStar.

◆ setDynamicObstacles()

void com.pathplanner.lib.pathfinding.Pathfinder.setDynamicObstacles ( List< Pair< Translation2d, Translation2d > > obs,
Translation2d currentRobotPos )

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 com.pathplanner.lib.pathfinding.LocalADStar.

◆ setGoalPosition()

void com.pathplanner.lib.pathfinding.Pathfinder.setGoalPosition ( Translation2d goalPosition)

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 com.pathplanner.lib.pathfinding.LocalADStar.

◆ setStartPosition()

void com.pathplanner.lib.pathfinding.Pathfinder.setStartPosition ( Translation2d startPosition)

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 com.pathplanner.lib.pathfinding.LocalADStar.


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