Main Content

Sign Following Robot with Time Synchronization Using ROS and Gazebo Co-Simulation

This example shows how to use Simulink® to enable synchronized simulation between ROS and the Gazebo robot simulator using the Gazebo Pacer (Robotics System Toolbox) block.

This example builds upon the Sign-Following Robot with ROS in Simulink example, which does not support synchronized simulation. Unsynchronized simulation can result in sensor data loss or delayed messages and simulation time mismatch. Gazebo Co-Simulation is ROS-independent, which enables it to synchronize the simulation times between Gazebo and Simulink when using the Gazebo Pacer block. For more details about Gazebo Co-Simulation, see Gazebo Simulation for Robotics System Toolbox (Robotics System Toolbox).

Start Robot Simulator

To follow along with this example:

  1. Download and install the virtual machine with ROS and Gazebo. See Setup Gazebo Simulation Environment in Perform Co-Simulation Between Simulink and Gazebo (Robotics System Toolbox).

  2. Start the Ubuntu® virtual machine (VM) desktop.

  3. On the Ubuntu desktop, click Gazebo Sign Follower ROS Co-Sim to start the Gazebo world built for this example.

Open Simulink Model

The Simulink model used in this example is based on the Simulink model used in the Sign-Following Robot with ROS in Simulink example, with the addition of the Gazebo Pacer block.

Open the Simulink model.

open_system("signFollowingRobotROSCoSim.slx")

You can add the Gazebo Pacer block to an existing ROS–Gazebo Simulink model, as shown in the model diagram, to enable synchronized simulation.

Configure Gazebo Pacer Block

Before simulating the model, configure Gazebo Co-Simulation using the Gazebo Pacer block.

open_system("signFollowingRobotROSCoSim/Gazebo Pacer")

Set Reset behavior to Reset Gazebo simulation time and scene.

To configure the connection to the Gazebo simulation, click Configure Gazebo network and simulation settings.

  1. Set Network Address to Custom.

  2. Enter the Hostname/IP Address of the VM.

  3. The default Port number for Gazebo is 14581. Check that the Port value is the same as in the <portnumber> tag in the world file.

  4. Set Response timeout to 10 seconds.

  5. Click Test to test the connection to the running Gazebo simulator.

  6. Click OK to apply your changes.

Configure ROS Network

To configure the network settings for ROS:

  1. From the Simulation tab, in the Prepare group, select ROS Network.

  2. Specify the IP address and port number of the ROS master in Gazebo. For this example, the ROS master in Gazebo is 192.168.145.143:11311. Set Hostname/IP Address to 192.168.145.143 and Port to 11311.

  3. Click OK to apply your changes.

Run Model

Run the model and observe this simulation behavior, in addition to the behavior of the robot in the robot simulator from the Sign-Following Robot with ROS in Simulink example.

  • Simulink Time and Gazebo Time are synchronized.

  • The image readings from the camera are synchronized with the movement of the robot.

  • When you pause the Simulink model, the Gazebo simulation preserves the pause state, and the robot maintains its current position.

Enable Synchronization in Other ROS–Gazebo Examples in VM

To enable synchronization in other ROS–Gazebo examples, follow these steps.

Set Up Gazebo Plugin

  • In the VM for your ROS–Gazebo co-simulation, locate the Gazebo plugin required for synchronized simulation in /home/user/src/GazeboPlugin.

  • To rebuild or replace the plugin, follow the Gazebo plugin manual installation steps in Perform Co-Simulation Between Simulink and Gazebo (Robotics System Toolbox).

Update Gazebo World File

  • Locate the shared library file of the synchronization plugin in /home/user/src/GazeboPlugin/export/lib/libGazeboCoSimPlugin.so.

  • To activate the Gazebo plugin in any Gazebo world, add the shared library file details to the world file.

  • For the Sign-Following Robot with ROS in Simulink example, the world file mw_vision_world_newstopsign.world is located in /home/user/catkin_ws/src/mw_vision_example/worlds.

  • Open the mw_vision_world_newstopsign.world and add these shared library details.

<plugin name="GazeboPlugin" filename="/home/user/src/GazeboPlugin/export/lib/libGazeboCoSimPlugin.so"><portNumber>14581</portNumber></plugin>
  • The code snippet of the updated world file shows the Gazebo plugin tag.