Skip to content

Commit edc68a7

Browse files
committed
Add new luanch script for multi-robot bringup
Rename luanch script for multi-robot simulation bringup Add new nav2_common script - Parse argument - Parse multirobot pose Update README.md
1 parent 5cd8043 commit edc68a7

File tree

5 files changed

+287
-3
lines changed

5 files changed

+287
-3
lines changed

nav2_bringup/README.md

Lines changed: 30 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,17 +1,44 @@
11
# nav2_bringup
22

3-
The `nav2_bringup` package is an example bringup system for Nav2 applications.
3+
The `nav2_bringup` package is an example bringup system for Nav2 applications.
44

5-
This is a very flexible example for nav2 bringup that can be modified for different maps/robots/hardware/worlds/etc. It is our expectation for an application specific robot system that you're mirroring `nav2_bringup` package and modifying it for your specific maps/robots/bringup needs. This is an applied and working demonstration for the default system bringup with many options that can be easily modified.
5+
This is a very flexible example for nav2 bringup that can be modified for different maps/robots/hardware/worlds/etc. It is our expectation for an application specific robot system that you're mirroring `nav2_bringup` package and modifying it for your specific maps/robots/bringup needs. This is an applied and working demonstration for the default system bringup with many options that can be easily modified.
66

77
Usual robot stacks will have a `<robot_name>_nav` package with config/bringup files and this is that for the general case to base a specific robot system off of.
88

99
Dynamically composed bringup (based on [ROS2 Composition](https://docs.ros.org/en/galactic/Tutorials/Composition.html)) is optional for users. It can be used to compose all Nav2 nodes in a single process instead of launching these nodes separately, which is useful for embedded systems users that need to make optimizations due to harsh resource constraints. Dynamically composed bringup is used by default, but can be disabled by using the launch argument `use_composition:=False`.
1010

1111
* Some discussions about performance improvement of composed bringup could be found here: https://discourse.ros.org/t/nav2-composition/22175.
1212

13-
To use, please see the Nav2 [Getting Started Page](https://navigation.ros.org/getting_started/index.html) on our documentation website. Additional [tutorials will help you](https://navigation.ros.org/tutorials/index.html) go from an initial setup in simulation to testing on a hardware robot, using SLAM, and more.
13+
To use, please see the Nav2 [Getting Started Page](https://navigation.ros.org/getting_started/index.html) on our documentation website. Additional [tutorials will help you](https://navigation.ros.org/tutorials/index.html) go from an initial setup in simulation to testing on a hardware robot, using SLAM, and more.
1414

1515
Note:
1616
* gazebo should be started with both libgazebo_ros_init.so and libgazebo_ros_factory.so to work correctly.
1717
* spawn_entity node could not remap /tf and /tf_static to tf and tf_static in the launch file yet, used only for multi-robot situations. Instead it should be done as remapping argument <remapping>/tf:=tf</remapping> <remapping>/tf_static:=tf_static</remapping> under ros2 tag in each plugin which publishs transforms in the SDF file. It is essential to differentiate the tf's of the different robot.
18+
19+
## Launch
20+
21+
### Multi-robot Simulation
22+
23+
This is how to launch multi-robot simulation with simple command line. Please see the Nav2 documentation for further arugmehts.
24+
25+
#### cloned
26+
27+
This allows to bring up the multiple robots cloning a single robot N times. And the parameter for single robot are loaded from `nav2_multirobot_params_all.yaml` file in default.
28+
The multiple robots that consists of name and initial pose in YAML format will be launched based on command-line. The format for each robot is `robot_name={x: 0.0, y: 0.0, yaw: 0.0, roll: 0.0, pitch: 0.0, yaw: 0.0}`.
29+
30+
Please refer to below examples.
31+
32+
```shell
33+
ros2 launch nav2_bringup cloned_multi_tb3_simulation_launch.py robots:="robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}"
34+
```
35+
36+
#### unique
37+
38+
There are two robots including name and intitial pose are hard-coded in the launch script. Two separated unique robots are required params file (`nav2_multirobot_params_1.yaml`, `nav2_multirobot_params_2.yaml`) for each robot to bring up.
39+
40+
If you want to bringup more than two robots, you should modify the `unique_multi_tb3_simulation_launch.py` script.
41+
42+
```shell
43+
ros2 launch nav2_bringup unique_multi_tb3_simulation_launch.py
44+
```
Lines changed: 174 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,174 @@
1+
# Copyright (c) 2023 LG Electronics.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
16+
import os
17+
from ament_index_python.packages import get_package_share_directory
18+
from launch import LaunchDescription
19+
from launch.actions import (DeclareLaunchArgument, ExecuteProcess, GroupAction,
20+
IncludeLaunchDescription, LogInfo)
21+
from launch.conditions import IfCondition
22+
from launch.launch_description_sources import PythonLaunchDescriptionSource
23+
from launch.substitutions import LaunchConfiguration, TextSubstitution
24+
from nav2_common.launch import ParseMultiRobotPose
25+
26+
27+
def generate_launch_description():
28+
'''
29+
To bringup multi-robot, give arguments robot name(which is namespace)
30+
and pose for initialization.
31+
Keep general yaml format.
32+
ex) robots:="robot1={x: 1.0, y: 1.0, yaw: 1.5707}; robot2={x: 1.0, y: 1.0, yaw: 1.5707}"
33+
ex) robots:="robot3={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707};
34+
robot4={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}"
35+
'''
36+
37+
# Get the launch directory
38+
bringup_dir = get_package_share_directory('nav2_bringup')
39+
launch_dir = os.path.join(bringup_dir, 'launch')
40+
41+
# Simulation settings
42+
world = LaunchConfiguration('world')
43+
simulator = LaunchConfiguration('simulator')
44+
45+
# On this example all robots are launched with the same settings
46+
map_yaml_file = LaunchConfiguration('map')
47+
params_file = LaunchConfiguration('params_file')
48+
autostart = LaunchConfiguration('autostart')
49+
rviz_config_file = LaunchConfiguration('rviz_config')
50+
use_robot_state_pub = LaunchConfiguration('use_robot_state_pub')
51+
use_rviz = LaunchConfiguration('use_rviz')
52+
log_settings = LaunchConfiguration('log_settings', default='true')
53+
54+
# Declare the launch arguments
55+
declare_world_cmd = DeclareLaunchArgument(
56+
'world',
57+
default_value=os.path.join(bringup_dir, 'worlds', 'world_only.model'),
58+
description='Full path to world file to load')
59+
60+
declare_simulator_cmd = DeclareLaunchArgument(
61+
'simulator',
62+
default_value='gazebo',
63+
description='The simulator to use (gazebo or gzserver)')
64+
65+
declare_map_yaml_cmd = DeclareLaunchArgument(
66+
'map',
67+
default_value=os.path.join(bringup_dir, 'maps', 'turtlebot3_world.yaml'),
68+
description='Full path to map file to load')
69+
70+
declare_params_file_cmd = DeclareLaunchArgument(
71+
'params_file',
72+
default_value=os.path.join(bringup_dir, 'params', 'nav2_multirobot_params_all.yaml'),
73+
description='Full path to the ROS2 parameters file to use for all launched nodes')
74+
75+
declare_autostart_cmd = DeclareLaunchArgument(
76+
'autostart', default_value='false',
77+
description='Automatically startup the stacks')
78+
79+
declare_rviz_config_file_cmd = DeclareLaunchArgument(
80+
'rviz_config',
81+
default_value=os.path.join(bringup_dir, 'rviz', 'nav2_namespaced_view.rviz'),
82+
description='Full path to the RVIZ config file to use.')
83+
84+
declare_use_robot_state_pub_cmd = DeclareLaunchArgument(
85+
'use_robot_state_pub',
86+
default_value='True',
87+
description='Whether to start the robot state publisher')
88+
89+
declare_use_rviz_cmd = DeclareLaunchArgument(
90+
'use_rviz',
91+
default_value='True',
92+
description='Whether to start RVIZ')
93+
94+
# Start Gazebo with plugin providing the robot spawning service
95+
start_gazebo_cmd = ExecuteProcess(
96+
cmd=[simulator, '--verbose', '-s', 'libgazebo_ros_init.so',
97+
'-s', 'libgazebo_ros_factory.so', world],
98+
output='screen')
99+
100+
robots_list = ParseMultiRobotPose('robots').value()
101+
102+
# Define commands for launching the navigation instances
103+
bringup_cmd_group = []
104+
for robot_name in robots_list:
105+
init_pose = robots_list[robot_name]
106+
group = GroupAction([
107+
LogInfo(msg=['Launching namespace=', robot_name, ' init_pose=', str(init_pose)]),
108+
109+
IncludeLaunchDescription(
110+
PythonLaunchDescriptionSource(
111+
os.path.join(launch_dir, 'rviz_launch.py')),
112+
condition=IfCondition(use_rviz),
113+
launch_arguments={'namespace': TextSubstitution(text=robot_name),
114+
'use_namespace': 'True',
115+
'rviz_config': rviz_config_file}.items()),
116+
117+
IncludeLaunchDescription(
118+
PythonLaunchDescriptionSource(os.path.join(bringup_dir,
119+
'launch',
120+
'tb3_simulation_launch.py')),
121+
launch_arguments={'namespace': robot_name,
122+
'use_namespace': 'True',
123+
'map': map_yaml_file,
124+
'use_sim_time': 'True',
125+
'params_file': params_file,
126+
'autostart': autostart,
127+
'use_rviz': 'False',
128+
'use_simulator': 'False',
129+
'headless': 'False',
130+
'use_robot_state_pub': use_robot_state_pub,
131+
'x_pose': TextSubstitution(text=str(init_pose['x'])),
132+
'y_pose': TextSubstitution(text=str(init_pose['y'])),
133+
'z_pose': TextSubstitution(text=str(init_pose['z'])),
134+
'roll': TextSubstitution(text=str(init_pose['roll'])),
135+
'pitch': TextSubstitution(text=str(init_pose['pitch'])),
136+
'yaw': TextSubstitution(text=str(init_pose['yaw'])),
137+
'robot_name':TextSubstitution(text=robot_name), }.items())
138+
])
139+
140+
bringup_cmd_group.append(group)
141+
142+
# Create the launch description and populate
143+
ld = LaunchDescription()
144+
145+
# Declare the launch options
146+
ld.add_action(declare_simulator_cmd)
147+
ld.add_action(declare_world_cmd)
148+
ld.add_action(declare_map_yaml_cmd)
149+
ld.add_action(declare_params_file_cmd)
150+
ld.add_action(declare_use_rviz_cmd)
151+
ld.add_action(declare_autostart_cmd)
152+
ld.add_action(declare_rviz_config_file_cmd)
153+
ld.add_action(declare_use_robot_state_pub_cmd)
154+
155+
# Add the actions to start gazebo, robots and simulations
156+
ld.add_action(start_gazebo_cmd)
157+
158+
ld.add_action(LogInfo(msg=['number_of_robots=', str(len(robots_list))]))
159+
160+
ld.add_action(LogInfo(condition=IfCondition(log_settings),
161+
msg=['map yaml: ', map_yaml_file]))
162+
ld.add_action(LogInfo(condition=IfCondition(log_settings),
163+
msg=['params yaml: ', params_file]))
164+
ld.add_action(LogInfo(condition=IfCondition(log_settings),
165+
msg=['rviz config file: ', rviz_config_file]))
166+
ld.add_action(LogInfo(condition=IfCondition(log_settings),
167+
msg=['using robot state pub: ', use_robot_state_pub]))
168+
ld.add_action(LogInfo(condition=IfCondition(log_settings),
169+
msg=['autostart: ', autostart]))
170+
171+
for cmd in bringup_cmd_group:
172+
ld.add_action(cmd)
173+
174+
return ld

nav2_common/nav2_common/launch/__init__.py

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,3 +15,4 @@
1515
from .has_node_params import HasNodeParams
1616
from .rewritten_yaml import RewrittenYaml
1717
from .replace_string import ReplaceString
18+
from .parse_multirobot_pose import ParseMultiRobotPose
Lines changed: 82 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,82 @@
1+
# Copyright (c) 2023 LG Electronics.
2+
#
3+
# Licensed under the Apache License, Version 2.0 (the "License");
4+
# you may not use this file except in compliance with the License.
5+
# You may obtain a copy of the License at
6+
#
7+
# http://www.apache.org/licenses/LICENSE-2.0
8+
#
9+
# Unless required by applicable law or agreed to in writing, software
10+
# distributed under the License is distributed on an "AS IS" BASIS,
11+
# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
# See the License for the specific language governing permissions and
13+
# limitations under the License.
14+
15+
import yaml
16+
import sys
17+
from typing import Text, Dict
18+
19+
20+
class ParseMultiRobotPose():
21+
"""
22+
Parsing argument using sys module
23+
"""
24+
25+
def __init__(self, target_argument: Text):
26+
"""
27+
Parse arguments for multi-robot's pose
28+
29+
for example,
30+
`ros2 launch nav2_bringup bringup_multirobot_launch.py
31+
robots:="robot1={x: 1.0, y: 1.0, yaw: 0.0};
32+
robot2={x: 1.0, y: 1.0, z: 1.0, roll: 0.0, pitch: 1.5707, yaw: 1.5707}"`
33+
34+
`target_argument` shall be 'robots'.
35+
Then, this will parse a string value for `robots` argument.
36+
37+
Each robot name which is corresponding to namespace and pose of it will be separted by `;`.
38+
The pose consists of x, y and yaw with YAML format.
39+
40+
:param: target argument name to parse
41+
"""
42+
self.__args: Text = self.__parse_argument(target_argument)
43+
44+
def __parse_argument(self, target_argument: Text) -> Text:
45+
"""
46+
get value of target argument
47+
"""
48+
if len(sys.argv) > 4:
49+
argv = sys.argv[4:]
50+
for arg in argv:
51+
if arg.startswith(target_argument + ":="):
52+
return arg.replace(target_argument + ":=", "")
53+
return ""
54+
55+
def value(self) -> Dict:
56+
"""
57+
get value of target argument
58+
"""
59+
args = self.__args
60+
parsed_args = list() if len(args) == 0 else args.split(';')
61+
multirobots = dict()
62+
for arg in parsed_args:
63+
key_val = arg.strip().split('=')
64+
if len(key_val) != 2:
65+
continue
66+
key = key_val[0].strip()
67+
val = key_val[1].strip()
68+
robot_pose = yaml.safe_load(val)
69+
if 'x' not in robot_pose:
70+
robot_pose['x'] = 0.0
71+
if 'y' not in robot_pose:
72+
robot_pose['y'] = 0.0
73+
if 'z' not in robot_pose:
74+
robot_pose['z'] = 0.0
75+
if 'roll' not in robot_pose:
76+
robot_pose['roll'] = 0.0
77+
if 'pitch' not in robot_pose:
78+
robot_pose['pitch'] = 0.0
79+
if 'yaw' not in robot_pose:
80+
robot_pose['yaw'] = 0.0
81+
multirobots[key] = robot_pose
82+
return multirobots

0 commit comments

Comments
 (0)