Class LocalADStar

java.lang.Object
com.pathplanner.lib.pathfinding.LocalADStar
All Implemented Interfaces:
Pathfinder

public class LocalADStar extends Object implements Pathfinder
Implementation of AD* running locally in a background thread

I would like to apologize to anyone trying to understand this code. The implementation I translated it from was much worse.

  • Constructor Details

    • LocalADStar

      public LocalADStar()
      Create a new pathfinder that runs AD* locally in a background thread
  • Method Details

    • isNewPathAvailable

      public boolean isNewPathAvailable()
      Get if a new path has been calculated since the last time a path was retrieved
      Specified by:
      isNewPathAvailable in interface Pathfinder
      Returns:
      True if a new path is available
    • getCurrentPath

      public PathPlannerPath getCurrentPath(PathConstraints constraints, GoalEndState goalEndState)
      Get the most recently calculated path
      Specified by:
      getCurrentPath in interface Pathfinder
      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
    • setStartPosition

      public void setStartPosition(Translation2d startPosition)
      Set the start position to pathfind from
      Specified by:
      setStartPosition in interface Pathfinder
      Parameters:
      startPosition - Start position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.
    • setGoalPosition

      public void setGoalPosition(Translation2d goalPosition)
      Set the goal position to pathfind to
      Specified by:
      setGoalPosition in interface Pathfinder
      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 void setDynamicObstacles(List<Pair<Translation2d,Translation2d>> obs, Translation2d currentRobotPos)
      Set the dynamic obstacles that should be avoided while pathfinding.
      Specified by:
      setDynamicObstacles in interface Pathfinder
      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.