Interface Pathfinder

All Known Implementing Classes:
LocalADStar

public interface Pathfinder
Interface for a pathfinder that can be used by PPLib's pathfinding commands
  • Method Details

    • isNewPathAvailable

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

      PathPlannerPath getCurrentPath(PathConstraints constraints, GoalEndState goalEndState)
      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
    • setStartPosition

      void setStartPosition(Translation2d startPosition)
      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.
    • setGoalPosition

      void setGoalPosition(Translation2d goalPosition)
      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.
    • setDynamicObstacles

      void setDynamicObstacles(List<Pair<Translation2d,Translation2d>> obs, Translation2d currentRobotPos)
      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