Auto
pathplannerlib Index / Pathplannerlib / Auto
Auto-generated documentation for pathplannerlib.auto module.
AutoBuilder
Signature
AutoBuilder.buildAuto
Builds an auto command for the given auto name.
Arguments
auto_name
- the name of the auto to build
Returns
an auto command for the given auto name
Signature
AutoBuilder.buildAutoChooser
Create and populate a sendable chooser with all PathPlannerAutos in the project and the default auto name selected.
Arguments
default_auto_name
- the name of the default auto to be selected in the chooser
Returns
a sendable chooser object populated with all of PathPlannerAutos in the project
Signature
AutoBuilder.configure
Configures the AutoBuilder for using PathPlanner's built-in commands.
Arguments
pose_supplier
- a supplier for the robot's current posereset_pose
- a consumer for resetting the robot's poserobot_relative_speeds_supplier
- a supplier for the robot's current robot relative chassis speedsoutput
- 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 :param controller Path following controller that will be used to follow paths :param robot_config The robot configuration
should_flip_path
- Supplier that determines if paths should be flipped to the other side of the field. This will maintain a global blue alliance origin.drive_subsystem
- the subsystem for the robot's drive
Signature
@staticmethod
def configure(
pose_supplier: Callable[[], Pose2d],
reset_pose: Callable[[Pose2d], None],
robot_relative_speeds_supplier: Callable[[], ChassisSpeeds],
output: Callable[[ChassisSpeeds, DriveFeedforwards], None],
controller: PathFollowingController,
robot_config: RobotConfig,
should_flip_path: Callable[[], bool],
drive_subsystem: Subsystem,
) -> None: ...
AutoBuilder.configureCustom
Configures the AutoBuilder with custom path following command builder. Building pathfinding commands is not supported if using a custom command builder.
Arguments
path_following_command_builder
- a function that builds a command to follow a given pathreset_pose
- a consumer for resetting the robot's pose :param isHolonomic Does the robot have a holonomic drivetrainshould_flip_pose
- 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.
Signature
@staticmethod
def configureCustom(
path_following_command_builder: Callable[[PathPlannerPath], Command],
reset_pose: Callable[[Pose2d], None],
isHolonomic: bool,
should_flip_pose: Callable[[], bool] = lambda: False,
) -> None: ...
AutoBuilder.followPath
Builds a command to follow a path with event markers.
Arguments
path
- the path to follow
Returns
a path following command with events for the given path
Signature
AutoBuilder.getCurrentPose
Get the current robot pose
Returns
Current robot pose
Signature
AutoBuilder.isConfigured
Returns whether the AutoBuilder has been configured.
Returns
true if the AutoBuilder has been configured, false otherwise
Signature
AutoBuilder.isHolonomic
Get if AutoBuilder was configured for a holonomic drive train
Returns
True if holonomic
Signature
AutoBuilder.isPathfindingConfigured
Returns whether the AutoBuilder has been configured for pathfinding.
Returns
true if the AutoBuilder has been configured for pathfinding, false otherwise
Signature
AutoBuilder.pathfindThenFollowPath
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.
Arguments
goal_path
- The path to pathfind to, then followpathfinding_constraints
- The constraints to use while pathfinding
Returns
A command to pathfind to a given path, then follow the path
Signature
@staticmethod
def pathfindThenFollowPath(
goal_path: PathPlannerPath, pathfinding_constraints: PathConstraints
) -> Command: ...
AutoBuilder.pathfindToPose
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.
Arguments
pose
- The pose to pathfind toconstraints
- The constraints to use while pathfindinggoal_end_vel
- The goal end velocity of the robot when reaching the target pose
Returns
A command to pathfind to a given pose
Signature
@staticmethod
def pathfindToPose(
pose: Pose2d, constraints: PathConstraints, goal_end_vel: float = 0.0
) -> Command: ...
AutoBuilder.pathfindToPoseFlipped
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.
Arguments
pose
- The pose to pathfind to. This will be flipped if the path flipping supplier returns trueconstraints
- The constraints to use while pathfindinggoal_end_vel
- The goal end velocity of the robot when reaching the target pose
Returns
A command to pathfind to a given pose
Signature
@staticmethod
def pathfindToPoseFlipped(
pose: Pose2d, constraints: PathConstraints, goal_end_vel: float = 0.0
) -> Command: ...
AutoBuilder.resetOdom
Create a command to reset the robot's odometry to a given blue alliance pose
Arguments
bluePose
- The pose to reset to, relative to blue alliance origin
Returns
Command to reset the robot's odometry
Signature
AutoBuilder.shouldFlip
Get if a path or field position should currently be flipped
Returns
True if path/positions should be flipped
Signature
CommandUtil
Signature
CommandUtil.commandFromJson
Builds a command from the given json object
Arguments
command_json
- the json dict to build the command fromload_choreo_paths
- Load path commands using choreo trajectories
Returns
a command built from the json dict
Signature
CommandUtil.wrappedEventCommand
Wraps a command with a functional command that calls the command's initialize, execute, end, and isFinished methods. This allows a command in the event map to be reused multiple times in different command groups
Arguments
event_command
- the command to wrap
Returns
a functional command that wraps the given command
Signature
NamedCommands
Signature
NamedCommands.getCommand
Returns the command with the given name.
Arguments
name
- the name of the command to get
Returns
the command with the given name, wrapped in a functional command, or a none command if it has not been registered
Signature
NamedCommands.hasCommand
Returns whether a command with the given name has been registered.
Arguments
name
- the name of the command to check
Returns
true if a command with the given name has been registered, false otherwise
Signature
NamedCommands.registerCommand
Registers a command with the given name
Arguments
name
- the name of the commandcommand
- the command to register
Signature
PathPlannerAuto
Signature
PathPlannerAuto().activePath
Create a trigger that is high when a certain path is being followed
Arguments
pathName
- The name of the path to check for
Returns
activePath trigger
Signature
PathPlannerAuto().condition
Create a trigger with a custom condition. This will be polled by this auto's event loop so that its condition is only polled when this auto is running.
Arguments
condition
- The condition represented by this trigger
Returns
Custom condition trigger
Signature
PathPlannerAuto().end
Signature
PathPlannerAuto().event
Create an EventTrigger that will be polled by this auto instead of globally across all path following commands
Arguments
eventName
- The event name that controls this trigger
Returns
EventTrigger for this auto
Signature
PathPlannerAuto().execute
Signature
PathPlannerAuto.getPathGroupFromAutoFile
Get a list of every path in the given auto (depth first)
Arguments
auto_name
- Name of the auto to get the path group from
Returns
List of paths in the auto
Signature
PathPlannerAuto().inFieldArea
Create a trigger that will be high when the robot is within a given area on the field. These positions will not be automatically flipped
Arguments
boundingBoxMin
- The minimum position of the bounding box for the target field area. The X and Y coordinates of this position should be less than the max position.boundingBoxMax
- The maximum position of the bounding box for the target field area. The X and Y coordinates of this position should be greater than the min position.
Returns
inFieldArea trigger
Signature
def inFieldArea(
self, boundingBoxMin: Translation2d, boundingBoxMax: Translation2d
) -> Trigger: ...
PathPlannerAuto().inFieldAreaAutoFlipped
Create a trigger that will be high when the robot is within a given area on the field. These positions will be automatically flipped
Arguments
blueBoundingBoxMin
- The minimum position of the bounding box for the target field area if on the blue alliance. The X and Y coordinates of this position should be less than the max position.blueBoundingBoxMax
- The maximum position of the bounding box for the target field area if on the blue alliance. The X & Y coordinates of this position should be greater than the min position.
Returns
inFieldAreaAutoFlipped trigger
Signature
def inFieldAreaAutoFlipped(
self, blueBoundingBoxMin: Translation2d, blueBoundingBoxMax: Translation2d
) -> Trigger: ...
PathPlannerAuto().initialize
Signature
PathPlannerAuto().isFinished
Signature
PathPlannerAuto().isRunning
Create a trigger that is high when this auto is running, and low when it is not running
Returns
isRunning trigger
Signature
PathPlannerAuto().nearFieldPosition
Create a trigger that is high when near a given field position. This field position is not automatically flipped
Arguments
fieldPosition
- The target field positiontoleranceMeters
- The position tolerance, in meters. The trigger will be high when within this distance from the target position
Returns
nearFieldPosition trigger
Signature
PathPlannerAuto().nearFieldPositionAutoFlipped
Create a trigger that is high when near a given field position. This field position will be automatically flipped
Arguments
blueFieldPosition
- The target field position if on the blue alliancetoleranceMeters
- The position tolerance, in meters. The trigger will be high when within this distance from the target position
Returns
nearFieldPositionAutoFlipped trigger
Signature
def nearFieldPositionAutoFlipped(
self, blueFieldPosition: Translation2d, toleranceMeters: float
) -> Trigger: ...
PathPlannerAuto().pointTowardsZone
Create a PointTowardsZoneTrigger that will be polled by this auto instead of globally across all path following commands
Arguments
zoneName
- The point towards zone name that controls this trigger
Returns
PointTowardsZoneTrigger for this auto
Signature
PathPlannerAuto().timeElapsed
Trigger that is high when the given time has elapsed
Arguments
time
- The amount of time this auto should run before the trigger is activated
Returns
timeElapsed trigger
Signature
PathPlannerAuto().timeRange
Trigger that is high when within a range of time since the start of this auto
Arguments
startTime
- The starting time of the rangeendTime
- The ending time of the range
Returns
timeRange trigger