pyrobosim.navigation.rrt.RRTPlanner.__init__
- RRTPlanner.__init__(*, bidirectional: bool = False, rrt_connect: bool = False, rrt_star: bool = False, collision_check_step_dist: float = 0.025, max_connection_dist: float = 0.25, max_nodes_sampled: int = 1000, max_time: float = 2.0, rewire_radius: float = 1.0, compress_path: bool = False) → None
Creates an instance of an RRT planner.
- Parameters:
bidirectional – If True, uses bidirectional RRT to grow trees from both start and goal.
rrt_connect – If True, uses RRTConnect to bias tree growth towards goals.
rrt_star – If True, uses RRT* to rewire trees to smooth and shorten paths.
collision_check_step_dist – Step size for discretizing collision checking.
max_connection_dist – Maximum connection distance between nodes.
max_nodes_sampled – Maximum nodes sampled before planning stops.
max_time – Maximum wall clock time before planning stops.
rewire_radius – Radius around a node to rewire the RRT, if using the RRT* algorithm.