From 74574069b2dbb2e86c5a992fe98a697d267bf137 Mon Sep 17 00:00:00 2001 From: daviddorf2023 Date: Sun, 5 Nov 2023 15:46:49 -0600 Subject: [PATCH] [STABLE] Docstrings and minor adjustments. --- ros2rrt/rrt2D.py | 74 +++++++++++++++++++++++++++++++++++++++++++++++- ros2rrt/rrt3D.py | 64 +++++++++++++++++++++++++++++++++++++++++ 2 files changed, 137 insertions(+), 1 deletion(-) diff --git a/ros2rrt/rrt2D.py b/ros2rrt/rrt2D.py index f57bdbe..93c6b22 100644 --- a/ros2rrt/rrt2D.py +++ b/ros2rrt/rrt2D.py @@ -9,6 +9,78 @@ class RRT2DNode(Node): + """ + A ROS2 node for generating a 2D RRT. + + Parameters + ---------- + start_x : float + The x coordinate of the start position. + start_y : float + The y coordinate of the start position. + goal_x : float + The x coordinate of the goal position. + goal_y : float + The y coordinate of the goal position. + map_sub_mode : bool + Whether or not to subscribe to the occupancy grid. + obstacle_sub_mode : bool + Whether or not to subscribe to the obstacle markers. + step_size : float + The step size for each node. + node_limit : int + The maximum number of nodes to generate. + goal_tolerance : float + The tolerance for reaching the goal. + wall_confidence : int + The confidence threshold for the occupancy grid. + + Attributes + ---------- + start_position : numpy.ndarray + The start position. + goal_position : numpy.ndarray + The goal position. + map_data : list + The map data. + map_size : numpy.ndarray + The size of the map. + map_resolution : float + The resolution of the map. + map_origin : numpy.ndarray + The origin of the map. + map_matrix : numpy.ndarray + A matrix representation of the map. + pixel_centers : numpy.ndarray + The centers of each pixel in the map. + wall_indices : tuple + The indices of the wall pixels in the map matrix. + wall_centers : numpy.ndarray + The center coordinates of the wall pixels. + start_node : TreeNode + The start node. + node_list : list + The list of nodes. + timer : Timer + The timer for publishing markers and the path. + + Methods + ------- + run_rrt_2D() + Generates the RRT. + timer_callback() + Timer callback for publishing the final markers and path until the node is destroyed. + occupancy_grid_callback(msg) + Callback for the OccupancyGrid subscriber. + obstacle_callback(msg) + Callback for the obstacle subscriber. + publish_markers() + Publishes a marker for each node in the RRT, as well as markers for the start and goal positions. + set_start_goal(start, goal) + Sets the start and goal positions. + publish_path() + Publishes the path. + """ def __init__(self): super().__init__('rrt_2d_node') @@ -34,7 +106,7 @@ def __init__(self): self.occupancy_grid_subscription = self.create_subscription( OccupancyGrid, 'occupancy_grid', self.occupancy_grid_callback, 10) else: - self.map_size = np.array([10, 10]) + self.map_size = np.array([100, 100]) self.map_resolution = 1.0 if self.obstacle_sub_mode: self.obstacle_list = [] diff --git a/ros2rrt/rrt3D.py b/ros2rrt/rrt3D.py index c09b9de..b13086b 100644 --- a/ros2rrt/rrt3D.py +++ b/ros2rrt/rrt3D.py @@ -9,6 +9,70 @@ class RRT3DNode(Node): + """ + A ROS2 node for generating a 2D RRT. + + Parameters + ---------- + start_x : float + The x coordinate of the start position. + start_y : float + The y coordinate of the start position. + goal_x : float + The x coordinate of the goal position. + goal_y : float + The y coordinate of the goal position. + goal_z : float + The z coordinate of the goal position. + map_bounds_x : float + The x boundary of the map. + map_bounds_y : float + The y boundary of the map. + map_bounds_z : float + The z boundary of the map. + obstacle_sub_mode : bool + Whether to subscribe to obstacle data or not. + step_size : float + The step size for the RRT. + node_limit : int + The maximum number of nodes to generate. + goal_tolerance : float + The tolerance for the goal position. + wall_confidence : int + The confidence threshold for the wall. + + Attributes + ---------- + start_position : numpy.ndarray + The start position. + goal_position : numpy.ndarray + The goal position. + map_size : numpy.ndarray + The boundaries containing the RRT. + obstacle_list : list + The list of obstacles. + start_node : TreeNode + The start node. + node_list : list + The list of nodes. + timer : Timer + The timer for publishing the final markers and path. + + Methods + ------- + run_rrt_3D() + Generates the RRT. + timer_callback() + Timer callback for publishing the final markers and path until the node is destroyed. + obstacle_callback(msg) + Callback for the obstacle subscriber. + publish_markers() + Publishes a marker for each node in the RRT, as well as markers for the start and goal positions. + set_start_goal(start, goal) + Sets the start and goal positions. + publish_path() + Publishes the path. + """ def __init__(self): super().__init__('rrt_3d_node')