|
Robot Core Documentation
|
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) |
Interface for a pathfinder that can be used by PPLib's pathfinding commands
| PathPlannerPath com.pathplanner.lib.pathfinding.Pathfinder.getCurrentPath | ( | PathConstraints | constraints, |
| GoalEndState | goalEndState ) |
Get the most recently calculated path
| constraints | The path constraints to use when creating the path |
| goalEndState | The goal end state to use when creating the path |
Implemented in com.pathplanner.lib.pathfinding.LocalADStar.
| boolean com.pathplanner.lib.pathfinding.Pathfinder.isNewPathAvailable | ( | ) |
Get if a new path has been calculated since the last time a path was retrieved
Implemented in com.pathplanner.lib.pathfinding.LocalADStar.
| void com.pathplanner.lib.pathfinding.Pathfinder.setDynamicObstacles | ( | List< Pair< Translation2d, Translation2d > > | obs, |
| Translation2d | currentRobotPos ) |
Set the dynamic obstacles that should be avoided while pathfinding.
| 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 to properly avoid obstacles |
Implemented in com.pathplanner.lib.pathfinding.LocalADStar.
| void com.pathplanner.lib.pathfinding.Pathfinder.setGoalPosition | ( | Translation2d | goalPosition | ) |
Set the goal position to pathfind to
| goalPosition | Goal 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.
| void com.pathplanner.lib.pathfinding.Pathfinder.setStartPosition | ( | Translation2d | startPosition | ) |
Set the start position to pathfind from
| startPosition | Start 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.