PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::AutoBuilder Class Reference

Static Public Member Functions

static void configure (std::function< frc::Pose2d()> poseSupplier, std::function< void(const frc::Pose2d &)> resetPose, std::function< frc::ChassisSpeeds()> robotRelativeSpeedsSupplier, std::function< void(const frc::ChassisSpeeds &, const DriveFeedforwards &)> output, std::shared_ptr< PathFollowingController > controller, RobotConfig robotConfig, std::function< bool()> shouldFlipPath, frc2::Subsystem *driveSubsystem)
 
static void configure (std::function< frc::Pose2d()> poseSupplier, std::function< void(const frc::Pose2d &)> resetPose, std::function< frc::ChassisSpeeds()> robotRelativeSpeedsSupplier, std::function< void(const frc::ChassisSpeeds &)> output, std::shared_ptr< PathFollowingController > controller, RobotConfig robotConfig, std::function< bool()> shouldFlipPath, frc2::Subsystem *driveSubsystem)
 
static void configureCustom (std::function< frc::Pose2d()> poseSupplier, std::function< frc2::CommandPtr(std::shared_ptr< PathPlannerPath >)> pathFollowingCommandBuilder, std::function< void(const frc::Pose2d &)> resetPose, bool isHolonomic, std::function< bool()> shouldFlipPose=[]() { return false;})
 
static bool isConfigured ()
 
static bool isHolonomic ()
 
static frc::Pose2d getCurrentPose ()
 
static bool shouldFlip ()
 
static frc2::CommandPtr followPath (std::shared_ptr< PathPlannerPath > path)
 
static frc2::CommandPtr buildAuto (std::string autoName)
 
static frc2::CommandPtr resetOdom (frc::Pose2d bluePose)
 
static frc2::CommandPtr pathfindToPose (frc::Pose2d pose, PathConstraints constraints, units::meters_per_second_t goalEndVel=0_mps)
 
static frc2::CommandPtr pathfindToPoseFlipped (frc::Pose2d pose, PathConstraints constraints, units::meters_per_second_t goalEndVel=0_mps)
 
static frc2::CommandPtr pathfindThenFollowPath (std::shared_ptr< PathPlannerPath > goalPath, PathConstraints pathfindingConstraints)
 
static void regenerateSendableReferences ()
 
static frc::SendableChooser< frc2::Command * > buildAutoChooser (std::string defaultAutoName="")
 
static frc::SendableChooser< frc2::Command * > buildAutoChooserFilter (std::function< bool(const PathPlannerAuto &)> filter, std::string defaultAutoName="")
 
static frc::SendableChooser< frc2::Command * > buildAutoChooserFilterPath (std::function< bool(const PathPlannerAuto &, std::filesystem::path)> filter, std::string defaultAutoName="")
 
static std::vector< std::string > getAllAutoNames ()
 
static std::vector< std::filesystem::path > getAllAutoPaths ()
 

Member Function Documentation

◆ buildAuto()

frc2::CommandPtr AutoBuilder::buildAuto ( std::string  autoName)
inlinestatic

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()

frc::SendableChooser< frc2::Command * > AutoBuilder::buildAutoChooser ( std::string  defaultAutoName = "")
static

Populate a sendable chooser with all loaded PathPlannerAutos in the project in pathplanner/auto deploy directory (recursively) Loads PathPlannerAutos from deploy/pathplanner/auto directory (recursively) on first call

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 frc2::cmd::None()
Returns
SendableChooser populated with all autos

◆ buildAutoChooserFilter()

frc::SendableChooser< frc2::Command * > AutoBuilder::buildAutoChooserFilter ( std::function< bool(const PathPlannerAuto &)>  filter,
std::string  defaultAutoName = "" 
)
static

Populate a sendable chooser with all loaded PathPlannerAutos in the project in pathplanner/auto deploy directory (recursively) Loads PathPlannerAutos from deploy/pathplanner/auto directory (recursively) on first call Filters certain PathPlannerAuto bases on their properties

Parameters
filterFunction which filters the auto commands out, returning true allows the command to be uploaded to sendable chooser while returning false prevents it from being added. autoCommand, const reference to PathPlannerAuto command which was generated
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 frc2::cmd::None(), defaultAutoName doesn't get filter out and always is in final sendable chooser (if found)
Returns
SendableChooser populated with all autos

◆ buildAutoChooserFilterPath()

frc::SendableChooser< frc2::Command * > AutoBuilder::buildAutoChooserFilterPath ( std::function< bool(const PathPlannerAuto &, std::filesystem::path)>  filter,
std::string  defaultAutoName = "" 
)
static

Populate a sendable chooser with all loaded PathPlannerAutos in the project in pathplanner/auto deploy directory (recursively) Loads PathPlannerAutos from deploy/pathplanner/auto directory (recursively) on first call Filters certain PathPlannerAuto bases on their properties and their filepath

Parameters
filterFunction which filters the auto commands out, returning true allows the command to be uploaded to sendable chooser while returning false prevents it from being added. autoCommand, const reference to PathPlannerAuto command which was generated autoPath, path to the autoCommand relative to pathplanner/auto deploy directory with extension ".auto"
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 frc2::cmd::None(), defaultAutoName doesn't get filter out and always is in final sendable chooser (if found)
Returns
SendableChooser populated with all autos

◆ configure() [1/2]

static void pathplanner::AutoBuilder::configure ( std::function< frc::Pose2d()>  poseSupplier,
std::function< void(const frc::Pose2d &)>  resetPose,
std::function< frc::ChassisSpeeds()>  robotRelativeSpeedsSupplier,
std::function< void(const frc::ChassisSpeeds &)>  output,
std::shared_ptr< PathFollowingController controller,
RobotConfig  robotConfig,
std::function< bool()>  shouldFlipPath,
frc2::Subsystem *  driveSubsystem 
)
inlinestatic

Configures the AutoBuilder for using PathPlanner's built-in commands.

Parameters
poseSuppliera function that returns the robot's current pose
resetPosea function used for resetting the robot's pose
robotRelativeSpeedsSuppliera function that returns the robot's current robot relative chassis speeds
outputOutput function that accepts robot-relative ChassisSpeeds.
controllerPath following controller that will be used to follow the path
robotConfigThe robot configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystema pointer to the subsystem for the robot's drive

◆ configure() [2/2]

void AutoBuilder::configure ( std::function< frc::Pose2d()>  poseSupplier,
std::function< void(const frc::Pose2d &)>  resetPose,
std::function< frc::ChassisSpeeds()>  robotRelativeSpeedsSupplier,
std::function< void(const frc::ChassisSpeeds &, const DriveFeedforwards &)>  output,
std::shared_ptr< PathFollowingController controller,
RobotConfig  robotConfig,
std::function< bool()>  shouldFlipPath,
frc2::Subsystem *  driveSubsystem 
)
static

Configures the AutoBuilder for using PathPlanner's built-in commands.

Parameters
poseSuppliera function that returns the robot's current pose
resetPosea function used for resetting the robot's pose
robotRelativeSpeedsSuppliera function that returns the robot's current robot relative chassis speeds
outputOutput 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

Parameters
controllerPath following controller that will be used to follow the path
robotConfigThe robot configuration
shouldFlipPathSupplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.
driveSubsystema pointer to the subsystem for the robot's drive

◆ configureCustom()

void AutoBuilder::configureCustom ( std::function< frc::Pose2d()>  poseSupplier,
std::function< frc2::CommandPtr(std::shared_ptr< PathPlannerPath >)>  pathFollowingCommandBuilder,
std::function< void(const frc::Pose2d &)>  resetPose,
bool  isHolonomic,
std::function< bool()>  shouldFlipPose = []() { return false; } 
)
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
poseSuppliera function that returns the robot's current pose
pathFollowingCommandBuildera function that builds a command to follow a given path
resetPosea function for resetting the robot's pose
isHolonomicDoes the robot have a holonomic drivetrain
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.

◆ followPath()

frc2::CommandPtr AutoBuilder::followPath ( std::shared_ptr< 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

◆ getAllAutoNames()

std::vector< std::string > AutoBuilder::getAllAutoNames ( )
static

Get a vector of all auto names in the pathplanner/auto deploy directory (recursively)

Returns
Vector of strings containing all auto names

◆ getAllAutoPaths()

std::vector< std::filesystem::path > AutoBuilder::getAllAutoPaths ( )
static

Get a vector of all auto paths in the pathplanner/auto deploy directory (recursively)

Returns
Vector of paths relative to autos deploy directory

◆ getCurrentPose()

static frc::Pose2d pathplanner::AutoBuilder::getCurrentPose ( )
inlinestatic

Get the current robot pose

Returns
Current robot pose

◆ isConfigured()

static bool pathplanner::AutoBuilder::isConfigured ( )
inlinestatic

Returns whether the AutoBuilder has been configured.

Returns
true if the AutoBuilder has been configured, false otherwise

◆ isHolonomic()

static bool pathplanner::AutoBuilder::isHolonomic ( )
inlinestatic

Returns whether the AutoBuilder has been configured for a holonomic drivetrain.

Returns
true if the AutoBuilder has been configured for a holonomic drivetrain, false otherwise

◆ pathfindThenFollowPath()

frc2::CommandPtr AutoBuilder::pathfindThenFollowPath ( std::shared_ptr< PathPlannerPath goalPath,
PathConstraints  pathfindingConstraints 
)
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
Returns
A command to pathfind to a given path, then follow the path

◆ pathfindToPose()

frc2::CommandPtr AutoBuilder::pathfindToPose ( frc::Pose2d  pose,
PathConstraints  constraints,
units::meters_per_second_t  goalEndVel = 0_mps 
)
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
Returns
A command to pathfind to a given pose

◆ pathfindToPoseFlipped()

static frc2::CommandPtr pathplanner::AutoBuilder::pathfindToPoseFlipped ( frc::Pose2d  pose,
PathConstraints  constraints,
units::meters_per_second_t  goalEndVel = 0_mps 
)
inlinestatic

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

◆ regenerateSendableReferences()

void AutoBuilder::regenerateSendableReferences ( )
static

Modifies the existing references that buildAutoChooser returns in SendableChooser to the most recent in the pathplanner/auto deploy directory

Loads PathPlannerAutos from deploy/pathplanner/auto directory (recursively) on every call Adds new auto paths from the pathplanner/auto deploy directory however doesn't remove autos already previously loaded

◆ resetOdom()

frc2::CommandPtr AutoBuilder::resetOdom ( frc::Pose2d  bluePose)
static

Create a command to reset the robot's odometry to a given blue alliance pose

Parameters
bluePoseThe pose to reset to, relative to blue alliance origin
Returns
Command to reset the robot's odometry

◆ shouldFlip()

static bool pathplanner::AutoBuilder::shouldFlip ( )
inlinestatic

Get if a path or field position should currently be flipped

Returns
True if path/positions should be flipped

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