Class Path

java.lang.Object
frc.robot.lib.BLine.Path

public class Path extends Object
Represents a path that a robot can follow, consisting of translation and rotation targets.

A Path is composed of Path.PathElement objects that define where the robot should go (translation targets) and what holonomic rotation it should have (rotation targets). These can be combined into waypoints for convenience.

Path Elements

Constraints

Paths support both path-specific constraints (Path.PathConstraints) and global default constraints (Path.DefaultGlobalConstraints). Path-specific constraints override global defaults when specified.

Creating Paths

Paths can be created programmatically or loaded from JSON files:


 // Programmatic path creation
 Path path = new Path(
     new Waypoint(new Pose2d(1, 1, Rotation2d.fromDegrees(0))),
     new TranslationTarget(2, 2),
     new RotationTarget(Rotation2d.fromDegrees(90), 0.5),
     new Waypoint(new Pose2d(3, 1, Rotation2d.fromDegrees(180)))
 );
 
 // Load from JSON file
 Path path = new Path("myPath");  // loads from deploy/autos/paths/myPath.json
 

Alliance Flipping

Paths can be flipped to the opposite alliance side using flip() and undoFlip(). This uses FlippingUtil to transform coordinates.

See Also:
  • Constructor Details

    • Path

      public Path(List<Path.PathElement> pathElements, Path.PathConstraints constraints, Path.DefaultGlobalConstraints defaultGlobalConstraints)
      Creates a new Path with the specified elements, constraints, and global defaults.
      Parameters:
      pathElements - The list of path elements defining the path
      constraints - Path-specific constraints (can be null for defaults)
      defaultGlobalConstraints - Global constraint defaults (can be null to load from config)
      Throws:
      IllegalArgumentException - if pathElements is null
      RuntimeException - if defaultGlobalConstraints is null and config cannot be loaded
    • Path

      public Path(Path.PathElement... pathElements)
      Creates a new Path from varargs path elements using current global defaults.
      Parameters:
      pathElements - The path elements defining the path
    • Path

      public Path(Path.PathConstraints constraints, Path.PathElement... pathElements)
      Creates a new Path with custom constraints from varargs path elements.
      Parameters:
      constraints - The path-specific constraints
      pathElements - The path elements defining the path
    • Path

      public Path(Path.PathElement[] pathElements, Path.PathConstraints constraints, Path.DefaultGlobalConstraints defaultGlobalConstraints)
      Creates a new Path from an array of path elements with constraints and global defaults.
      Parameters:
      pathElements - The array of path elements
      constraints - The path-specific constraints
      defaultGlobalConstraints - The global constraint defaults
    • Path

      public Path(List<Path.PathElement> pathElements)
      Creates a new Path from a list of path elements using current global defaults.
      Parameters:
      pathElements - The list of path elements
    • Path

      public Path(List<Path.PathElement> pathElements, Path.PathConstraints constraints)
      Creates a new Path from a list with custom constraints.
      Parameters:
      pathElements - The list of path elements
      constraints - The path-specific constraints
    • Path

      public Path(File autosDir, String pathFileName)
      Loads a Path from a JSON file in the specified autos directory.
      Parameters:
      autosDir - The directory containing the autos folder structure
      pathFileName - The name of the path file (without .json extension)
    • Path

      public Path(String pathFileName)
      Loads a Path from a JSON file in the default project root directory.

      The file is loaded from deploy/autos/paths/<pathFileName>.json.

      Parameters:
      pathFileName - The name of the path file (without .json extension)
  • Method Details

    • isValid

      public boolean isValid()
      Checks if this path passed validation.
      Returns:
      true if the path is valid and can be followed, false otherwise
    • getDefaultGlobalConstraints

      public Path.DefaultGlobalConstraints getDefaultGlobalConstraints()
      Gets a copy of the current default global constraints.
      Returns:
      A copy of the default global constraints
    • setDefaultGlobalConstraints

      public static void setDefaultGlobalConstraints(Path.DefaultGlobalConstraints defaultGlobalConstraints)
      Sets the default global constraints used by all paths.

      This is a static method that affects all subsequently created paths.

      Parameters:
      defaultGlobalConstraints - The new global constraints
      Throws:
      IllegalArgumentException - if defaultGlobalConstraints is null
    • getPathConstraints

      public Path.PathConstraints getPathConstraints()
      Gets a copy of this path's constraints.
      Returns:
      A copy of the path constraints
    • setPathConstraints

      public void setPathConstraints(Path.PathConstraints pathConstraints)
      Sets this path's constraints.
      Parameters:
      pathConstraints - The new path constraints
      Throws:
      IllegalArgumentException - if pathConstraints is null
    • getEndTranslationToleranceMeters

      public double getEndTranslationToleranceMeters()
      Gets the end translation tolerance, using path-specific if set, otherwise global default.
      Returns:
      The end translation tolerance in meters
    • getEndRotationToleranceDeg

      public double getEndRotationToleranceDeg()
      Gets the end rotation tolerance, using path-specific if set, otherwise global default.
      Returns:
      The end rotation tolerance in degrees
    • addPathElement

      public Path addPathElement(Path.PathElement pathElement)
      Adds a path element to the end of this path.
      Parameters:
      pathElement - The element to add
      Returns:
      This path for chaining
    • getElement

      public Path.PathElement getElement(int index)
      Gets a path element by index.
      Parameters:
      index - The index of the element
      Returns:
      The path element at the specified index
      Throws:
      IndexOutOfBoundsException - if index is out of range
    • setElement

      public void setElement(int index, Path.PathElement element)
      Sets a path element at the specified index.
      Parameters:
      index - The index to set
      element - The new element
      Throws:
      IndexOutOfBoundsException - if index is out of range
    • removeElement

      public Path.PathElement removeElement(int index)
      Removes and returns a path element at the specified index.
      Parameters:
      index - The index of the element to remove
      Returns:
      The removed element
      Throws:
      IndexOutOfBoundsException - if index is out of range
    • reorderElements

      public Path reorderElements(List<Integer> newOrder)
      Reorders the path elements according to the specified order.
      Parameters:
      newOrder - List of indices specifying the new order
      Returns:
      This path for chaining
      Throws:
      IllegalArgumentException - if newOrder doesn't match the number of elements
    • getPathElements

      public List<Path.PathElement> getPathElements()
      Gets a copy of all path elements.
      Returns:
      A new list containing all path elements
    • setPathElements

      public void setPathElements(List<Path.PathElement> pathElements)
      Sets the path elements, replacing all existing elements.
      Parameters:
      pathElements - The new list of path elements
      Throws:
      IllegalArgumentException - if pathElements is null
    • getPathElementsWithConstraints

      public List<edu.wpi.first.math.Pair<Path.PathElement,Path.PathElementConstraint>> getPathElementsWithConstraints()
      Gets all path elements paired with their computed constraints.

      This method resolves which constraints apply to each element based on path-specific constraints and global defaults.

      Returns:
      List of (PathElement, PathElementConstraint) pairs
    • getPathElementsWithConstraintsNoWaypoints

      public List<edu.wpi.first.math.Pair<Path.PathElement,Path.PathElementConstraint>> getPathElementsWithConstraintsNoWaypoints()
      Gets all path elements with constraints, expanding waypoints into separate translation and rotation targets.

      This method is used by the path follower to get a flat list of targets without waypoint wrappers. Waypoints are split into their component translation and rotation targets with appropriate t_ratios set.

      Returns:
      List of (PathElement, PathElementConstraint) pairs with waypoints expanded
    • flip

      public void flip()
      Flips this path to the opposite alliance side.

      Uses FlippingUtil to transform all coordinates. This method only flips once - subsequent calls have no effect until undoFlip() is called.

    • undoFlip

      public void undoFlip()
      Undoes a previous flip operation, restoring original coordinates.

      Has no effect if the path has not been flipped.

    • getStartPose

      public edu.wpi.first.math.geometry.Pose2d getStartPose()
      Gets the starting pose for this path using a default rotation of 0.
      Returns:
      The starting pose
      Throws:
      IllegalStateException - if the path is invalid or empty
      See Also:
    • getStartPose

      public edu.wpi.first.math.geometry.Pose2d getStartPose(edu.wpi.first.math.geometry.Rotation2d fallbackRotation)
      Gets the starting pose for this path.

      The translation comes from the first translation target. The rotation comes from the first rotation target, or falls back to the provided rotation if none exists.

      Parameters:
      fallbackRotation - The rotation to use if no rotation target is found
      Returns:
      The starting pose
      Throws:
      IllegalStateException - if the path is invalid or has no translation targets
      See Also:
    • getInitialModuleDirection

      public edu.wpi.first.math.geometry.Rotation2d getInitialModuleDirection()
      Gets the initial direction the robot's modules should face when starting this path.

      Recommendation: It is highly recommended to pre-orient swerve modules toward this direction before the start of an autonomous routine (either via a command or by physically setting module orientations during robot setup). This prevents micro-deviations at the start of the autonomous routine caused by modules needing to rotate before driving.

      This optimization is primarily important for the autonomous phase where precise initial movement matters most.

      Returns:
      The initial module direction as a Rotation2d
      See Also:
    • getInitialModuleDirection

      public edu.wpi.first.math.geometry.Rotation2d getInitialModuleDirection(edu.wpi.first.math.geometry.Rotation2d fallbackRotation)
      Gets the initial module direction using a fallback rotation for the start pose.

      Recommendation: It is highly recommended to pre-orient swerve modules toward this direction before the start of an autonomous routine. See getInitialModuleDirection() for details.

      Parameters:
      fallbackRotation - The fallback rotation for computing start pose
      Returns:
      The initial module direction
      See Also:
    • getInitialModuleDirection

      public edu.wpi.first.math.geometry.Rotation2d getInitialModuleDirection(Supplier<edu.wpi.first.math.geometry.Pose2d> poseSupplier)
      Gets the initial module direction using a custom pose supplier.

      This calculates the direction the swerve modules should face when beginning to follow the path, pointing toward the first translation target that is outside the robot's current handoff radius.

      Recommendation: It is highly recommended to pre-orient swerve modules toward this direction before the start of an autonomous routine (either via a command or by physically setting module orientations during robot setup). This prevents micro-deviations at the start of the autonomous routine caused by modules needing to rotate before driving.

      This optimization is primarily important for the autonomous phase where precise initial movement matters most.

      Parameters:
      poseSupplier - Supplier for the robot's current pose
      Returns:
      The initial module direction relative to the robot's rotation
      See Also:
    • copy

      public Path copy()
      Creates a deep copy of this path.

      The copy includes all path elements, constraints, and preserves the flipped state.

      Returns:
      A new Path with copied data