Skip to content

Commit 8fe6363

Browse files
committed
Using Simple Commander API for multi robot systems (#3803)
* support multirobot namespaces * add docs
1 parent a85466b commit 8fe6363

File tree

2 files changed

+9
-7
lines changed

2 files changed

+9
-7
lines changed

nav2_simple_commander/README.md

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -14,6 +14,8 @@ See its [API Guide Page](https://navigation.ros.org/commander_api/index.html) fo
1414

1515
The methods provided by the basic navigator are shown below, with inputs and expected returns. If a server fails, it may throw an exception or return a `None` object, so please be sure to properly wrap your navigation calls in try/catch and check results for `None` type.
1616

17+
New as of September 2023: the simple navigator constructor will accept a `namespace` field to support multi-robot applications or namespaced Nav2 launches.
18+
1719
| Robot Navigator Method | Description |
1820
| --------------------------------- | -------------------------------------------------------------------------- |
1921
| setInitialPose(initial_pose) | Sets the initial pose (`PoseStamped`) of the robot to localization. |

nav2_simple_commander/nav2_simple_commander/robot_navigator.py

Lines changed: 7 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -46,8 +46,8 @@ class TaskResult(Enum):
4646

4747
class BasicNavigator(Node):
4848

49-
def __init__(self, node_name='basic_navigator'):
50-
super().__init__(node_name=node_name)
49+
def __init__(self, node_name='basic_navigator', namespace=''):
50+
super().__init__(node_name=node_name, namespace=namespace)
5151
self.initial_pose = PoseStamped()
5252
self.initial_pose.header.frame_id = 'map'
5353
self.goal_handle = None
@@ -83,13 +83,13 @@ def __init__(self, node_name='basic_navigator'):
8383
self.initial_pose_pub = self.create_publisher(PoseWithCovarianceStamped,
8484
'initialpose',
8585
10)
86-
self.change_maps_srv = self.create_client(LoadMap, '/map_server/load_map')
86+
self.change_maps_srv = self.create_client(LoadMap, 'map_server/load_map')
8787
self.clear_costmap_global_srv = self.create_client(
88-
ClearEntireCostmap, '/global_costmap/clear_entirely_global_costmap')
88+
ClearEntireCostmap, 'global_costmap/clear_entirely_global_costmap')
8989
self.clear_costmap_local_srv = self.create_client(
90-
ClearEntireCostmap, '/local_costmap/clear_entirely_local_costmap')
91-
self.get_costmap_global_srv = self.create_client(GetCostmap, '/global_costmap/get_costmap')
92-
self.get_costmap_local_srv = self.create_client(GetCostmap, '/local_costmap/get_costmap')
90+
ClearEntireCostmap, 'local_costmap/clear_entirely_local_costmap')
91+
self.get_costmap_global_srv = self.create_client(GetCostmap, 'global_costmap/get_costmap')
92+
self.get_costmap_local_srv = self.create_client(GetCostmap, 'local_costmap/get_costmap')
9393

9494
def destroyNode(self):
9595
self.destroy_node()

0 commit comments

Comments
 (0)