Package frc.robot.util
Class LocalADStarAK
java.lang.Object
frc.robot.util.LocalADStarAK
- All Implemented Interfaces:
Pathfinder
AdvantageKit wrapper for the PathPlanner LocalADStar pathfinder.
This wrapper handles logging path data to AdvantageKit, allowing for recording, replaying, and analyzing pathfinding results in simulation or via log files.
-
Constructor Summary
Constructors -
Method Summary
Modifier and TypeMethodDescriptiongetCurrentPath(PathConstraints constraints, GoalEndState goalEndState) Retrieves the most recently calculated path.booleanChecks if a new path has been calculated since the last retrieval.voidsetDynamicObstacles(List<Pair<Translation2d, Translation2d>> obs, Translation2d currentRobotPos) Sets the dynamic obstacles that should be avoided while pathfinding.voidsetGoalPosition(Translation2d goalPosition) Sets the goal position to pathfind to.voidsetStartPosition(Translation2d startPosition) Sets the start position to pathfind from.
-
Constructor Details
-
LocalADStarAK
public LocalADStarAK()
-
-
Method Details
-
isNewPathAvailable
public boolean isNewPathAvailable()Checks if a new path has been calculated since the last retrieval.- Specified by:
isNewPathAvailablein interfacePathfinder- Returns:
- True if a new path is available.
-
getCurrentPath
Retrieves the most recently calculated path.- Specified by:
getCurrentPathin interfacePathfinder- 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, or null.
-
setStartPosition
Sets the start position to pathfind from.- Specified by:
setStartPositionin interfacePathfinder- Parameters:
startPosition- Start position on the field.
-
setGoalPosition
Sets the goal position to pathfind to.- Specified by:
setGoalPositionin interfacePathfinder- Parameters:
goalPosition- Goal position on the field.
-
setDynamicObstacles
public void setDynamicObstacles(List<Pair<Translation2d, Translation2d>> obs, Translation2d currentRobotPos) Sets the dynamic obstacles that should be avoided while pathfinding.- Specified by:
setDynamicObstaclesin interfacePathfinder- Parameters:
obs- A List of Translation2d pairs representing obstacles.currentRobotPos- The current position of the robot.
-