◆ getCurrentPath()
Get the most recently calculated path
- Parameters
-
constraints | The path constraints to use when creating the path |
goalEndState | The goal end state to use when creating the path |
- Returns
- The PathPlannerPath created from the points calculated by the pathfinder
Implements pathplanner::Pathfinder.
◆ isNewPathAvailable()
bool pathplanner::LocalADStar::isNewPathAvailable |
( |
| ) |
|
|
inlineoverridevirtual |
Get if a new path has been calculated since the last time a path was retrieved
- Returns
- True if a new path is available
Implements pathplanner::Pathfinder.
◆ setDynamicObstacles()
void LocalADStar::setDynamicObstacles |
( |
const std::vector< std::pair< frc::Translation2d, frc::Translation2d > > & |
obs, |
|
|
const frc::Translation2d & |
currentRobotPos |
|
) |
| |
|
overridevirtual |
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 to properly avoid obstacles |
Implements pathplanner::Pathfinder.
◆ setGoalPosition()
void LocalADStar::setGoalPosition |
( |
const frc::Translation2d & |
goalPosition | ) |
|
|
overridevirtual |
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. |
Implements pathplanner::Pathfinder.
◆ setStartPosition()
void LocalADStar::setStartPosition |
( |
const frc::Translation2d & |
startPosition | ) |
|
|
overridevirtual |
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. |
Implements pathplanner::Pathfinder.
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/pathfinding/LocalADStar.h
- src/main/native/cpp/pathplanner/lib/pathfinding/LocalADStar.cpp