From c71224454fb4e12d50228c00a76ce12765352fb9 Mon Sep 17 00:00:00 2001 From: "M. Mostafa Farzan" Date: Wed, 27 Apr 2022 22:12:34 +0430 Subject: [PATCH] Clean up action clients in nav2_simple_commander (#2924) * Clean up action clients in nav2_simple_commander * Add camelCase version * Add docs --- nav2_simple_commander/README.md | 1 + .../nav2_simple_commander/robot_navigator.py | 15 +++++++++++++++ 2 files changed, 16 insertions(+) diff --git a/nav2_simple_commander/README.md b/nav2_simple_commander/README.md index 177ce667f94..a8f0b4de45e 100644 --- a/nav2_simple_commander/README.md +++ b/nav2_simple_commander/README.md @@ -36,6 +36,7 @@ The methods provided by the basic navigator are shown below, with inputs and exp | waitUntilNav2Active(navigator='bt_navigator, localizer='amcl') | Blocks until Nav2 is completely online and lifecycle nodes are in the active state. To be used in conjunction with autostart or external lifecycle bringup. Custom navigator and localizer nodes can be specified | | lifecycleStartup() | Sends a request to all lifecycle management servers to bring them into the active state, to be used if autostart is `false` and you want this program to control Nav2's lifecycle. | | lifecycleShutdown() | Sends a request to all lifecycle management servers to shut them down. | +| destroyNode() | Releases the resources used by the object. | A general template for building applications is as follows: diff --git a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py index 4bcf8093d63..24307b97d86 100644 --- a/nav2_simple_commander/nav2_simple_commander/robot_navigator.py +++ b/nav2_simple_commander/nav2_simple_commander/robot_navigator.py @@ -87,6 +87,21 @@ def __init__(self): self.get_costmap_global_srv = self.create_client(GetCostmap, '/global_costmap/get_costmap') self.get_costmap_local_srv = self.create_client(GetCostmap, '/local_costmap/get_costmap') + def destroyNode(self): + self.destroy_node() + + def destroy_node(self): + self.nav_through_poses_client.destroy() + self.nav_to_pose_client.destroy() + self.follow_waypoints_client.destroy() + self.follow_path_client.destroy() + self.compute_path_to_pose_client.destroy() + self.compute_path_through_poses_client.destroy() + self.smoother_client.destroy() + self.spin_client.destroy() + self.backup_client.destroy() + super().destroy_node() + def setInitialPose(self, initial_pose): """Set the initial pose to the localization system.""" self.initial_pose_received = False