Skip to content

Auto

pathplannerlib Index / Pathplannerlib / Auto

Auto-generated documentation for pathplannerlib.auto module.

AutoBuilder

Show source in auto.py:148

Signature

class AutoBuilder: ...

AutoBuilder.buildAuto

Show source in auto.py:491

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

@staticmethod
def buildAuto(auto_name: str) -> Command: ...

AutoBuilder.buildAutoChooser

Show source in auto.py:505

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

@staticmethod
def buildAutoChooser(default_auto_name: str = "") -> SendableChooser: ...

AutoBuilder.configureCustom

Show source in auto.py:346

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 path
  • pose_supplier - a supplier for the robot's current pose
  • reset_pose - a consumer for resetting the robot's pose
  • should_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

Show source in auto.py:160

Configures the AutoBuilder for a holonomic drivetrain.

Arguments

  • pose_supplier - a supplier for the robot's current pose
  • reset_pose - a consumer for resetting the robot's pose
  • robot_relative_speeds_supplier - a supplier for the robot's current robot relative chassis speeds
  • robot_relative_output - a consumer for setting the robot's robot-relative chassis speeds
  • config - HolonomicPathFollowerConfig for configuring the path following commands
  • 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 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

Show source in auto.py:280

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

Arguments

  • pose_supplier - a supplier for the robot's current pose
  • reset_pose - a consumer for resetting the robot's pose
  • robot_relative_speeds_supplier - a supplier for the robot's current robot relative chassis speeds
  • robot_relative_output - a consumer for setting the robot's robot-relative chassis speeds
  • qelems - The maximum desired error tolerance for each state
  • relems - The maximum desired control effort for each input
  • dt - The amount of time between each robot control loop, default is 0.02s
  • replanning_config - Path replanning 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 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

Show source in auto.py:221

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

Arguments

  • pose_supplier - a supplier for the robot's current pose
  • reset_pose - a consumer for resetting the robot's pose
  • robot_relative_speeds_supplier - a supplier for the robot's current robot relative chassis speeds
  • robot_relative_output - a consumer for setting the robot's robot-relative chassis speeds
  • replanning_config - Path replanning 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 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

Show source in auto.py:387

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

@staticmethod
def followPath(path: PathPlannerPath) -> Command: ...

AutoBuilder.getAutoCommandFromJson

Show source in auto.py:472

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

@staticmethod
def getAutoCommandFromJson(auto_json: dict) -> Command: ...

AutoBuilder.getStartingPoseFromJson

Show source in auto.py:457

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

@staticmethod
def getStartingPoseFromJson(starting_pose_json: dict) -> Pose2d: ...

AutoBuilder.isConfigured

Show source in auto.py:369

Returns whether the AutoBuilder has been configured.

Returns

true if the AutoBuilder has been configured, false otherwise

Signature

@staticmethod
def isConfigured() -> bool: ...

AutoBuilder.isPathfindingConfigured

Show source in auto.py:378

Returns whether the AutoBuilder has been configured for pathfinding.

Returns

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

Signature

@staticmethod
def isPathfindingConfigured() -> bool: ...

AutoBuilder.pathfindThenFollowPath

Show source in auto.py:440

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 follow
  • pathfinding_constraints - The constraints to use while pathfinding
  • rotation_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

Show source in auto.py:400

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 to
  • constraints - The constraints to use while pathfinding
  • goal_end_vel - The goal end velocity of the robot when reaching the target pose
  • rotation_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

Show source in auto.py:419

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 true
  • constraints - The constraints to use while pathfinding
  • goal_end_vel - The goal end velocity of the robot when reaching the target pose
  • rotation_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

Show source in auto.py:60

Signature

class CommandUtil: ...

CommandUtil.commandFromJson

Show source in auto.py:79

Builds a command from the given json object

Arguments

  • command_json - the json dict to build the command from
  • load_choreo_paths - Load path commands using choreo trajectories

Returns

a command built from the json dict

Signature

@staticmethod
def commandFromJson(command_json: dict, load_choreo_paths: bool) -> Command: ...

CommandUtil.wrappedEventCommand

Show source in auto.py:61

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

@staticmethod
def wrappedEventCommand(event_command: Command) -> Command: ...

NamedCommands

Show source in auto.py:20

Signature

class NamedCommands: ...

NamedCommands.getCommand

Show source in auto.py:43

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

@staticmethod
def getCommand(name: str) -> Command: ...

NamedCommands.hasCommand

Show source in auto.py:33

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

@staticmethod
def hasCommand(name: str) -> bool: ...

NamedCommands.registerCommand

Show source in auto.py:23

Registers a command with the given name

Arguments

  • name - the name of the command
  • command - the command to register

Signature

@staticmethod
def registerCommand(name: str, command: Command) -> None: ...

PathPlannerAuto

Show source in auto.py:533

Signature

class PathPlannerAuto(Command):
    def __init__(self, auto_name: str): ...

PathPlannerAuto().end

Show source in auto.py:613

Signature

def end(self, interrupted: bool): ...

PathPlannerAuto().execute

Show source in auto.py:607

Signature

def execute(self): ...

PathPlannerAuto.getPathGroupFromAutoFile

Show source in auto.py:588

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

@staticmethod
def getPathGroupFromAutoFile(auto_name: str) -> List[PathPlannerPath]: ...

PathPlannerAuto.getStartingPoseFromAutoFile

Show source in auto.py:556

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

Signature

@staticmethod
def getStartingPoseFromAutoFile(auto_name: str) -> Pose2d: ...

PathPlannerAuto().initialize

Show source in auto.py:604

Signature

def initialize(self): ...

PathPlannerAuto().isFinished

Show source in auto.py:610

Signature

def isFinished(self) -> bool: ...