Class Pathfinding

java.lang.Object
com.pathplanner.lib.pathfinding.Pathfinding

public class Pathfinding extends Object
Static class for interacting with the chosen pathfinding implementation from the pathfinding commands
  • Constructor Details

    • Pathfinding

      public Pathfinding()
  • Method Details

    • setPathfinder

      public static void setPathfinder(Pathfinder pathfinder)
      Set the pathfinder that should be used by the path following commands
      Parameters:
      pathfinder - The pathfinder to use
    • ensureInitialized

      public static void ensureInitialized()
      Ensure that a pathfinding implementation has been chosen. If not, set it to the default.
    • isNewPathAvailable

      public static 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

      public static 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

      public static 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

      public static 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

      public static 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 if the robot is now within an obstacle.