|
Robot Core Documentation
|
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) |
Static class for interacting with the chosen pathfinding implementation from the pathfinding commands
|
static |
Ensure that a pathfinding implementation has been chosen. If not, set it to the default.
|
static |
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 |
|
static |
Get if a new path has been calculated since the last time a path was retrieved
|
static |
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 if the robot is now within an obstacle. |
|
static |
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. |
|
static |
Set the pathfinder that should be used by the path following commands
| pathfinder | The pathfinder to use |
|
static |
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. |