irsim.lib.path_planners.rrt#

Rapidly-exploring Random Tree (RRT) path planner.

Collision precedence (delegated to env_map.is_collision(geometry)):
  1. Grid lookup when env_map.grid is not None; if occupied, collision.

2. When the grid reports free or is unavailable, geometry vs. obstacle_list. The planner builds the robot shape as a geometry (e.g. circle, or polygon for non-circular robots) and calls the unified interface; the map supports any Shapely geometry.

Reference:

S. M. LaValle, “Rapidly-Exploring Random Trees: A New Tool for Path Planning,” 1998.

Implementation reference:

ZJU-FAST-Lab/sampling-based-path-finding https://github.com/ZJU-FAST-Lab/sampling-based-path-finding (C++ implementation with kd-tree and efficient tree management.)

Adapted for ir-sim.

Attributes#

Classes#

TreeNode

A node in the RRT search tree.

RRT

Rapidly-exploring Random Tree (RRT) path planner.

Module Contents#

irsim.lib.path_planners.rrt.logger#
class irsim.lib.path_planners.rrt.TreeNode[source]#

A node in the RRT search tree.

Identity-based equality (eq=False) is used so that nodes can be safely compared with == / is and used as dictionary keys without triggering recursive field comparisons.

x#

X position.

y#

Y position.

cost#

Cumulative cost from the start node (cost_from_start).

cost_from_parent#

Cost of the edge from parent to this node.

parent#

Parent node (None for the root).

children#

Direct children in the tree.

path_x#

Discretised X coordinates from parent to this node (used for visualisation and per-point collision checking).

path_y#

Discretised Y coordinates from parent to this node.

x: float#
y: float#
cost: float = 0.0#
cost_from_parent: float = 0.0#
parent: TreeNode | None = None#
children: list[TreeNode] = []#
path_x: list[float] = []#
path_y: list[float] = []#
class irsim.lib.path_planners.rrt.RRT(env_map: irsim.world.map.EnvGridMap, robot: irsim.world.object_base.ObjectBase, expand_dis: float = 1.0, path_resolution: float = 0.25, goal_sample_rate: int = 5, max_iter: int = 500)[source]#

Rapidly-exploring Random Tree (RRT) path planner.

Algorithmic improvements over the naive implementation (inspired by ZJU-FAST-Lab/sampling-based-path-finding):

  • Nodes track their children, enabling O(subtree) cost propagation via BFS instead of O(n) linear scans.

  • scipy.spatial.KDTree is used for nearest-neighbour and range queries when available, falling back to numpy otherwise.

  • A dedicated goal node is kept in the tree; whenever a new node can reach the goal at a lower cost the goal’s parent is rewired.

Initialise the RRT planner.

Robot shape is taken from robot.original_geometry (e.g. pass robot=env.robot).

Parameters:
  • env_map – Environment map (EnvGridMap).

  • robot – Robot object; its original_geometry is used for collision.

  • expand_dis – Maximum extension distance per steer step.

  • path_resolution – Discretisation resolution along steered edges.

  • goal_sample_rate – Percentage chance of sampling the goal.

  • max_iter – Maximum number of iterations.

Node#
class AreaBounds(env_map: irsim.world.map.EnvGridMap)[source]#

Rectangular play-area bounds in world coordinates.

xmin: float#
ymin: float#
xmax: float#
ymax: float#
obstacle_list#
play_area#
max_x#
max_y#
min_rand#
max_rand#
expand_dis = 1.0#
path_resolution = 0.25#
goal_sample_rate = 5#
max_iter = 500#
node_list = []#
start = None#
end = None#
robot_radius#
planning(start_pose: list[float], goal_pose: list[float], show_animation: bool = True) numpy.ndarray | None[source]#

Run RRT path planning.

Parameters:
  • start_pose – Start position [x, y].

  • goal_pose – Goal position [x, y].

  • show_animation – Render the exploration tree during planning.

Returns:

(2, N) numpy array [rx, ry] or None.

steer(from_node: TreeNode, to_node: TreeNode, extend_length: float = float('inf')) TreeNode[source]#

Steer from from_node towards to_node.

Returns a temporary TreeNode (not yet registered in the tree) with path_x/path_y populated and parent set to from_node.

get_random_node() TreeNode[source]#

Uniform random sample with goal-bias.

is_collision(node: TreeNode) bool[source]#

Check whether node’s edge is collision-free.

Uses _collision_geometry translated to each path point. Returns True if the path is collision-free.

draw_graph(rnd: TreeNode | None = None) None[source]#

Render the RRT tree on the active matplotlib axes.

calc_dist_to_goal(x: float, y: float) float[source]#

Euclidean distance from (x, y) to the goal.

static calc_distance_and_angle(from_node: TreeNode, to_node: TreeNode) tuple[float, float][source]#

Euclidean distance and heading between two nodes.