Robot Core Documentation
|
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< Command > | buildAutoChooser () |
static SendableChooser< Command > | buildAutoChooser (String defaultAutoName) |
static SendableChooser< Command > | buildAutoChooserWithOptionsModifier (Function< Stream< PathPlannerAuto >, Stream< PathPlannerAuto > > optionsModifier) |
static SendableChooser< Command > | buildAutoChooserWithOptionsModifier (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) |
Utility class used to build auto routines
|
static |
Builds an auto command for the given auto name.
autoName | the name of the auto to build |
|
static |
Create and populate a sendable chooser with all PathPlannerAutos in the project. The default option will be Commands.none()
|
static |
Create and populate a sendable chooser with all PathPlannerAutos in the project
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() |
|
static |
Create and populate a sendable chooser with all PathPlannerAutos in the project. 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 |
|
static |
Create and populate a sendable chooser with all PathPlannerAutos in the project
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 |
|
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.
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 |
|
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.
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. |
|
static |
Configures the AutoBuilder for a holonomic drivetrain.
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 |
robotRelativeOutput | a consumer for setting the robot's robot-relative chassis speeds |
config | com.pathplanner.lib.util.HolonomicPathFollowerConfig for configuring the path following commands |
shouldFlipPath | Supplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin. |
driveSubsystem | the subsystem for the robot's drive |
|
static |
Configures the AutoBuilder for a differential drivetrain using a LTVUnicycleController path follower.
poseSupplier | a supplier for the robot's current pose |
resetPose | a consumer for resetting the robot's pose |
speedsSupplier | a supplier for the robot's current chassis speeds |
output | a consumer for setting the robot's chassis speeds |
dt | Period of the robot control loop in seconds (default 0.02) |
replanningConfig | Path replanning 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. |
driveSubsystem | the subsystem for the robot's drive |
|
static |
Configures the AutoBuilder for a differential drivetrain using a LTVUnicycleController path follower.
poseSupplier | a supplier for the robot's current pose |
resetPose | a consumer for resetting the robot's pose |
speedsSupplier | a supplier for the robot's current chassis speeds |
output | a consumer for setting the robot's chassis speeds |
qelems | The maximum desired error tolerance for each state. |
relems | The maximum desired control effort for each input. |
dt | Period of the robot control loop in seconds (default 0.02) |
replanningConfig | Path replanning 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. |
driveSubsystem | the subsystem for the robot's drive |
|
static |
Configures the AutoBuilder for a differential drivetrain using a RAMSETE path follower.
poseSupplier | a supplier for the robot's current pose |
resetPose | a consumer for resetting the robot's pose |
speedsSupplier | a supplier for the robot's current chassis speeds |
output | a consumer for setting the robot's chassis speeds |
b | Tuning parameter (b > 0 rad^2/m^2) for which larger values make convergence more aggressive like a proportional term. |
zeta | Tuning parameter (0 rad^-1 < zeta < 1 rad^-1) for which larger values provide more damping in response. |
replanningConfig | Path replanning 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. |
driveSubsystem | the subsystem for the robot's drive |
|
static |
Configures the AutoBuilder for a differential drivetrain using a RAMSETE path follower.
poseSupplier | a supplier for the robot's current pose |
resetPose | a consumer for resetting the robot's pose |
speedsSupplier | a supplier for the robot's current chassis speeds |
output | a consumer for setting the robot's chassis speeds |
replanningConfig | Path replanning 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. |
driveSubsystem | the subsystem for the robot's drive |
|
static |
Builds a command to follow a path. PathPlannerLib commands will also trigger event markers along the way.
path | the path to follow |
AutoBuilderException | if the AutoBuilder has not been configured |
|
static |
Builds a command to follow a path with event markers.
path | the path to follow |
AutoBuilderException | if the AutoBuilder has not been configured |
|
static |
Get a list of all auto names in the project
|
static |
Builds an auto command from the given JSON object.
autoJson | the JSON object to build the command from |
|
static |
Get the starting pose from its JSON representation. This is only used internally.
startingPoseJson | JSON object representing a starting pose. |
|
static |
Returns whether the AutoBuilder has been configured.
|
static |
Returns whether the AutoBuilder has been configured for pathfinding.
|
static |
Build a command to pathfind to a given path, then follow that path.
goalPath | The path to pathfind to, then follow |
pathfindingConstraints | The constraints to use while pathfinding |
|
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.
goalPath | The path to pathfind to, then follow |
pathfindingConstraints | The constraints to use while pathfinding |
rotationDelayDistance | The distance the robot should move from the start position before attempting to rotate to the final rotation |
|
static |
Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation will have no effect.
pose | The pose to pathfind to |
constraints | The constraints to use while pathfinding |
|
static |
Build a command to pathfind to a given pose. If not using a holonomic drivetrain, the pose rotation will have no effect.
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 |
|
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.
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 |
rotationDelayDistance | The distance the robot should move from the start position before attempting to rotate to the final rotation |
|
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.
pose | The pose to pathfind to. This will be flipped if the path flipping supplier returns true |
constraints | The constraints to use while pathfinding |
|
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.
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 |
|
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.
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 |
rotationDelayDistance | The distance the robot should move from the start position before attempting to rotate to the final rotation |