Class PathPlannerPath

java.lang.Object
com.pathplanner.lib.path.PathPlannerPath

public class PathPlannerPath extends Object
A PathPlanner path. NOTE: This is not a trajectory and isn't directly followed.
  • Field Details

    • name

      public String name
      Name of the path. Optional for using current path triggers on PathPlannerAuto
    • preventFlipping

      public boolean preventFlipping
      Set to true to prevent this path from being flipped (useful for OTF paths that already have the correct coords)
  • Constructor Details

    • PathPlannerPath

      public PathPlannerPath(List<Waypoint> waypoints, List<RotationTarget> holonomicRotations, List<PointTowardsZone> pointTowardsZones, List<ConstraintsZone> constraintZones, List<EventMarker> eventMarkers, PathConstraints globalConstraints, IdealStartingState idealStartingState, GoalEndState goalEndState, boolean reversed)
      Create a new path planner path
      Parameters:
      waypoints - List of waypoints representing the path. For on-the-fly paths, you likely want to use waypointsFromPoses to create these.
      holonomicRotations - List of rotation targets along the path
      pointTowardsZones - List of point towards zones along the path
      constraintZones - List of constraint zones along the path
      eventMarkers - List of event markers along the path
      globalConstraints - The global constraints of the path
      idealStartingState - The ideal starting state of the path. Can be null if unknown
      goalEndState - The goal end state of the path
      reversed - Should the robot follow the path reversed (differential drive only)
    • PathPlannerPath

      public PathPlannerPath(List<Waypoint> waypoints, PathConstraints constraints, IdealStartingState idealStartingState, GoalEndState goalEndState, boolean reversed)
      Simplified constructor to create a path with no rotation targets, constraint zones, or event markers.

      You likely want to use bezierFromPoses to create the waypoints.

      Parameters:
      waypoints - List of waypoints representing the path. For on-the-fly paths, you likely want to use waypointsFromPoses to create these.
      constraints - The global constraints of the path
      idealStartingState - The ideal starting state of the path. Can be null if unknown
      goalEndState - The goal end state of the path
      reversed - Should the robot follow the path reversed (differential drive only)
    • PathPlannerPath

      public PathPlannerPath(List<Waypoint> waypoints, PathConstraints constraints, IdealStartingState idealStartingState, GoalEndState goalEndState)
      Simplified constructor to create a path with no rotation targets, constraint zones, or event markers.
      Parameters:
      waypoints - List of waypoints representing the path. For on-the-fly paths, you likely want to use waypointsFromPoses to create these.
      constraints - The global constraints of the path
      idealStartingState - The ideal starting state of the path. Can be null if unknown
      goalEndState - The goal end state of the path
  • Method Details

    • fromPathPoints

      public static PathPlannerPath fromPathPoints(List<PathPoint> pathPoints, PathConstraints constraints, GoalEndState goalEndState)
      Create a path with pre-generated points. This should already be a smooth path.
      Parameters:
      pathPoints - Path points along the smooth curve of the path
      constraints - The global constraints of the path
      goalEndState - The goal end state of the path
      Returns:
      A PathPlannerPath following the given pathpoints
    • bezierFromPoses

      @Deprecated(forRemoval=true) public static List<Waypoint> bezierFromPoses(List<Pose2d> poses)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Renamed to waypointsFromPoses
      Create the bezier waypoints necessary to create a path using a list of poses
      Parameters:
      poses - List of poses. Each pose represents one waypoint.
      Returns:
      Bezier curve waypoints
    • bezierFromPoses

      @Deprecated(forRemoval=true) public static List<Waypoint> bezierFromPoses(Pose2d... poses)
      Deprecated, for removal: This API element is subject to removal in a future version.
      Renamed to waypointsFromPoses
      Create the bezier waypoints necessary to create a path using a list of poses
      Parameters:
      poses - List of poses. Each pose represents one waypoint.
      Returns:
      Bezier curve waypoints
    • waypointsFromPoses

      public static List<Waypoint> waypointsFromPoses(Pose2d... poses)
      Create the bezier waypoints necessary to create a path using a list of poses
      Parameters:
      poses - List of poses. Each pose represents one waypoint.
      Returns:
      Bezier curve waypoints
    • waypointsFromPoses

      public static List<Waypoint> waypointsFromPoses(List<Pose2d> poses)
      Create the bezier waypoints necessary to create a path using a list of poses
      Parameters:
      poses - List of poses. Each pose represents one waypoint.
      Returns:
      Bezier curve waypoints
    • hotReload

      public void hotReload(org.json.simple.JSONObject pathJson)
      Hot reload the path. This is used internally.
      Parameters:
      pathJson - Updated JSONObject for the path
    • fromPathFile

      public static PathPlannerPath fromPathFile(String pathName) throws IOException, org.json.simple.parser.ParseException, FileVersionException
      Load a path from a path file in storage
      Parameters:
      pathName - The name of the path to load
      Returns:
      PathPlannerPath created from the given file name
      Throws:
      IOException - if the file cannot be read
      FileNotFoundException - if the file cannot be found
      org.json.simple.parser.ParseException - If the JSON cannot be parsed
      FileVersionException - If the file version does not match the expected version
    • fromChoreoTrajectory

      public static PathPlannerPath fromChoreoTrajectory(String trajectoryName, int splitIndex) throws IOException, org.json.simple.parser.ParseException, FileVersionException
      Load a Choreo trajectory as a PathPlannerPath
      Parameters:
      trajectoryName - The name of the Choreo trajectory to load. This should be just the name of the trajectory.
      splitIndex - The index of the split to use
      Returns:
      PathPlannerPath created from the given Choreo trajectory and split index
      Throws:
      IOException - if the file cannot be read
      FileNotFoundException - if the file cannot be found
      org.json.simple.parser.ParseException - If the JSON cannot be parsed
      FileVersionException - If the file version does not match the expected version
    • fromChoreoTrajectory

      public static PathPlannerPath fromChoreoTrajectory(String trajectoryName) throws IOException, org.json.simple.parser.ParseException, FileVersionException
      Load a Choreo trajectory as a PathPlannerPath
      Parameters:
      trajectoryName - The name of the Choreo trajectory to load. This should be just the name of the trajectory. The trajectories must be located in the "deploy/choreo" directory.
      Returns:
      PathPlannerPath created from the given Choreo trajectory
      Throws:
      IOException - if the file cannot be read
      FileNotFoundException - if the file cannot be found
      org.json.simple.parser.ParseException - If the JSON cannot be parsed
      FileVersionException - If the file version does not match the expected version
    • clearCache

      public static void clearCache()
      Clear the cache of previously loaded paths.
    • getIdealTrajectory

      public Optional<PathPlannerTrajectory> getIdealTrajectory(RobotConfig robotConfig)
      If possible, get the ideal trajectory for this path. This trajectory can be used if the robot is currently near the start of the path and at the ideal starting state. If there is no ideal starting state, there can be no ideal trajectory.
      Parameters:
      robotConfig - The config to generate the ideal trajectory with if it has not already been generated
      Returns:
      An optional containing the ideal trajectory if it exists, an empty optional otherwise
    • getInitialHeading

      public Rotation2d getInitialHeading()
      Get the initial heading, or direction of travel, at the start of the path.
      Returns:
      Initial heading
    • getStartingDifferentialPose

      public Pose2d getStartingDifferentialPose()
      Get the differential pose for the start point of this path.
      Returns:
      Pose at the path's starting point
    • getStartingHolonomicPose

      public Optional<Pose2d> getStartingHolonomicPose()
      Get the holonomic pose for the start point of this path. If the path does not have an ideal starting state, this will return an empty optional.
      Returns:
      The ideal starting pose if an ideal starting state is present, empty optional otherwise
    • getWaypoints

      public List<Waypoint> getWaypoints()
      Get the waypoints for this path
      Returns:
      List of this path's waypoints
    • getRotationTargets

      public List<RotationTarget> getRotationTargets()
      Get the rotation targets for this path
      Returns:
      List of this path's rotation targets
    • getPointTowardsZones

      public List<PointTowardsZone> getPointTowardsZones()
      Get the point towards zones for this path
      Returns:
      List of this path's point towards zones
    • getConstraintZones

      public List<ConstraintsZone> getConstraintZones()
      Get the constraint zones for this path
      Returns:
      List of this path's constraint zones
    • getAllPathPoints

      public List<PathPoint> getAllPathPoints()
      Get all the path points in this path
      Returns:
      Path points in the path
    • numPoints

      public int numPoints()
      Get the number of points in this path
      Returns:
      Number of points in the path
    • getPoint

      public PathPoint getPoint(int index)
      Get a specific point along this path
      Parameters:
      index - Index of the point to get
      Returns:
      The point at the given index
    • getGlobalConstraints

      public PathConstraints getGlobalConstraints()
      Get the global constraints for this path
      Returns:
      Global constraints that apply to this path
    • getGoalEndState

      public GoalEndState getGoalEndState()
      Get the goal end state of this path
      Returns:
      The goal end state
    • getIdealStartingState

      public IdealStartingState getIdealStartingState()
      Get the ideal starting state of this path
      Returns:
      The ideal starting state
    • getEventMarkers

      public List<EventMarker> getEventMarkers()
      Get all the event markers for this path
      Returns:
      The event markers for this path
    • isReversed

      public boolean isReversed()
      Should the path be followed reversed (differential drive only)
      Returns:
      True if reversed
    • isChoreoPath

      public boolean isChoreoPath()
      Check if this path is loaded from a Choreo trajectory
      Returns:
      True if this path is from choreo, false otherwise
    • generateTrajectory

      public PathPlannerTrajectory generateTrajectory(ChassisSpeeds startingSpeeds, Rotation2d startingRotation, RobotConfig config)
      Generate a trajectory for this path.
      Parameters:
      startingSpeeds - The robot-relative starting speeds.
      startingRotation - The starting rotation of the robot.
      config - The robot configuration
      Returns:
      The generated trajectory.
    • flipPath

      public PathPlannerPath flipPath()
      Flip a path to the other side of the field, maintaining a global blue alliance origin
      Returns:
      The flipped path
    • getPathPoses

      public List<Pose2d> getPathPoses()
      Get a list of poses representing every point in this path. This can be used to display a path on a field 2d widget, for example.
      Returns:
      List of poses for each point in this path
    • equals

      public boolean equals(Object o)
      Overrides:
      equals in class Object
    • hashCode

      public int hashCode()
      Overrides:
      hashCode in class Object