Class AutoBuilder

java.lang.Object
com.pathplanner.lib.auto.AutoBuilder

public class AutoBuilder extends Object
Utility class used to build auto routines
  • Constructor Details

    • AutoBuilder

      public AutoBuilder()
  • Method Details

    • configure

      public static void configure(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetPose, Supplier<ChassisSpeeds> robotRelativeSpeedsSupplier, BiConsumer<ChassisSpeeds,DriveFeedforwards> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... driveRequirements)
      Configures the AutoBuilder for using PathPlanner's built-in commands.
      Parameters:
      poseSupplier - a supplier for the robot's current pose
      resetPose - a consumer for resetting the robot's pose
      robotRelativeSpeedsSupplier - a supplier for the robot's current robot relative chassis speeds
      output - Output function that accepts robot-relative ChassisSpeeds and feedforwards for each drive motor. If using swerve, these feedforwards will be in FL, FR, BL, BR order. If using a differential drive, they will be in L, R order.

      NOTE: These feedforwards are assuming unoptimized module states. When you optimize your module states, you will need to reverse the feedforwards for modules that have been flipped

      controller - Path following controller that will be used to follow paths
      robotConfig - The robot configuration
      shouldFlipPath - Supplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
      driveRequirements - the subsystem requirements for the robot's drive train
    • configure

      public static void configure(Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetPose, Supplier<ChassisSpeeds> robotRelativeSpeedsSupplier, Consumer<ChassisSpeeds> output, PathFollowingController controller, RobotConfig robotConfig, BooleanSupplier shouldFlipPath, Subsystem... driveRequirements)
      Configures the AutoBuilder for using PathPlanner's built-in commands.
      Parameters:
      poseSupplier - a supplier for the robot's current pose
      resetPose - a consumer for resetting the robot's pose
      robotRelativeSpeedsSupplier - a supplier for the robot's current robot relative chassis speeds
      output - Output function that accepts robot-relative ChassisSpeeds.
      controller - Path following controller that will be used to follow paths
      robotConfig - The robot configuration
      shouldFlipPath - Supplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
      driveRequirements - the subsystem requirements for the robot's drive train
    • configureCustom

      public static void configureCustom(Function<PathPlannerPath,Command> pathFollowingCommandBuilder, Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetPose, BooleanSupplier shouldFlipPose, boolean isHolonomic)
      Configures the AutoBuilder with custom path following command builder. Building pathfinding commands is not supported if using a custom command builder. Custom path following commands will not have the path flipped for them, and event markers will not be triggered automatically.
      Parameters:
      pathFollowingCommandBuilder - a function that builds a command to follow a given path
      poseSupplier - a supplier for the robot's current pose
      resetPose - a consumer for resetting the robot's pose
      shouldFlipPose - Supplier that determines if the starting pose should be flipped to the other side of the field. This will maintain a global blue alliance origin. NOTE: paths will not be flipped when configured with a custom path following command. Flipping the paths must be handled in your command.
      isHolonomic - Does the robot have a holonomic drivetrain
    • configureCustom

      public static void configureCustom(Function<PathPlannerPath,Command> pathFollowingCommandBuilder, Supplier<Pose2d> poseSupplier, Consumer<Pose2d> resetPose, boolean isHolonomic)
      Configures the AutoBuilder with custom path following command builder. Building pathfinding commands is not supported if using a custom command builder. Custom path following commands will not have the path flipped for them, and event markers will not be triggered automatically.
      Parameters:
      pathFollowingCommandBuilder - a function that builds a command to follow a given path
      poseSupplier - a supplier for the robot's current pose
      resetPose - a consumer for resetting the robot's pose
      isHolonomic - Does the robot have a holonomic drivetrain
    • isConfigured

      public static boolean isConfigured()
      Returns whether the AutoBuilder has been configured.
      Returns:
      true if the AutoBuilder has been configured, false otherwise
    • isPathfindingConfigured

      public static boolean isPathfindingConfigured()
      Returns whether the AutoBuilder has been configured for pathfinding.
      Returns:
      true if the AutoBuilder has been configured for pathfinding, false otherwise
    • getCurrentPose

      public static Pose2d getCurrentPose()
      Get the current robot pose
      Returns:
      Current robot pose
    • shouldFlip

      public static boolean shouldFlip()
      Get if a path or field position should currently be flipped
      Returns:
      True if path/positions should be flipped
    • followPath

      public static Command followPath(PathPlannerPath path)
      Builds a command to follow a path. PathPlannerLib commands will also trigger event markers along the way.
      Parameters:
      path - the path to follow
      Returns:
      a path following command with for the given path
      Throws:
      AutoBuilderException - if the AutoBuilder has not been configured
    • pathfindToPose

      public static Command pathfindToPose(Pose2d pose, PathConstraints constraints, double goalEndVelocity)
      Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation and rotation delay distance will have no effect.
      Parameters:
      pose - The pose to pathfind to
      constraints - The constraints to use while pathfinding
      goalEndVelocity - The goal end velocity of the robot when reaching the target pose
      Returns:
      A command to pathfind to a given pose
    • pathfindToPose

      public static Command pathfindToPose(Pose2d pose, PathConstraints constraints, edu.wpi.first.units.measure.LinearVelocity goalEndVelocity)
      Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation and rotation delay distance will have no effect.
      Parameters:
      pose - The pose to pathfind to
      constraints - The constraints to use while pathfinding
      goalEndVelocity - The goal end velocity of the robot when reaching the target pose
      Returns:
      A command to pathfind to a given pose
    • pathfindToPose

      public static Command pathfindToPose(Pose2d pose, PathConstraints constraints)
      Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation will have no effect.
      Parameters:
      pose - The pose to pathfind to
      constraints - The constraints to use while pathfinding
      Returns:
      A command to pathfind to a given pose
    • pathfindToPoseFlipped

      public static Command pathfindToPoseFlipped(Pose2d pose, PathConstraints constraints, double goalEndVelocity)
      Build a command to pathfind to a given pose that will be flipped based on the value of the path flipping supplier when this command is run. If not using a holonomic drivetrain, the pose rotation and rotation delay distance will have no effect.
      Parameters:
      pose - The pose to pathfind to. This will be flipped if the path flipping supplier returns true
      constraints - The constraints to use while pathfinding
      goalEndVelocity - The goal end velocity of the robot when reaching the target pose
      Returns:
      A command to pathfind to a given pose
    • pathfindToPoseFlipped

      public static Command pathfindToPoseFlipped(Pose2d pose, PathConstraints constraints, edu.wpi.first.units.measure.LinearVelocity goalEndVelocity)
      Build a command to pathfind to a given pose that will be flipped based on the value of the path flipping supplier when this command is run. If not using a holonomic drivetrain, the pose rotation and rotation delay distance will have no effect.
      Parameters:
      pose - The pose to pathfind to. This will be flipped if the path flipping supplier returns true
      constraints - The constraints to use while pathfinding
      goalEndVelocity - The goal end velocity of the robot when reaching the target pose
      Returns:
      A command to pathfind to a given pose
    • pathfindToPoseFlipped

      public static Command pathfindToPoseFlipped(Pose2d pose, PathConstraints constraints)
      Build a command to pathfind to a given pose that will be flipped based on the value of the path flipping supplier when this command is run. If not using a holonomic drivetrain, the pose rotation and rotation delay distance will have no effect.
      Parameters:
      pose - The pose to pathfind to. This will be flipped if the path flipping supplier returns true
      constraints - The constraints to use while pathfinding
      Returns:
      A command to pathfind to a given pose
    • pathfindThenFollowPath

      public static Command pathfindThenFollowPath(PathPlannerPath goalPath, PathConstraints pathfindingConstraints)
      Build a command to pathfind to a given path, then follow that path. If not using a holonomic drivetrain, the pose rotation delay distance will have no effect.
      Parameters:
      goalPath - The path to pathfind to, then follow
      pathfindingConstraints - The constraints to use while pathfinding
      Returns:
      A command to pathfind to a given path, then follow the path
    • buildAutoChooser

      public static SendableChooser<Command> buildAutoChooser()
      Create and populate a sendable chooser with all PathPlannerAutos in the project. The default option will be Commands.none()
      Returns:
      SendableChooser populated with all autos
    • buildAutoChooser

      public static SendableChooser<Command> buildAutoChooser(String defaultAutoName)
      Create and populate a sendable chooser with all PathPlannerAutos in the project
      Parameters:
      defaultAutoName - The name of the auto that should be the default option. If this is an empty string, or if an auto with the given name does not exist, the default option will be Commands.none()
      Returns:
      SendableChooser populated with all autos
    • buildAutoChooserWithOptionsModifier

      public static SendableChooser<Command> buildAutoChooserWithOptionsModifier(Function<Stream<PathPlannerAuto>,Stream<PathPlannerAuto>> optionsModifier)
      Create and populate a sendable chooser with all PathPlannerAutos in the project. The default option will be Commands.none()
      Parameters:
      optionsModifier - A lambda function that can be used to modify the options before they go into the AutoChooser
      Returns:
      SendableChooser populated with all autos
    • buildAutoChooserWithOptionsModifier

      public static SendableChooser<Command> buildAutoChooserWithOptionsModifier(String defaultAutoName, Function<Stream<PathPlannerAuto>,Stream<PathPlannerAuto>> optionsModifier)
      Create and populate a sendable chooser with all PathPlannerAutos in the project
      Parameters:
      defaultAutoName - The name of the auto that should be the default option. If this is an empty string, or if an auto with the given name does not exist, the default option will be Commands.none()
      optionsModifier - A lambda function that can be used to modify the options before they go into the AutoChooser
      Returns:
      SendableChooser populated with all autos
    • getAllAutoNames

      public static List<String> getAllAutoNames()
      Get a list of all auto names in the project
      Returns:
      List of all auto names
    • isHolonomic

      public static boolean isHolonomic()
      Get if AutoBuilder was configured for a holonomic drive train
      Returns:
      True if holonomic
    • buildAuto

      public static Command buildAuto(String autoName)
      Builds an auto command for the given auto name.
      Parameters:
      autoName - the name of the auto to build
      Returns:
      an auto command for the given auto name
    • resetOdom

      public static Command resetOdom(Pose2d bluePose)
      Create a command to reset the robot's odometry to a given blue alliance pose
      Parameters:
      bluePose - The pose to reset to, relative to blue alliance origin
      Returns:
      Command to reset the robot's odometry