Package com.pathplanner.lib.pathfinding
Class Pathfinding
java.lang.Object
com.pathplanner.lib.pathfinding.Pathfinding
Static class for interacting with the chosen pathfinding implementation from the pathfinding
commands
-
Constructor Summary
-
Method Summary
Modifier and TypeMethodDescriptionstatic void
Ensure that a pathfinding implementation has been chosen.static PathPlannerPath
getCurrentPath
(PathConstraints constraints, GoalEndState goalEndState) Get the most recently calculated pathstatic boolean
Get if a new path has been calculated since the last time a path was retrievedstatic void
setDynamicObstacles
(List<Pair<Translation2d, Translation2d>> obs, Translation2d currentRobotPos) Set the dynamic obstacles that should be avoided while pathfinding.static void
setGoalPosition
(Translation2d goalPosition) Set the goal position to pathfind tostatic void
setPathfinder
(Pathfinder pathfinder) Set the pathfinder that should be used by the path following commandsstatic void
setStartPosition
(Translation2d startPosition) Set the start position to pathfind from
-
Constructor Details
-
Pathfinding
public Pathfinding()
-
-
Method Details
-
setPathfinder
Set the pathfinder that should be used by the path following commands- Parameters:
pathfinder
- The pathfinder to use
-
ensureInitialized
public static void ensureInitialized()Ensure that a pathfinding implementation has been chosen. If not, set it to the default. -
isNewPathAvailable
public static boolean 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
-
getCurrentPath
public static PathPlannerPath getCurrentPath(PathConstraints constraints, GoalEndState goalEndState) Get the most recently calculated path- Parameters:
constraints
- The path constraints to use when creating the pathgoalEndState
- The goal end state to use when creating the path- Returns:
- The PathPlannerPath created from the points calculated by the pathfinder
-
setStartPosition
Set the start position to pathfind from- Parameters:
startPosition
- Start position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.
-
setGoalPosition
Set the goal position to pathfind to- Parameters:
goalPosition
- Goal position on the field. f this is within an obstacle it will be moved to the nearest non-obstacle node.
-
setDynamicObstacles
public static void setDynamicObstacles(List<Pair<Translation2d, Translation2d>> obs, Translation2d currentRobotPos) Set the dynamic obstacles that should be avoided while pathfinding.- Parameters:
obs
- A List of Translation2d pairs representing obstacles. Each Translation2d represents opposite corners of a bounding box.currentRobotPos
- The current position of the robot. This is needed to change the start position of the path if the robot is now within an obstacle.
-