Creating and Managing a Multi-Robot Simulation in Gazebo with ROS 2 Foxy: A Guide for Scalable TurtleBot3 Deployment

Arshad Mehmood
9 min readMay 18, 2023

This article presents a comprehensive guide on how to launch multiple TurtleBot3 robots in a Gazebo simulation using ROS 2 Foxy using individual namespaces. The tutorial provides a robust and systematic procedure for sequentially deploying a fleet of 30 robots into Gazebo environment that prevent an overload of service requests that could crash server. Each robot is assigned a unique namespace, facilitating easy identification and control.

The configuration of the Gazebo physics engine is customized to effectively manage interactions between the robot entities, ensuring real-time simulation behavior. A time step size of 20 milliseconds has been chosen for the physics engine updates, which typically take about 12 milliseconds for all 30 robots, allowing the simulation to run smoothly at a real-time factor of 1.

In addition, the guide outlines how to organize a grid of robots based on rows and columns, with namespaces assigned based on their positions. It also highlights how the ROS 2 remapping feature is utilized to maintain accurate spatial relationships between the robots by redirecting TF messages to the appropriate namespace.

Ultimately, this article can serve as a starting guide for creating a scalable and efficient multi-robot simulation environment, with emphasis on structured deployment, effective physics engine configuration, systematic robot naming and positioning, and efficient TF message handling.

Prerequisites

Before proceeding, make sure you have the following prerequisites:

  1. ROS 2 Foxy: The ROS 2 Foxy software must be installed on your system. For installation instructions, you can visit the official ROS documentation. Repo has been validated on ROS2 Humble too. Please use repo’s master branch for that.
  2. Gazebo Simulator: You will also need the Gazebo simulator installed on your computer. You can find installation guide online or on the Gazebo website.
  3. TurtleBot3 ROS 2 Packages: Finally, make sure to have the TurtleBot3 ROS 2 packages installed on your machine. Instructions for this can be found in the TurtleBot3 documentation.

Launching Multiple TurtleBot3 Robots

To alter the TurtleBot3 models, we need access to the source code. Also, all the necessary dependencies must be installed for smooth operation, and this can be streamlined using rosdep, a command-line tool in ROS. Rosdep installs system dependencies automatically, ensuring a ready-to-use environment with provided modifications.

Clone repo and install dependencies

mkdir -p robot_ws/src
cd robot_ws/src

git clone https://github.com/arshadlab/turtlebot3_multi_robot.git -b foxy

source /opt/ros/foxy/setup.bash
cd robot_ws
rosdep install --from-paths src -r -y

The referenced TurtleBot3 simulation repository already includes the necessary changes that will be discussed further in this guide. Therefore, your primary tasks are to build and launch the simulation environment, as the required modifications have been pre-integrated.

Build and Run

To build and run the Gazebo environment, follow these steps:

  1. Navigate to the robot_ws directory: cd robot_ws/
  2. Build the workspace: colcon build --symlink-install
  3. Source the setup file: source ./install/setup.bash
  4. Launch the simulation: ros2 launch turtlebot3_gazebo multi_turtlebot3_world.launch.py
cd robot_ws/
colcon build --symlink-install
source ./install/setup.bash
ros2 launch turtlebot3_multi_robot gazebo_multi_world.launch.py
Gazebo launch with 30 robots

Within the launch script for the simulation, robot drive nodes are automatically initialized to control the movement and behavior of the robots. However, there’s a launch parameter enable_drive which can be adjusted to enable or disable this function based on your needs. By default, enable_drive is set to True, which means the drive nodes will be activated immediately as part of the script execution. If you wish to disable the drive nodes initially, you can set enable_drive to False at launch time

ros2 node list output:

$ ros2 node list
/gazebo
/spawn_entity
/tb0_0/robot_state_publisher
/tb0_0/turtlebot3_diff_drive
/tb0_0/turtlebot3_drive_node
/tb0_0/turtlebot3_imu
/tb0_0/turtlebot3_joint_state
/tb0_0/turtlebot3_laserscan
/tb0_1/robot_state_publisher
/tb0_1/turtlebot3_drive_node
/tb0_1/turtlebot3_diff_drive
/tb0_1/turtlebot3_imu
/tb0_1/turtlebot3_joint_state
/tb0_1/turtlebot3_laserscan
...
...
/tb4_4/robot_state_publisher
/tb4_4/turtlebot3_diff_drive
/tb4_4/turtlebot3_drive_node
/tb4_4/turtlebot3_imu
/tb4_4/turtlebot3_joint_state
/tb4_4/turtlebot3_laserscan

Launching without drive nodes

Alternatively you can launch environment without drive nodes. This will require drive node to be run explicitly in console.

Console A:

ros2 launch turtlebot3_multi_robot gazebo_multi_world.launch.py enable_drive:=False

Console B:

Drive turtlebot3 under namespace /tb0_3

Syntax:

ros2 run turtlebot3_gazebo turtlebot3_drive — ros-args -r __ns:=<robot_namespace>

cd robot_ws/
source ./install/setup.bash
ros2 run turtlebot3_gazebo turtlebot3_drive --ros-args -r __ns:=/tb0_3
Robot with namespace 0_3 moving

Summary of Changes:

  1. A new launch file created. This file initiates the world environment and spawns the robots.
  2. The Turtlebot3 (Burger) model updated to handle tf remapping. Additionally, namespaces tags within plugin tags are disabled.
  3. A world file for spawning Turtlebots added. This file provides an empty world with a simple wall bounded area.

Source Code

Under the hood

In a multi-robot ROS2 environment, namespaces play a crucial role in ensuring the proper coordination and management of multiple robots. By providing a distinct namespace for each robot, it allows for the isolation and organization of topics, services, and parameters specific to each robot. This separation prevents naming conflicts and allows for seamless communication and control of individual robots within the system. Namespaces enable the development of modular and scalable robot systems, where different robots can operate concurrently without interfering with each other. Moreover, namespaces facilitate easy identification and understanding of the components related to each robot, making the system more maintainable and extensible. Overall, namespaces are essential for establishing a well-structured and efficient multi-robot environment in ROS2.

Gazebo Physics Engine configuration

In this simulation setup, the physics engine’s configurations are tailored to effectively manage the interactions of 30 robot entities. I have chosen a physics engine time step size of 20 milliseconds. This step size dictates the frequency at which the physics engine computes the new states of all objects in the simulation, based on the forces and torques acting on them.

In our scenario, each physics engine update cycle takes approximately 12 milliseconds (on TGL i7 NUC with 16 GB RAM) to complete for all 30 robots. Given that the time step size is 20 milliseconds, this setup allows ample time for each update to be computed within the time step duration. The remaining 8 milliseconds serve as a buffer to account for any computational delays or overheads.

Time chart of Gazebo physics update

As you can see from above chart obtain by method explained in article, the duration from one update to another update is ~20 which each update spending around ~12 milliseconds giving enough time for gazebo to prepare to next update.

This configuration ensures that the simulation can run at a real-time factor of 1. In other words, the simulation time and the real-world time stay in sync, making the simulation’s outputs accurately reflect the real-time behaviors of the system. The choice of step size is crucial in balancing computational load and simulation accuracy, and in our case, the 20-millisecond step provides a robust setup for managing the physics of our 30 robot entities efficiently.

empty.world file

<physics type="ode">
<real_time_update_rate>50</real_time_update_rate>
<max_step_size>0.020</max_step_size>
<real_time_factor>1</real_time_factor>
...
</physics>

Sequential robot launching

A robust and sequenced launch procedure is developed for deploying a fleet of 30 TurtleBot robots in a Gazebo simulation environment. The process begins by launching the Gazebo server (gzserver) and client (gzclient) with an empty world that contains nothing more than a wall to confine the robots.

To avoid overwhelming the system and potentially crashing the Gazebo server, a sequential spawning mechanism is implemented using spawn_entity.py. This approach ensures that each TurtleBot robot instance is fully launched before initiating the spawning process for the subsequent robot. This step also includes starting the robot_state_publisher for each robot which is an essential tool in a ROS (Robot Operating System) environment. It publishes the state of a robot, represented as transformations between different coordinate frames using tf2 (Transform) library in ROS. The key to this process is its sequential nature, which prevents a mass influx of simultaneous spawn_entity service requests that could destabilize the Gazebo server.

Once all the robots have been successfully spawned into the environment, the script then proceed to launch the robot driver nodes, which control the movement and behavior of the robots. The activation of these nodes is governed by a launch parameter, which provides us the flexibility to control their initiation. By default, this parameter is set to enable the drive nodes immediately after all the robots are spawned.

This systematic procedure ensures a stable, controlled, and resource-conscious deployment of multiple robots in a simulated environment, thereby promoting efficient experimentation and testing.

Namespace naming

The implementation aims to deploy a grid of robots in Gazebo using spawn_entity.py. The grid is organized by a specified number of rows and columns. Each robot is assigned a unique namespace based on its position in the grid, thereby ensuring a structured and easily identifiable system for robot interaction and control. The namespace is assigned as /tb<i>_<y>, where <i> corresponds to the row index and <y> is the column index of the robot's position within the grid. This standardized naming and organization enable streamlined operations, facilitating efficient communication, and interaction across all the robot entities within the simulation. This arrangement also provides an easy way to reference individual robots, especially when monitoring, controlling, or debugging specific units in the simulation.

Refer to the node list output shown earlier.

/tf and /tf_static mapping

In ROS2, namespaces are a powerful mechanism for organizing and isolating topics, services, and parameters. However, when it comes to the /tf and /tf_static topics, namespaces alone are not sufficient due to the nature of the Transform (TF) system. The TF system provides hierarchical relationships between coordinate frames, and these relationships are defined globally across the entire system. As a result, TF messages are broadcasted and listened to by all nodes, regardless of their namespace.

To address this limitation, ROS2 provides the remapping mode for /tf and /tf_static topics. Remapping allows for the redirection of TF messages between different namespaces. With remapping, robots operating in different namespaces can still communicate and understand the correct coordinate frames by redirecting TF messages to the appropriate namespace. This ensures that the TF system functions seamlessly in a multi-robot environment, allowing robots to maintain accurate spatial relationships despite their namespaces.

A generic /tf remapping is needed for both state publisher and for the diff drive plugin in .sdf file. The namespace parameter during node creations does take care of the rest.

State publisher node in launch file is provided namespace and remapping for accurately receiving joint_states from its related robot and publishing /tf and /tf_static topics

  namespace='/tb' + str(i) + "_" + str(j)

# Create state publisher node for that instance
turtlebot_state_publisher = Node(
package='robot_state_publisher',
namespace=namespace,
executable='robot_state_publisher',
output='screen',
parameters=[{'use_sim_time': False, 'publish_frequency': 10.0}],
remappings=remappings,
arguments=[urdf])

The differential drive mapping within the Simulation Description Format (SDF) file is key to its movement, as it translates linear and angular velocities into appropriate wheel speeds. However, to offer greater flexibility in multi-robot simulations, the namespace tag is intentionally disabled in the SDF file. Instead, unique namespaces are dynamically assigned to each Turtlebot3 instance at runtime using the spawn_entity.sh script. This strategy helps avoid any overlap between different robots’ topics, services, and actions, thus enhancing the organization and control in a multi-robot simulation. Additionally, the /tf and /tf_static topics are remapped to each robot's unique namespace using remapping tags. This process maintains accurate coordinate frame relationships among the multiple robots, ensuring effective communication and coordination.

<plugin name="turtlebot3_diff_drive" filename="libgazebo_ros_diff_drive.so">
<ros>
<!--<namespace>/tb3</namespace>-->
<remapping>/tf:=tf</remapping>
</ros>
<update_rate>10</update_rate>
...
</plugin>

/tf and /tf_static per Robot

This implementation adheres to the scheme of having each robot with its own tf tree published under its specific namespace (e.g., /tb1/tf) without the use of tf_prefix. Currently, the map server is created individually for each robot, but as a future enhancement, it can be created once for all the robots, optimizing resource utilization and improving efficiency.

tf tree for tb0_0 and tb0_1 robots

Conclusion

This article provides a comprehensive tutorial on launching multiple TurtleBot3 robots in a Gazebo simulation using ROS 2 Foxy. The guide meticulously details a sequence of launching that avoids server crashes by regulating service requests. Additionally, the physics engine configuration of Gazebo is tailored to ensure an accurate and real-time simulation behavior. The tutorial further explains how robots can be systematically deployed in a grid-like structure, with each robot assigned a unique namespace based on its position. It also sheds light on the utility of ROS 2’s remapping feature for managing Transform messages between robots, thereby maintaining precise spatial relationships in a multi-robot environment. Overall, the guide is a robust resource for those aiming to create a well-structured, efficient, and scalable multi-robot system.

Source Code

--

--

Arshad Mehmood

As the technical lead at Intel Corporation, my work orbits around the intriguing world of Robotics and Artificial Intelligence.