Class Path.PathConstraints

java.lang.Object
frc.robot.lib.BLine.Path.PathConstraints
Enclosing class:
Path

public static final class Path.PathConstraints extends Object
Path-specific constraints that override global defaults.

This class allows setting velocity and acceleration limits that apply only to a specific path. Constraints can be set as single values (applying to the entire path) or as ranged constraints (applying to specific sections).

Uses a fluent API for easy configuration:


 PathConstraints constraints = new PathConstraints()
     .setMaxVelocityMetersPerSec(3.0)
     .setMaxAccelerationMetersPerSec2(2.0)
     .setEndTranslationToleranceMeters(0.05);
 
  • Constructor Details

    • PathConstraints

      public PathConstraints()
      Creates an empty PathConstraints with no overrides set.
  • Method Details

    • setMaxVelocityMetersPerSec

      public Path.PathConstraints setMaxVelocityMetersPerSec(double value)
      Sets a global maximum translational velocity for the entire path.
      Parameters:
      value - The maximum velocity in meters per second
      Returns:
      This PathConstraints for chaining
    • setMaxVelocityMetersPerSec

      public Path.PathConstraints setMaxVelocityMetersPerSec(Path.RangedConstraint... constraints)
      Sets ranged maximum translational velocity constraints.
      Parameters:
      constraints - The ranged constraints to apply
      Returns:
      This PathConstraints for chaining
    • setMaxAccelerationMetersPerSec2

      public Path.PathConstraints setMaxAccelerationMetersPerSec2(double value)
      Sets a global maximum translational acceleration for the entire path.
      Parameters:
      value - The maximum acceleration in meters per second squared
      Returns:
      This PathConstraints for chaining
    • setMaxAccelerationMetersPerSec2

      public Path.PathConstraints setMaxAccelerationMetersPerSec2(Path.RangedConstraint... constraints)
      Sets ranged maximum translational acceleration constraints.
      Parameters:
      constraints - The ranged constraints to apply
      Returns:
      This PathConstraints for chaining
    • setMaxVelocityDegPerSec

      public Path.PathConstraints setMaxVelocityDegPerSec(double value)
      Sets a global maximum rotational velocity for the entire path.
      Parameters:
      value - The maximum angular velocity in degrees per second
      Returns:
      This PathConstraints for chaining
    • setMaxVelocityDegPerSec

      public Path.PathConstraints setMaxVelocityDegPerSec(Path.RangedConstraint... constraints)
      Sets ranged maximum rotational velocity constraints.
      Parameters:
      constraints - The ranged constraints to apply
      Returns:
      This PathConstraints for chaining
    • setMaxAccelerationDegPerSec2

      public Path.PathConstraints setMaxAccelerationDegPerSec2(double value)
      Sets a global maximum rotational acceleration for the entire path.
      Parameters:
      value - The maximum angular acceleration in degrees per second squared
      Returns:
      This PathConstraints for chaining
    • setMaxAccelerationDegPerSec2

      public Path.PathConstraints setMaxAccelerationDegPerSec2(Path.RangedConstraint... constraints)
      Sets ranged maximum rotational acceleration constraints.
      Parameters:
      constraints - The ranged constraints to apply
      Returns:
      This PathConstraints for chaining
    • setEndTranslationToleranceMeters

      public Path.PathConstraints setEndTranslationToleranceMeters(double value)
      Sets the translation tolerance for path completion.
      Parameters:
      value - The tolerance in meters
      Returns:
      This PathConstraints for chaining
    • setEndRotationToleranceDeg

      public Path.PathConstraints setEndRotationToleranceDeg(double value)
      Sets the rotation tolerance for path completion.
      Parameters:
      value - The tolerance in degrees
      Returns:
      This PathConstraints for chaining
    • getMaxVelocityMetersPerSec

      public Optional<ArrayList<Path.RangedConstraint>> getMaxVelocityMetersPerSec()
      Returns:
      Optional ranged constraints for maximum translational velocity
    • getMaxAccelerationMetersPerSec2

      public Optional<ArrayList<Path.RangedConstraint>> getMaxAccelerationMetersPerSec2()
      Returns:
      Optional ranged constraints for maximum translational acceleration
    • getMaxVelocityDegPerSec

      public Optional<ArrayList<Path.RangedConstraint>> getMaxVelocityDegPerSec()
      Returns:
      Optional ranged constraints for maximum rotational velocity
    • getMaxAccelerationDegPerSec2

      public Optional<ArrayList<Path.RangedConstraint>> getMaxAccelerationDegPerSec2()
      Returns:
      Optional ranged constraints for maximum rotational acceleration
    • getEndTranslationToleranceMeters

      public Optional<Double> getEndTranslationToleranceMeters()
      Returns:
      Optional end translation tolerance override
    • getEndRotationToleranceDeg

      public Optional<Double> getEndRotationToleranceDeg()
      Returns:
      Optional end rotation tolerance override
    • copy

      public Path.PathConstraints copy()
      Creates a deep copy of these constraints.
      Returns:
      A new PathConstraints with the same values