Skip to content

Auto

pathplannerlib Index / Pathplannerlib / Auto

Auto-generated documentation for pathplannerlib.auto module.

AutoBuilder

Show source in auto.py:425

Signature

class AutoBuilder: ...

AutoBuilder.buildAuto

Show source in auto.py:649

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:659

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.configure

Show source in auto.py:438

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

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
  • output - 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

Show source in auto.py:508

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
  • reset_pose - a consumer for resetting the robot's pose :param isHolonomic Does the robot have a holonomic drivetrain
  • 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],
    reset_pose: Callable[[Pose2d], None],
    isHolonomic: bool,
    should_flip_pose: Callable[[], bool] = lambda: False,
) -> None: ...

AutoBuilder.followPath

Show source in auto.py:577

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.getCurrentPose

Show source in auto.py:559

Get the current robot pose

Returns

Current robot pose

Signature

@staticmethod
def getCurrentPose() -> Pose2d: ...

AutoBuilder.isConfigured

Show source in auto.py:532

Returns whether the AutoBuilder has been configured.

Returns

true if the AutoBuilder has been configured, false otherwise

Signature

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

AutoBuilder.isHolonomic

Show source in auto.py:550

Get if AutoBuilder was configured for a holonomic drive train

Returns

True if holonomic

Signature

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

AutoBuilder.isPathfindingConfigured

Show source in auto.py:541

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:624

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

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

Show source in auto.py:590

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

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

Show source in auto.py:606

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

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

Show source in auto.py:638

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

@staticmethod
def resetOdom(bluePose: Pose2d) -> Command: ...

AutoBuilder.shouldFlip

Show source in auto.py:568

Get if a path or field position should currently be flipped

Returns

True if path/positions should be flipped

Signature

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

CommandUtil

Show source in auto.py:62

Signature

class CommandUtil: ...

CommandUtil.commandFromJson

Show source in auto.py:81

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:63

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:22

Signature

class NamedCommands: ...

NamedCommands.getCommand

Show source in auto.py:45

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:35

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:25

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:154

Signature

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

PathPlannerAuto().activePath

Show source in auto.py:332

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

def activePath(self, pathName: str) -> Trigger: ...

PathPlannerAuto().condition

Show source in auto.py:275

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

def condition(self, condition: Callable[[], bool]) -> Trigger: ...

PathPlannerAuto().end

Show source in auto.py:268

Signature

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

PathPlannerAuto().event

Show source in auto.py:312

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

def event(self, eventName: str) -> Trigger: ...

PathPlannerAuto().execute

Show source in auto.py:260

Signature

def execute(self): ...

PathPlannerAuto.getPathGroupFromAutoFile

Show source in auto.py:237

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

Show source in auto.py:374

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

Show source in auto.py:395

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

Show source in auto.py:253

Signature

def initialize(self): ...

PathPlannerAuto().isFinished

Show source in auto.py:265

Signature

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

PathPlannerAuto().isRunning

Show source in auto.py:285

Create a trigger that is high when this auto is running, and low when it is not running

Returns

isRunning trigger

Signature

def isRunning(self) -> Trigger: ...

PathPlannerAuto().nearFieldPosition

Show source in auto.py:341

Create a trigger that is high when near a given field position. This field position is not automatically flipped

Arguments

  • fieldPosition - The target field position
  • toleranceMeters - The position tolerance, in meters. The trigger will be high when within this distance from the target position

Returns

nearFieldPosition trigger

Signature

def nearFieldPosition(
    self, fieldPosition: Translation2d, toleranceMeters: float
) -> Trigger: ...

PathPlannerAuto().nearFieldPositionAutoFlipped

Show source in auto.py:354

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 alliance
  • toleranceMeters - 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

Show source in auto.py:322

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

def pointTowardsZone(self, zoneName: str) -> Trigger: ...

PathPlannerAuto().timeElapsed

Show source in auto.py:293

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

def timeElapsed(self, time: float) -> Trigger: ...

PathPlannerAuto().timeRange

Show source in auto.py:302

Trigger that is high when within a range of time since the start of this auto

Arguments

  • startTime - The starting time of the range
  • endTime - The ending time of the range

Returns

timeRange trigger

Signature

def timeRange(self, startTime: float, endTime: float) -> Trigger: ...