Class FollowPath.Builder

java.lang.Object
frc.robot.lib.BLine.FollowPath.Builder
Enclosing class:
FollowPath

public static class FollowPath.Builder extends Object
Builder class for constructing FollowPath commands with a fluent API.

The Builder allows you to configure a path follower once with all the robot-specific parameters, then build multiple commands for different paths. This avoids repeating the same configuration for each path.

Important: This builder is mutable and stateful. Optional settings configured through with... methods persist for all subsequent build(Path) calls until you change them again. For example, once withPoseReset(Consumer) is set, later built commands will continue resetting pose unless you override it (for example, with a no-op consumer).

Required Parameters

The constructor requires:

  • Drive subsystem - For command requirements
  • Pose supplier - Returns current robot pose
  • Robot-relative speeds supplier - Returns current chassis speeds
  • Robot-relative speeds consumer - Accepts commanded chassis speeds
  • Three PID controllers for translation, rotation, and cross-track correction

Optional Configuration

Example


 FollowPath.Builder builder = new FollowPath.Builder(
     driveSubsystem,
     this::getPose,
     this::getSpeeds,
     this::drive,
     translationPID,
     rotationPID,
     crossTrackPID
 ).withDefaultShouldFlip();
 
 Command cmd = builder.build(myPath);
 
  • Constructor Details

    • Builder

      public Builder(edu.wpi.first.wpilibj2.command.Subsystem driveSubsystem, Supplier<edu.wpi.first.math.geometry.Pose2d> poseSupplier, Supplier<edu.wpi.first.math.kinematics.ChassisSpeeds> robotRelativeSpeedsSupplier, Consumer<edu.wpi.first.math.kinematics.ChassisSpeeds> robotRelativeSpeedsConsumer, edu.wpi.first.math.controller.PIDController translationController, edu.wpi.first.math.controller.PIDController rotationController, edu.wpi.first.math.controller.PIDController crossTrackController)
      Creates a new FollowPath Builder with the required configuration.
      Parameters:
      driveSubsystem - The drive subsystem that the command will require
      poseSupplier - Supplier that returns the current robot pose in field coordinates
      robotRelativeSpeedsSupplier - Supplier that returns current robot-relative chassis speeds
      robotRelativeSpeedsConsumer - Consumer that accepts robot-relative chassis speeds to drive
      translationController - PID controller for calculating command speed by minimizing path distance remaining
      rotationController - PID controller for rotating toward rotation targets
      crossTrackController - PID controller for staying on the line between waypoints
  • Method Details

    • withShouldFlip

      public FollowPath.Builder withShouldFlip(Supplier<Boolean> shouldFlipPathSupplier)
      Configures a custom supplier to determine whether the path should be flipped.

      When the supplier returns true, the path will be flipped to the opposite alliance side using FlippingUtil during command initialization.

      This setting persists for future build(Path) calls until changed.

      Parameters:
      shouldFlipPathSupplier - Supplier returning true if the path should be flipped
      Returns:
      This builder for chaining
    • withDefaultShouldFlip

      public FollowPath.Builder withDefaultShouldFlip()
      Configures the builder to use the default alliance-based path flipping.

      When enabled, paths will automatically be flipped when the robot is on the red alliance, based on DriverStation.getAlliance().

      This setting persists for future build(Path) calls until changed.

      Returns:
      This builder for chaining
    • withPoseReset

      public FollowPath.Builder withPoseReset(Consumer<edu.wpi.first.math.geometry.Pose2d> poseResetConsumer)
      Configures a consumer to reset the robot's pose at the start of path following.

      When set, the command will call this consumer with the path's starting pose during initialization. This is useful for resetting odometry when starting autonomous routines or when the robot is placed at a known location.

      This setting persists for future build(Path) calls until changed. To disable pose reset on later commands when reusing the same builder, set a no-op consumer such as withPoseReset(pose -> {}).

      Parameters:
      poseResetConsumer - Consumer that resets the robot's pose estimate
      Returns:
      This builder for chaining
    • withTRatioBasedTranslationHandoffs

      public FollowPath.Builder withTRatioBasedTranslationHandoffs(boolean enabled)
      Enables or disables t_ratio-based translation handoffs.

      When enabled, translation target handoffs occur based on projected segment progress rather than raw distance, which can be more robust at higher speeds on riskier paths. Defaults to false.

      This setting persists for future build(Path) calls until changed.

      Parameters:
      enabled - true to use t_ratio-based handoffs, false for radius-based
      Returns:
      This builder for chaining
    • build

      public FollowPath build(Path path)
      Builds a FollowPath command for the specified path.

      The built command will use all the configuration from this builder. Each call to build() creates an independent command that can be scheduled, using the builder's current optional settings at the time of the call.

      Parameters:
      path - The path to follow
      Returns:
      A new FollowPath command configured for the given path
      Throws:
      IllegalArgumentException - if any required controllers are null