Skip to content

Pathfinders

pathplannerlib Index / Pathplannerlib / Pathfinders

Auto-generated documentation for pathplannerlib.pathfinders module.

GridPosition

Show source in pathfinders.py:171

Signature

class GridPosition: ...

GridPosition().compareTo

Show source in pathfinders.py:181

Signature

def compareTo(self, o: GridPosition) -> int: ...

LocalADStar

Show source in pathfinders.py:189

Signature

class LocalADStar(Pathfinder):
    def __init__(self): ...

See also

LocalADStar().getCurrentPath

Show source in pathfinders.py:287

Get the most recently calculated path

Arguments

  • constraints - The path constraints to use when creating the path
  • goal_end_state - The goal end state to use when creating the path

Returns

The PathPlannerPath created from the points calculated by the pathfinder

Signature

def getCurrentPath(
    self, constraints: PathConstraints, goal_end_state: GoalEndState
) -> Union[PathPlannerPath, None]: ...

LocalADStar().isNewPathAvailable

Show source in pathfinders.py:279

Get if a new path has been calculated since the last time a path was retrieved

Returns

True if a new path is available

Signature

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

LocalADStar().setDynamicObstacles

Show source in pathfinders.py:341

Set the dynamic obstacles that should be avoided while pathfinding.

Arguments

  • obs - A List of Translation2d pairs representing obstacles. Each Translation2d represents opposite corners of a bounding box.
  • current_robot_pos - The current position of the robot. This is needed to change the start position of the path to properly avoid obstacles

Signature

def setDynamicObstacles(
    self,
    obs: List[Tuple[Translation2d, Translation2d]],
    current_robot_pos: Translation2d,
) -> None: ...

LocalADStar().setGoalPosition

Show source in pathfinders.py:323

Set the goal position to pathfind to

Arguments

  • goal_position - Goal position on the field. f this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setGoalPosition(self, goal_position: Translation2d) -> None: ...

LocalADStar().setStartPosition

Show source in pathfinders.py:307

Set the start position to pathfind from

Arguments

  • start_position - Start position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setStartPosition(self, start_position: Translation2d) -> None: ...

Pathfinder

Show source in pathfinders.py:19

Signature

class Pathfinder: ...

Pathfinder().getCurrentPath

Show source in pathfinders.py:28

Get the most recently calculated path

Arguments

  • constraints - The path constraints to use when creating the path
  • goal_end_state - The goal end state to use when creating the path

Returns

The PathPlannerPath created from the points calculated by the pathfinder

Signature

def getCurrentPath(
    self, constraints: PathConstraints, goal_end_state: GoalEndState
) -> Union[PathPlannerPath, None]: ...

Pathfinder().isNewPathAvailable

Show source in pathfinders.py:20

Get if a new path has been calculated since the last time a path was retrieved

Returns

True if a new path is available

Signature

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

Pathfinder().setDynamicObstacles

Show source in pathfinders.py:55

Set the dynamic obstacles that should be avoided while pathfinding.

Arguments

  • obs - A List of Translation2d pairs representing obstacles. Each Translation2d represents opposite corners of a bounding box.
  • current_robot_pos - The current position of the robot. This is needed to change the start position of the path to properly avoid obstacles

Signature

def setDynamicObstacles(
    self,
    obs: List[Tuple[Translation2d, Translation2d]],
    current_robot_pos: Translation2d,
) -> None: ...

Pathfinder().setGoalPosition

Show source in pathfinders.py:47

Set the goal position to pathfind to

Arguments

  • goal_position - Goal position on the field. f this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setGoalPosition(self, goal_position: Translation2d) -> None: ...

Pathfinder().setStartPosition

Show source in pathfinders.py:39

Set the start position to pathfind from

Arguments

  • start_position - Start position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setStartPosition(self, start_position: Translation2d) -> None: ...

RemoteADStar

Show source in pathfinders.py:66

Signature

class RemoteADStar(Pathfinder):
    def __init__(self): ...

See also

RemoteADStar().getCurrentPath

Show source in pathfinders.py:116

Get the most recently calculated path

Arguments

  • constraints - The path constraints to use when creating the path
  • goal_end_state - The goal end state to use when creating the path

Returns

The PathPlannerPath created from the points calculated by the pathfinder

Signature

def getCurrentPath(
    self, constraints: PathConstraints, goal_end_state: GoalEndState
) -> Union[PathPlannerPath, None]: ...

RemoteADStar().isNewPathAvailable

Show source in pathfinders.py:108

Get if a new path has been calculated since the last time a path was retrieved

Returns

True if a new path is available

Signature

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

RemoteADStar().setDynamicObstacles

Show source in pathfinders.py:150

Set the dynamic obstacles that should be avoided while pathfinding.

Arguments

  • obs - A List of Translation2d pairs representing obstacles. Each Translation2d represents opposite corners of a bounding box.
  • current_robot_pos - The current position of the robot. This is needed to change the start position of the path to properly avoid obstacles

Signature

def setDynamicObstacles(
    self,
    obs: List[Tuple[Translation2d, Translation2d]],
    current_robot_pos: Translation2d,
) -> None: ...

RemoteADStar().setGoalPosition

Show source in pathfinders.py:142

Set the goal position to pathfind to

Arguments

  • goal_position - Goal position on the field. f this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setGoalPosition(self, goal_position: Translation2d) -> None: ...

RemoteADStar().setStartPosition

Show source in pathfinders.py:134

Set the start position to pathfind from

Arguments

  • start_position - Start position on the field. If this is within an obstacle it will be moved to the nearest non-obstacle node.

Signature

def setStartPosition(self, start_position: Translation2d) -> None: ...