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.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 pathpose_supplier
- a supplier for the robot's current posereset_pose
- a consumer for resetting the robot's poseshould_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],
pose_supplier: Callable[[], Pose2d],
reset_pose: Callable[[Pose2d], None],
should_flip_pose: Callable[[], bool] = lambda: False,
) -> None: ...
AutoBuilder.configureHolonomic
Configures the AutoBuilder for a holonomic drivetrain.
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 speedsrobot_relative_output
- a consumer for setting the robot's robot-relative chassis speedsconfig
- HolonomicPathFollowerConfig for configuring the path following commandsshould_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 configureHolonomic(
pose_supplier: Callable[[], Pose2d],
reset_pose: Callable[[Pose2d], None],
robot_relative_speeds_supplier: Callable[[], ChassisSpeeds],
robot_relative_output: Callable[[ChassisSpeeds], None],
config: HolonomicPathFollowerConfig,
should_flip_path: Callable[[], bool],
drive_subsystem: Subsystem,
) -> None: ...
AutoBuilder.configureLTV
Configures the AutoBuilder for a differential drivetrain using a LTVUnicycleController path follower.
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 speedsrobot_relative_output
- a consumer for setting the robot's robot-relative chassis speedsqelems
- The maximum desired error tolerance for each staterelems
- The maximum desired control effort for each inputdt
- The amount of time between each robot control loop, default is 0.02sreplanning_config
- Path replanning configurationshould_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 configureLTV(
pose_supplier: Callable[[], Pose2d],
reset_pose: Callable[[Pose2d], None],
robot_relative_speeds_supplier: Callable[[], ChassisSpeeds],
robot_relative_output: Callable[[ChassisSpeeds], None],
qelems: Tuple[float, float, float],
relems: Tuple[float, float],
dt: float,
replanning_config: ReplanningConfig,
should_flip_path: Callable[[], bool],
drive_subsystem: Subsystem,
) -> None: ...
AutoBuilder.configureRamsete
Configures the AutoBuilder for a differential drivetrain using a RAMSETE path follower.
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 speedsrobot_relative_output
- a consumer for setting the robot's robot-relative chassis speedsreplanning_config
- Path replanning configurationshould_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 configureRamsete(
pose_supplier: Callable[[], Pose2d],
reset_pose: Callable[[Pose2d], None],
robot_relative_speeds_supplier: Callable[[], ChassisSpeeds],
robot_relative_output: Callable[[ChassisSpeeds], None],
replanning_config: ReplanningConfig,
should_flip_path: Callable[[], bool],
drive_subsystem: Subsystem,
) -> 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.getAutoCommandFromJson
Builds an auto command from the given JSON dict.
Arguments
auto_json
- the JSON dict to build the command from
Returns
an auto command built from the JSON object
Signature
AutoBuilder.getStartingPoseFromJson
Get the starting pose from its JSON representation. This is only used internally.
Arguments
starting_pose_json
- JSON dict representing a starting pose.
Returns
The Pose2d starting pose
Signature
AutoBuilder.isConfigured
Returns whether the AutoBuilder has been configured.
Returns
true if the AutoBuilder has been configured, false otherwise
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 pathfindingrotation_delay_distance
- The 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
Signature
@staticmethod
def pathfindThenFollowPath(
goal_path: PathPlannerPath,
pathfinding_constraints: PathConstraints,
rotation_delay_distance: float = 0.0,
) -> 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 poserotation_delay_distance
- The 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
Signature
@staticmethod
def pathfindToPose(
pose: Pose2d,
constraints: PathConstraints,
goal_end_vel: float = 0.0,
rotation_delay_distance: 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 poserotation_delay_distance
- The 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
Signature
@staticmethod
def pathfindToPoseFlipped(
pose: Pose2d,
constraints: PathConstraints,
goal_end_vel: float = 0.0,
rotation_delay_distance: float = 0.0,
) -> Command: ...
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().end
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.getStartingPoseFromAutoFile
Get the starting pose from the given auto file
Arguments
auto_name
- Name of the auto to get the pose from
Returns
Starting pose from the given auto