Robot Core Documentation
Loading...
Searching...
No Matches
com.pathplanner.lib.auto.AutoBuilder Class Reference

Classes

interface  QuadFunction
 
interface  TriFunction
 

Static Public Member Functions

static void configureHolonomic (Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, Supplier< ChassisSpeeds > robotRelativeSpeedsSupplier, Consumer< ChassisSpeeds > robotRelativeOutput, HolonomicPathFollowerConfig config, BooleanSupplier shouldFlipPath, Subsystem driveSubsystem)
 
static void configureRamsete (Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem driveSubsystem)
 
static void configureRamsete (Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, double b, double zeta, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem driveSubsystem)
 
static void configureLTV (Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, double dt, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem driveSubsystem)
 
static void configureLTV (Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, Supplier< ChassisSpeeds > speedsSupplier, Consumer< ChassisSpeeds > output, Vector< N3 > qelems, Vector< N2 > relems, double dt, ReplanningConfig replanningConfig, BooleanSupplier shouldFlipPath, Subsystem driveSubsystem)
 
static void configureCustom (Function< PathPlannerPath, Command > pathFollowingCommandBuilder, Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose, BooleanSupplier shouldFlipPose)
 
static void configureCustom (Function< PathPlannerPath, Command > pathFollowingCommandBuilder, Supplier< Pose2d > poseSupplier, Consumer< Pose2d > resetPose)
 
static boolean isConfigured ()
 
static boolean isPathfindingConfigured ()
 
static Command followPathWithEvents (PathPlannerPath path)
 
static Command followPath (PathPlannerPath path)
 
static Command pathfindToPose (Pose2d pose, PathConstraints constraints, double goalEndVelocity, double rotationDelayDistance)
 
static Command pathfindToPose (Pose2d pose, PathConstraints constraints, double goalEndVelocity)
 
static Command pathfindToPose (Pose2d pose, PathConstraints constraints)
 
static Command pathfindToPoseFlipped (Pose2d pose, PathConstraints constraints, double goalEndVelocity, double rotationDelayDistance)
 
static Command pathfindToPoseFlipped (Pose2d pose, PathConstraints constraints, double goalEndVelocity)
 
static Command pathfindToPoseFlipped (Pose2d pose, PathConstraints constraints)
 
static Command pathfindThenFollowPath (PathPlannerPath goalPath, PathConstraints pathfindingConstraints, double rotationDelayDistance)
 
static Command pathfindThenFollowPath (PathPlannerPath goalPath, PathConstraints pathfindingConstraints)
 
static SendableChooser< CommandbuildAutoChooser ()
 
static SendableChooser< CommandbuildAutoChooser (String defaultAutoName)
 
static SendableChooser< CommandbuildAutoChooserWithOptionsModifier (Function< Stream< PathPlannerAuto >, Stream< PathPlannerAuto > > optionsModifier)
 
static SendableChooser< CommandbuildAutoChooserWithOptionsModifier (String defaultAutoName, Function< Stream< PathPlannerAuto >, Stream< PathPlannerAuto > > optionsModifier)
 
static List< String > getAllAutoNames ()
 
static Pose2d getStartingPoseFromJson (JSONObject startingPoseJson)
 
static Command buildAuto (String autoName)
 
static Command getAutoCommandFromJson (JSONObject autoJson)
 

Detailed Description

Utility class used to build auto routines

Member Function Documentation

◆ buildAuto()

static Command com.pathplanner.lib.auto.AutoBuilder.buildAuto ( String autoName)
static

Builds an auto command for the given auto name.

Parameters
autoNamethe name of the auto to build
Returns
an auto command for the given auto name

◆ buildAutoChooser() [1/2]

static SendableChooser< Command > com.pathplanner.lib.auto.AutoBuilder.buildAutoChooser ( )
static

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() [2/2]

static SendableChooser< Command > com.pathplanner.lib.auto.AutoBuilder.buildAutoChooser ( String defaultAutoName)
static

Create and populate a sendable chooser with all PathPlannerAutos in the project

Parameters
defaultAutoNameThe 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() [1/2]

static SendableChooser< Command > com.pathplanner.lib.auto.AutoBuilder.buildAutoChooserWithOptionsModifier ( Function< Stream< PathPlannerAuto >, Stream< PathPlannerAuto > > optionsModifier)
static

Create and populate a sendable chooser with all PathPlannerAutos in the project. The default option will be Commands.none()

Parameters
optionsModifierA lambda function that can be used to modify the options before they go into the AutoChooser
Returns
SendableChooser populated with all autos

◆ buildAutoChooserWithOptionsModifier() [2/2]

static SendableChooser< Command > com.pathplanner.lib.auto.AutoBuilder.buildAutoChooserWithOptionsModifier ( String defaultAutoName,
Function< Stream< PathPlannerAuto >, Stream< PathPlannerAuto > > optionsModifier )
static

Create and populate a sendable chooser with all PathPlannerAutos in the project

Parameters
defaultAutoNameThe 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()
optionsModifierA lambda function that can be used to modify the options before they go into the AutoChooser
Returns
SendableChooser populated with all autos

◆ configureCustom() [1/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureCustom ( Function< PathPlannerPath, Command > pathFollowingCommandBuilder,
Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose )
static

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
pathFollowingCommandBuildera function that builds a command to follow a given path
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose

◆ configureCustom() [2/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureCustom ( Function< PathPlannerPath, Command > pathFollowingCommandBuilder,
Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
BooleanSupplier shouldFlipPose )
static

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
pathFollowingCommandBuildera function that builds a command to follow a given path
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
shouldFlipPoseSupplier 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.

◆ configureHolonomic()

static void com.pathplanner.lib.auto.AutoBuilder.configureHolonomic ( Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
Supplier< ChassisSpeeds > robotRelativeSpeedsSupplier,
Consumer< ChassisSpeeds > robotRelativeOutput,
HolonomicPathFollowerConfig config,
BooleanSupplier shouldFlipPath,
Subsystem driveSubsystem )
static

Configures the AutoBuilder for a holonomic drivetrain.

Parameters
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
robotRelativeSpeedsSuppliera supplier for the robot's current robot relative chassis speeds
robotRelativeOutputa consumer for setting the robot's robot-relative chassis speeds
configcom.pathplanner.lib.util.HolonomicPathFollowerConfig for configuring the path following commands
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystemthe subsystem for the robot's drive

◆ configureLTV() [1/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureLTV ( Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
double dt,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem driveSubsystem )
static

Configures the AutoBuilder for a differential drivetrain using a LTVUnicycleController path follower.

Parameters
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
speedsSuppliera supplier for the robot's current chassis speeds
outputa consumer for setting the robot's chassis speeds
dtPeriod of the robot control loop in seconds (default 0.02)
replanningConfigPath replanning configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystemthe subsystem for the robot's drive

◆ configureLTV() [2/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureLTV ( Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
Vector< N3 > qelems,
Vector< N2 > relems,
double dt,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem driveSubsystem )
static

Configures the AutoBuilder for a differential drivetrain using a LTVUnicycleController path follower.

Parameters
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
speedsSuppliera supplier for the robot's current chassis speeds
outputa consumer for setting the robot's chassis speeds
qelemsThe maximum desired error tolerance for each state.
relemsThe maximum desired control effort for each input.
dtPeriod of the robot control loop in seconds (default 0.02)
replanningConfigPath replanning configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystemthe subsystem for the robot's drive

◆ configureRamsete() [1/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureRamsete ( Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
double b,
double zeta,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem driveSubsystem )
static

Configures the AutoBuilder for a differential drivetrain using a RAMSETE path follower.

Parameters
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
speedsSuppliera supplier for the robot's current chassis speeds
outputa consumer for setting the robot's chassis speeds
bTuning parameter (b > 0 rad^2/m^2) for which larger values make convergence more aggressive like a proportional term.
zetaTuning parameter (0 rad^-1 < zeta < 1 rad^-1) for which larger values provide more damping in response.
replanningConfigPath replanning configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystemthe subsystem for the robot's drive

◆ configureRamsete() [2/2]

static void com.pathplanner.lib.auto.AutoBuilder.configureRamsete ( Supplier< Pose2d > poseSupplier,
Consumer< Pose2d > resetPose,
Supplier< ChassisSpeeds > speedsSupplier,
Consumer< ChassisSpeeds > output,
ReplanningConfig replanningConfig,
BooleanSupplier shouldFlipPath,
Subsystem driveSubsystem )
static

Configures the AutoBuilder for a differential drivetrain using a RAMSETE path follower.

Parameters
poseSuppliera supplier for the robot's current pose
resetPosea consumer for resetting the robot's pose
speedsSuppliera supplier for the robot's current chassis speeds
outputa consumer for setting the robot's chassis speeds
replanningConfigPath replanning configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystemthe subsystem for the robot's drive

◆ followPath()

static Command com.pathplanner.lib.auto.AutoBuilder.followPath ( PathPlannerPath path)
static

Builds a command to follow a path. PathPlannerLib commands will also trigger event markers along the way.

Parameters
paththe path to follow
Returns
a path following command with for the given path
Exceptions
AutoBuilderExceptionif the AutoBuilder has not been configured

◆ followPathWithEvents()

static Command com.pathplanner.lib.auto.AutoBuilder.followPathWithEvents ( PathPlannerPath path)
static

Builds a command to follow a path with event markers.

Parameters
paththe path to follow
Returns
a path following command with events for the given path
Exceptions
AutoBuilderExceptionif the AutoBuilder has not been configured
Deprecated
Renamed to "followPath"

◆ getAllAutoNames()

static List< String > com.pathplanner.lib.auto.AutoBuilder.getAllAutoNames ( )
static

Get a list of all auto names in the project

Returns
List of all auto names

◆ getAutoCommandFromJson()

static Command com.pathplanner.lib.auto.AutoBuilder.getAutoCommandFromJson ( JSONObject autoJson)
static

Builds an auto command from the given JSON object.

Parameters
autoJsonthe JSON object to build the command from
Returns
an auto command built from the JSON object

◆ getStartingPoseFromJson()

static Pose2d com.pathplanner.lib.auto.AutoBuilder.getStartingPoseFromJson ( JSONObject startingPoseJson)
static

Get the starting pose from its JSON representation. This is only used internally.

Parameters
startingPoseJsonJSON object representing a starting pose.
Returns
The Pose2d starting pose

◆ isConfigured()

static boolean com.pathplanner.lib.auto.AutoBuilder.isConfigured ( )
static

Returns whether the AutoBuilder has been configured.

Returns
true if the AutoBuilder has been configured, false otherwise

◆ isPathfindingConfigured()

static boolean com.pathplanner.lib.auto.AutoBuilder.isPathfindingConfigured ( )
static

Returns whether the AutoBuilder has been configured for pathfinding.

Returns
true if the AutoBuilder has been configured for pathfinding, false otherwise

◆ pathfindThenFollowPath() [1/2]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindThenFollowPath ( PathPlannerPath goalPath,
PathConstraints pathfindingConstraints )
static

Build a command to pathfind to a given path, then follow that path.

Parameters
goalPathThe path to pathfind to, then follow
pathfindingConstraintsThe constraints to use while pathfinding
Returns
A command to pathfind to a given path, then follow the path

◆ pathfindThenFollowPath() [2/2]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindThenFollowPath ( PathPlannerPath goalPath,
PathConstraints pathfindingConstraints,
double rotationDelayDistance )
static

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
goalPathThe path to pathfind to, then follow
pathfindingConstraintsThe constraints to use while pathfinding
rotationDelayDistanceThe distance the robot should move from the start position before attempting to rotate to the final rotation
Returns
A command to pathfind to a given path, then follow the path

◆ pathfindToPose() [1/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPose ( Pose2d pose,
PathConstraints constraints )
static

Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation will have no effect.

Parameters
poseThe pose to pathfind to
constraintsThe constraints to use while pathfinding
Returns
A command to pathfind to a given pose

◆ pathfindToPose() [2/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPose ( Pose2d pose,
PathConstraints constraints,
double goalEndVelocity )
static

Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation will have no effect.

Parameters
poseThe pose to pathfind to
constraintsThe constraints to use while pathfinding
goalEndVelocityThe goal end velocity of the robot when reaching the target pose
Returns
A command to pathfind to a given pose

◆ pathfindToPose() [3/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPose ( Pose2d pose,
PathConstraints constraints,
double goalEndVelocity,
double rotationDelayDistance )
static

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
poseThe pose to pathfind to
constraintsThe constraints to use while pathfinding
goalEndVelocityThe goal end velocity of the robot when reaching the target pose
rotationDelayDistanceThe distance the robot should move from the start position before attempting to rotate to the final rotation
Returns
A command to pathfind to a given pose

◆ pathfindToPoseFlipped() [1/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPoseFlipped ( Pose2d pose,
PathConstraints constraints )
static

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
poseThe pose to pathfind to. This will be flipped if the path flipping supplier returns true
constraintsThe constraints to use while pathfinding
Returns
A command to pathfind to a given pose

◆ pathfindToPoseFlipped() [2/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPoseFlipped ( Pose2d pose,
PathConstraints constraints,
double goalEndVelocity )
static

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
poseThe pose to pathfind to. This will be flipped if the path flipping supplier returns true
constraintsThe constraints to use while pathfinding
goalEndVelocityThe goal end velocity of the robot when reaching the target pose
Returns
A command to pathfind to a given pose

◆ pathfindToPoseFlipped() [3/3]

static Command com.pathplanner.lib.auto.AutoBuilder.pathfindToPoseFlipped ( Pose2d pose,
PathConstraints constraints,
double goalEndVelocity,
double rotationDelayDistance )
static

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
poseThe pose to pathfind to. This will be flipped if the path flipping supplier returns true
constraintsThe constraints to use while pathfinding
goalEndVelocityThe goal end velocity of the robot when reaching the target pose
rotationDelayDistanceThe distance the robot should move from the start position before attempting to rotate to the final rotation
Returns
A command to pathfind to a given pose

The documentation for this class was generated from the following file: