|
| 1 | +.. _costmap_multirobot: |
| 2 | + |
| 3 | +=================================== |
| 4 | +Multi-Robot Navigation with EasyNav |
| 5 | +=================================== |
| 6 | + |
| 7 | +This HowTo demonstrates how to run multiple EasyNav robots simultaneously in a shared simulation. |
| 8 | +Each robot operates independently using its own namespaced set of nodes, topics, and frames. |
| 9 | + |
| 10 | +.. contents:: On this page |
| 11 | + :local: |
| 12 | + :depth: 2 |
| 13 | + |
| 14 | +Overview |
| 15 | +-------- |
| 16 | + |
| 17 | +.. raw:: html |
| 18 | + |
| 19 | + <div align="center"> |
| 20 | + <iframe width="450" height="300" src="https://www.youtube.com/embed/BDOEr_L4mq8" frameborder="0" allowfullscreen></iframe> |
| 21 | + </div> |
| 22 | + |
| 23 | +Multi-robot navigation with EasyNav is straightforward, but it **requires discipline** when naming topics and managing TF frames. |
| 24 | +This tutorial explains how to set up multiple robots safely without topic or TF conflicts. |
| 25 | + |
| 26 | +--- |
| 27 | + |
| 28 | +Setup |
| 29 | +----- |
| 30 | + |
| 31 | +Before starting, make sure you have followed the installation instructions in :doc:`../build_install/index`. |
| 32 | +Then ensure that your workspace includes at least: |
| 33 | + |
| 34 | +- ``EasyNavigation`` |
| 35 | +- ``easynav_plugins`` |
| 36 | +- ``easynav_playground_kobuki`` |
| 37 | +- ``easynav_indoor_testcase`` |
| 38 | + |
| 39 | +and that everything builds correctly: |
| 40 | + |
| 41 | +.. code-block:: bash |
| 42 | +
|
| 43 | + cd ~/ros/ros2/easynav_ws |
| 44 | + colcon build --symlink-install |
| 45 | + source install/setup.bash |
| 46 | +
|
| 47 | +--- |
| 48 | + |
| 49 | +1. Topic Naming and TF Management (Plugin developers) |
| 50 | +----------------------------------------------------- |
| 51 | + |
| 52 | +### Fully-qualified topic names |
| 53 | + |
| 54 | +Each plugin should publish topics under its **fully qualified name**, which includes the node and plugin names. |
| 55 | +This prevents collisions when several robots run the same plugins. |
| 56 | + |
| 57 | +Example (in C++): |
| 58 | + |
| 59 | +.. code-block:: cpp |
| 60 | +
|
| 61 | + path_pub_ = node->create_publisher<nav_msgs::msg::Path>( |
| 62 | + node->get_fully_qualified_name() + std::string("/") + plugin_name + "/path", |
| 63 | + 10); |
| 64 | +
|
| 65 | +This ensures topics look like: |
| 66 | + |
| 67 | +``/r1/controller_node/simple/path`` |
| 68 | +``/r2/controller_node/simple/path`` |
| 69 | + |
| 70 | +instead of clashing on ``/path``. |
| 71 | + |
| 72 | +--- |
| 73 | + |
| 74 | +### TF topic remapping |
| 75 | + |
| 76 | +Each robot typically has its **own TF tree**. |
| 77 | +To isolate TF data, remap the global TF topics (``/tf`` and ``/tf_static``) to **relative ones**, |
| 78 | +so they are automatically namespaced: |
| 79 | + |
| 80 | +.. code-block:: bash |
| 81 | +
|
| 82 | + -r /tf:=tf -r /tf_static:=tf_static |
| 83 | +
|
| 84 | +This yields separate TF topics for each robot: |
| 85 | + |
| 86 | +``/r1/tf`` and ``/r1/tf_static`` |
| 87 | +``/r2/tf`` and ``/r2/tf_static`` |
| 88 | + |
| 89 | +.. note:: |
| 90 | + |
| 91 | + Do **not** apply this remap if both robots are designed to share the same TF tree (which is rare). |
| 92 | + |
| 93 | +--- |
| 94 | + |
| 95 | +### Namespaced frames |
| 96 | + |
| 97 | +If you configure a TF prefix for each system node (e.g., ``tf_prefix: r1``), |
| 98 | +then all frames will include this prefix: |
| 99 | + |
| 100 | +``r1/map``, ``r1/odom``, ``r1/base_link``, etc. |
| 101 | + |
| 102 | +Example configuration snippet: |
| 103 | + |
| 104 | +.. code-block:: yaml |
| 105 | +
|
| 106 | + r1/system_node: |
| 107 | + ros__parameters: |
| 108 | + use_sim_time: true |
| 109 | + use_real_time: true |
| 110 | + position_tolerance: 0.1 |
| 111 | + angle_tolerance: 0.05 |
| 112 | + tf_prefix: r1 |
| 113 | +
|
| 114 | +--- |
| 115 | + |
| 116 | +2. Launching in Simulation |
| 117 | +-------------------------- |
| 118 | + |
| 119 | +### Step 1 — Start the simulator with two robots |
| 120 | + |
| 121 | +The multi-robot launch file spawns two Kobuki robots within the same Gazebo world: |
| 122 | + |
| 123 | +.. code-block:: bash |
| 124 | +
|
| 125 | + ros2 launch easynav_playground_kobuki playground_multirobot_kobuki.launch.py do_tf_remapping:=true gui:=false |
| 126 | +
|
| 127 | +.. note:: |
| 128 | + |
| 129 | + If your launch file uses a different name, adjust the command accordingly. |
| 130 | + |
| 131 | +--- |
| 132 | + |
| 133 | +### Step 2 — Start EasyNav for each robot |
| 134 | + |
| 135 | +Run the EasyNav system for each robot in **separate terminals**. |
| 136 | +Each instance uses the same parameter file but with its own namespace and TF remapping. |
| 137 | + |
| 138 | +**Terminal 1 (robot r1):** |
| 139 | + |
| 140 | +.. code-block:: bash |
| 141 | +
|
| 142 | + ros2 run easynav_system system_main \ |
| 143 | + --ros-args \ |
| 144 | + --params-file ~/ros/ros2/easynav_ws/src/easynav_indoor_testcase/robots_params/costmap_multirobot.params.yaml \ |
| 145 | + -r __ns:=r1 \ |
| 146 | + -r /tf:=tf -r /tf_static:=tf_static |
| 147 | +
|
| 148 | +**Terminal 2 (robot r2):** |
| 149 | + |
| 150 | +.. code-block:: bash |
| 151 | +
|
| 152 | + ros2 run easynav_system system_main \ |
| 153 | + --ros-args \ |
| 154 | + --params-file ~/ros/ros2/easynav_ws/src/easynav_indoor_testcase/robots_params/costmap_multirobot.params.yaml \ |
| 155 | + -r __ns:=r2 \ |
| 156 | + -r /tf:=tf -r /tf_static:=tf_static |
| 157 | +
|
| 158 | +--- |
| 159 | + |
| 160 | +### Step 3 — Launch RViz for each robot |
| 161 | + |
| 162 | +Open one RViz window per robot namespace to visualize each navigation stack independently: |
| 163 | + |
| 164 | +.. code-block:: bash |
| 165 | +
|
| 166 | + ros2 launch easynav_playground_kobuki rviz_namespaced.launch.py \ |
| 167 | + namespace:=r1 use_sim_time:=true \ |
| 168 | + rviz_config_file:=~/ros/ros2/easynav_ws/src/easynav_playground_kobuki/rviz/nav2_namespaced_view.rviz |
| 169 | +
|
| 170 | + ros2 launch easynav_playground_kobuki rviz_namespaced.launch.py \ |
| 171 | + namespace:=r2 use_sim_time:=true \ |
| 172 | + rviz_config_file:=~/ros/ros2/easynav_ws/src/easynav_playground_kobuki/rviz/nav2_namespaced_view.rviz |
| 173 | +
|
| 174 | +You can now send **2D Goal Poses** independently in each RViz instance. |
| 175 | + |
| 176 | +--- |
| 177 | + |
| 178 | +3. Example Parameters |
| 179 | +--------------------- |
| 180 | + |
| 181 | +Below is a complete example parameter file for two robots. |
| 182 | +Each section is namespaced (``r1/...``, ``r2/...``), so the same plugins can operate without topic or TF collisions. |
| 183 | + |
| 184 | +.. code-block:: yaml |
| 185 | +
|
| 186 | + r1/controller_node: |
| 187 | + ros__parameters: |
| 188 | + use_sim_time: true |
| 189 | + controller_types: [simple] |
| 190 | + simple: |
| 191 | + rt_freq: 30.0 |
| 192 | + plugin: easynav_simple_controller/SimpleController |
| 193 | + max_linear_speed: 1.0 |
| 194 | + max_angular_speed: 1.5 |
| 195 | + look_ahead_dist: 0.2 |
| 196 | + k_rot: 0.7 |
| 197 | +
|
| 198 | + r1/localizer_node: |
| 199 | + ros__parameters: |
| 200 | + use_sim_time: true |
| 201 | + localizer_types: [costmap] |
| 202 | + costmap: |
| 203 | + rt_freq: 50.0 |
| 204 | + freq: 5.0 |
| 205 | + reseed_freq: 1.0 |
| 206 | + plugin: easynav_costmap_localizer/AMCLLocalizer |
| 207 | + num_particles: 100 |
| 208 | + noise_translation: 0.05 |
| 209 | + noise_rotation: 0.1 |
| 210 | + noise_translation_to_rotation: 0.1 |
| 211 | + initial_pose: |
| 212 | + x: 0.0 |
| 213 | + y: 0.0 |
| 214 | + yaw: 0.0 |
| 215 | + std_dev_xy: 0.1 |
| 216 | + std_dev_yaw: 0.01 |
| 217 | +
|
| 218 | + r1/maps_manager_node: |
| 219 | + ros__parameters: |
| 220 | + use_sim_time: true |
| 221 | + map_types: [costmap] |
| 222 | + costmap: |
| 223 | + freq: 10.0 |
| 224 | + plugin: easynav_costmap_maps_manager/CostmapMapsManager |
| 225 | + package: easynav_indoor_testcase |
| 226 | + map_path_file: maps/home2.yaml |
| 227 | + filters: [obstacles, inflation] |
| 228 | + obstacles: |
| 229 | + plugin: easynav_costmap_maps_manager/ObstacleFilter |
| 230 | + inflation: |
| 231 | + plugin: easynav_costmap_maps_manager/InflationFilter |
| 232 | + inflation_radius: 1.3 |
| 233 | + cost_scaling_factor: 3.0 |
| 234 | +
|
| 235 | + r1/planner_node: |
| 236 | + ros__parameters: |
| 237 | + use_sim_time: true |
| 238 | + planner_types: [simple] |
| 239 | + simple: |
| 240 | + freq: 0.5 |
| 241 | + plugin: easynav_costmap_planner/CostmapPlanner |
| 242 | + cost_factor: 10.0 |
| 243 | +
|
| 244 | + r1/sensors_node: |
| 245 | + ros__parameters: |
| 246 | + use_sim_time: true |
| 247 | + forget_time: 0.5 |
| 248 | + sensors: [laser1] |
| 249 | + perception_default_frame: odom |
| 250 | + laser1: |
| 251 | + topic: scan_raw |
| 252 | + type: sensor_msgs/msg/LaserScan |
| 253 | + group: points |
| 254 | + camera1: |
| 255 | + topic: rgbd_camera/points |
| 256 | + type: sensor_msgs/msg/PointCloud2 |
| 257 | + group: points |
| 258 | +
|
| 259 | + r1/system_node: |
| 260 | + ros__parameters: |
| 261 | + use_sim_time: true |
| 262 | + use_real_time: true |
| 263 | + position_tolerance: 0.1 |
| 264 | + angle_tolerance: 0.05 |
| 265 | + tf_prefix: r1 |
| 266 | +
|
| 267 | + # Robot 2 (r2) - identical configuration with different initial pose and TF prefix |
| 268 | +
|
| 269 | + r2/controller_node: |
| 270 | + ros__parameters: |
| 271 | + use_sim_time: true |
| 272 | + controller_types: [simple] |
| 273 | + simple: |
| 274 | + rt_freq: 30.0 |
| 275 | + plugin: easynav_simple_controller/SimpleController |
| 276 | + max_linear_speed: 1.0 |
| 277 | + max_angular_speed: 1.5 |
| 278 | + look_ahead_dist: 0.2 |
| 279 | + k_rot: 0.7 |
| 280 | +
|
| 281 | + r2/localizer_node: |
| 282 | + ros__parameters: |
| 283 | + use_sim_time: true |
| 284 | + localizer_types: [costmap] |
| 285 | + costmap: |
| 286 | + rt_freq: 50.0 |
| 287 | + freq: 5.0 |
| 288 | + reseed_freq: 1.0 |
| 289 | + plugin: easynav_costmap_localizer/AMCLLocalizer |
| 290 | + num_particles: 100 |
| 291 | + noise_translation: 0.05 |
| 292 | + noise_rotation: 0.1 |
| 293 | + noise_translation_to_rotation: 0.1 |
| 294 | + initial_pose: |
| 295 | + x: 2.0 |
| 296 | + y: 1.0 |
| 297 | + yaw: 0.0 |
| 298 | + std_dev_xy: 0.1 |
| 299 | + std_dev_yaw: 0.01 |
| 300 | +
|
| 301 | + r2/maps_manager_node: |
| 302 | + ros__parameters: |
| 303 | + use_sim_time: true |
| 304 | + map_types: [costmap] |
| 305 | + costmap: |
| 306 | + freq: 10.0 |
| 307 | + plugin: easynav_costmap_maps_manager/CostmapMapsManager |
| 308 | + package: easynav_indoor_testcase |
| 309 | + map_path_file: maps/home2.yaml |
| 310 | + filters: [obstacles, inflation] |
| 311 | + obstacles: |
| 312 | + plugin: easynav_costmap_maps_manager/ObstacleFilter |
| 313 | + inflation: |
| 314 | + plugin: easynav_costmap_maps_manager/InflationFilter |
| 315 | + inflation_radius: 1.3 |
| 316 | + cost_scaling_factor: 3.0 |
| 317 | +
|
| 318 | + r2/planner_node: |
| 319 | + ros__parameters: |
| 320 | + use_sim_time: true |
| 321 | + planner_types: [simple] |
| 322 | + simple: |
| 323 | + freq: 0.5 |
| 324 | + plugin: easynav_costmap_planner/CostmapPlanner |
| 325 | + cost_factor: 10.0 |
| 326 | +
|
| 327 | + r2/sensors_node: |
| 328 | + ros__parameters: |
| 329 | + use_sim_time: true |
| 330 | + forget_time: 0.5 |
| 331 | + sensors: [laser1] |
| 332 | + perception_default_frame: odom |
| 333 | + laser1: |
| 334 | + topic: scan_raw |
| 335 | + type: sensor_msgs/msg/LaserScan |
| 336 | + group: points |
| 337 | + camera1: |
| 338 | + topic: rgbd_camera/points |
| 339 | + type: sensor_msgs/msg/PointCloud2 |
| 340 | + group: points |
| 341 | +
|
| 342 | + r2/system_node: |
| 343 | + ros__parameters: |
| 344 | + use_sim_time: true |
| 345 | + use_real_time: true |
| 346 | + position_tolerance: 0.1 |
| 347 | + angle_tolerance: 0.05 |
| 348 | + tf_prefix: r2 |
| 349 | +
|
| 350 | +--- |
| 351 | + |
| 352 | +Tips & Gotchas |
| 353 | +-------------- |
| 354 | + |
| 355 | +- **Namespaces everywhere:** |
| 356 | + Verify all relative topics (e.g., ``scan_raw``) are correctly resolved under each robot namespace (``/r1/scan_raw``, ``/r2/scan_raw``). |
| 357 | + |
| 358 | +- **Avoid over-remapping:** |
| 359 | + Only remap ``/tf`` and ``/tf_static`` to relative topics when each robot manages its own TF tree. |
| 360 | + |
| 361 | +- **Frame references:** |
| 362 | + With ``tf_prefix`` set, refer to frames as ``r1/base_link``, ``r1/odom``, etc. |
| 363 | + |
| 364 | +- **ROS Domain IDs:** |
| 365 | + If you want isolation or multiple networks, assign different ``ROS_DOMAIN_ID`` per fleet. |
| 366 | + Otherwise, keep the same domain for shared visualization. |
| 367 | + |
| 368 | +--- |
| 369 | + |
| 370 | +With this setup, each robot runs a full EasyNav navigation stack under its own namespace, |
| 371 | +enabling **coordinated multi-robot simulation** in Gazebo and RViz. |
0 commit comments