RobotLabs
  • Welcome
  • ESP32
    • PlatformIO
      • 1.1 Arduino Basics
      • 1.2 Install PlatformIO
      • 2.1 GPIO - LED Blink
      • 2.2 GPIO - LED Multi
      • 2.3 GPIO - LED Button
      • 3.1 PWM - LED Fade
      • 3.2 ADC - Analog Input
      • 4.1 IIC - OLED
    • MicroPython
    • ESP32 Projects
  • ROS
    • ROS2 Jazzy
      • 1.1 Install ROS 2 Jazzy
      • 1.2 Install VS Code
      • 1.3 Save ROS code on GitHub
      • 2.1 Create a Mobile Robot with URDF and Visualize it
      • 2.3 Create Launch Files to Display the URDF in RViz
      • 2.4 Simulation with Gazebo
      • 2.5 Gazebo sensors
      • 2.6 Sensor fusion and SLAM
    • MoveIt2
      • Moveit 2 joint position control with keyboard
      • Moveit2 joint velocity control for Panda robot arm
    • Perception
      • PCL-ROS
  • FOC
    • SimpleFOC
      • Install simpleFOC Lib
  • Template
    • Markdown
    • Interactive blocks
    • OpenAPI
    • Integrations
Powered by GitBook
On this page
  • Prerequisite
  • Load Gazebo World
  • 1. Create a new package for Sim
  • 2. Launch Gazebo world from ROS
  • Load URDF files to Gazebo environment
  • Gazebo integration
  • 1. Add Gazebo plugin
  • 2. ROS gz bridge
  • 3. Driving around
  • Mecanum wheel
  1. ROS
  2. ROS2 Jazzy

2.4 Simulation with Gazebo

Previous2.3 Create Launch Files to Display the URDF in RVizNext2.5 Gazebo sensors

Last updated 3 months ago

Gazebo is a powerful robotics simulation tool that provides a 3D environment for simulating robots, sensors, and objects. It is widely used in the ROS ecosystem for testing and developing robotics algorithms in a realistic virtual environment before deploying them to real hardware.

In ROS2 with the latest Gazebo releases the integration is facilitated by ros_gz.

To install Gazebo Harmonic binaries on Ubuntu 24.04 simply follow our or step by step video guide:

Run Gazebo examples

Once it's installed we can try it with the following command:

gz sim shapes.sdf

If you have a problem with opening this example shapes.sdf there might be various reasons that requires some debugging skills with Gazebo and Linux.

  • export QT_QPA_PLATFORM=xcb
  • gz sim shapes.sdf --render-engine ogre
  1. Blue - Start and pause the simulation. By default Gazebo starts the simulation paused but if you add the -r when you start Gazebo it automatically starts the simulation.

  2. Cyan - The display shows the real time factor. It should be always close to 100%, if it drops seriously (below 60-70%) it's recommended to change the simulation step size. We'll see this later.

  3. Red - You can add basic shapes or lights here and you can move and rotate them.

  4. Pink - The model hierarchy, every item in the simulation is shown here, you can check the links (children) of the model, their collision, inertia, etc.

  5. Green - Detailed information of the selected model in 4. some parameters can be changed most of them are read only.

  6. Plug-in browser(top right corner and scroll down to find other plugins), we'll open useful tools like Resource Spawner, Visualize Lidar, Image Display, etc.

You can download models and place them in the home folder of your user. To let Gazebo know about the offline model library we have to set the GZ_SIM_RESOURCE_PATH environmental variable, the best is to add it to the .bashrc:

export GZ_SIM_RESOURCE_PATH=~/gazebo_models

After setting up the offline model library let's open the empty.sdf in Gazebo and add a few models through the Resource Spawner within the plug-in browser:

Prerequisite

If not, there is a start package with URDF files that you can donwload from GitHub. You should download it with the main branch (with the -b branch flag) to your ros workspace:

cd ~/ros2_ws/src/
git clone -b main https://github.com/roboticslabs/mec_mobile.git
cd ~/ros2_ws/src/mec_mobile/mec_mobile_description/urdf

To let Gazebo know about the offline model library we have to set the GZ_SIM_RESOURCE_PATH environmental variable, the best is to add it to the .bashrc:

export GZ_SIM_RESOURCE_PATH=~/gazebo_models

Load Gazebo World

Firstly, make sure you get the start package with URDF files ready.

1. Create a new package for Sim

cd ~/ros2_ws/src/mec_mobile/
ros2 pkg create --build-type ament_cmake mec_mobile_gazebo

Create Gazebo world files

Inside the mec_mobile_gazebo package, create a worlds folder and put the world.sdf files in:

cd ~/ros2_ws/src/mec_mobile/mec_mobile_gazebo
mkdir worlds

You can open the world file with command:

gz sim world.sdf
# If you have problem with the default OGRE2 rendering engine, switch to OGRE:
gz sim world.sdf --render-engine ogre

To edit your own world in Gazebo, use the resource spawner and save it with .sdf extension.

2. Launch Gazebo world from ROS

world.launch.py
import os
from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import  LaunchConfiguration, PathJoinSubstitution, TextSubstitution


def generate_launch_description():

    world_arg = DeclareLaunchArgument(
        'world', default_value='world.sdf',
        description='Name of the Gazebo world file to load'
    )

    pkg_mec_mobile = get_package_share_directory('mec_mobile_gazebo')
    pkg_ros_gz_sim = get_package_share_directory('ros_gz_sim')

    # Add your own gazebo library path here
    gazebo_models_path = "/home/robotlabs/gazebo_models"
    os.environ["GZ_SIM_RESOURCE_PATH"] = os.pathsep + gazebo_models_path


    gazebo_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_ros_gz_sim, 'launch', 'gz_sim.launch.py'),
        ),
        launch_arguments={'gz_args': [PathJoinSubstitution([
            pkg_mec_mobile,
            'worlds',
            LaunchConfiguration('world')
        ]),
        #TextSubstitution(text=' -r -v -v1 --render-engine ogre')],
        TextSubstitution(text=' -r -v -v1')],
        'on_exit_shutdown': 'true'}.items()
    )

    launchDescriptionObject = LaunchDescription()

    launchDescriptionObject.add_action(world_arg)
    launchDescriptionObject.add_action(gazebo_launch)

    return launchDescriptionObject

This launch file has one argument, the world file's name - you can change the default value to your new world. It also ensures that the offline Gazebo model folder is added to the environmental variable, and finally it launches Gazebo through the ros_gz_sim package with the right arguments (note that the simulation will start automatically because of the -r flag).

In case you have problem with the default OGRE2 rendering engine you can switch to OGRE as before:

TextSubstitution(text=' -r -v -v1 --render-engine ogre')],

Add launch and worlds to the CMakeLists.txt and dependencies. Then build the workspace:

cd ~/ros2_ws
colcon build
source install/setup.bash
ros2 launch mec_mobile_gazebo world.launch.py

Load URDF files to Gazebo environment

We already have a mecanum mobile robot model that we see in RViz, but RViz is just a visualization tool, even if we can rotate some joints with the joint_state_publisher_gui, it has nothing to do with the physical simulation.

To load our robot model into the Gazebo simulation environment, we have to write a new launch file that spawns the robot through the right services of Gazebo.

spawn_robot.launch.py
import os
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.conditions import IfCondition
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution, Command
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory

def generate_launch_description():

    pkg_urdf_path = get_package_share_directory('mec_mobile_description')
    pkg_gazebo_path = get_package_share_directory('mec_mobile_gazebo')

    gazebo_models_path, ignore_last_dir = os.path.split(pkg_urdf_path)
    #os.environ["GZ_SIM_RESOURCE_PATH"] += os.pathsep + gazebo_models_path

    rviz_launch_arg = DeclareLaunchArgument(
        'rviz', default_value='true',
        description='Open RViz.'
    )

    world_arg = DeclareLaunchArgument(
        'world', default_value='empty.sdf',
        description='Name of the Gazebo world file to load'
    )

    model_arg = DeclareLaunchArgument(
        'model', default_value='robot_3d.urdf.xacro',
        description='Name of the URDF description to load'
    )

    # Define the path to your URDF or Xacro file
    urdf_file_path = PathJoinSubstitution([
        pkg_urdf_path,  # Replace with your package name
        "urdf","robots",
        LaunchConfiguration('model')  # Replace with your URDF or Xacro file
    ])

    world_launch = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(
            os.path.join(pkg_gazebo_path, 'launch', 'world.launch.py'),
        ),
        launch_arguments={
        'world': LaunchConfiguration('world'),
        }.items()
    )

    # Launch rviz
    rviz_node = Node(
        package='rviz2',
        executable='rviz2',
        arguments=['-d', os.path.join(pkg_urdf_path, 'rviz', 'rviz.rviz')],
        condition=IfCondition(LaunchConfiguration('rviz')),
        parameters=[
            {'use_sim_time': True},
        ]
    )

    # Spawn the URDF model using the `/world/<world_name>/create` service
    spawn_urdf_node = Node(
        package="ros_gz_sim",
        executable="create",
        arguments=[
            "-name", "my_robot",
            "-topic", "robot_description",
            "-x", "0.0", "-y", "0.0", "-z", "0.5", "-Y", "0.0"  # Initial spawn position
        ],
        output="screen",
        parameters=[
            {'use_sim_time': True},
        ]
    )

    robot_state_publisher_node = Node(
        package='robot_state_publisher',
        executable='robot_state_publisher',
        name='robot_state_publisher',
        output='screen',
        parameters=[
            {'robot_description': Command(['xacro', ' ', urdf_file_path]),
             'use_sim_time': True},
        ],
        remappings=[
            ('/tf', 'tf'),
            ('/tf_static', 'tf_static')
        ]
    )

    joint_state_publisher_gui_node = Node(
        package='joint_state_publisher_gui',
        executable='joint_state_publisher_gui',
    )

    launchDescriptionObject = LaunchDescription()

    launchDescriptionObject.add_action(rviz_launch_arg)
    launchDescriptionObject.add_action(world_arg)
    launchDescriptionObject.add_action(model_arg)
    launchDescriptionObject.add_action(world_launch)
    launchDescriptionObject.add_action(rviz_node)
    launchDescriptionObject.add_action(spawn_urdf_node)
    launchDescriptionObject.add_action(robot_state_publisher_node)
    launchDescriptionObject.add_action(joint_state_publisher_gui_node)

    return launchDescriptionObject

This launch file will include the world.launch.py that we created earlier, so we don't have to load the world into Gazebo again. It will open RViz with a pre-configured view, and with three new nodes:

  • create node of the ros_gz_sim package to spawn the robot from the robot_description topic into a specific location within the simulation.

  • robot_state_publisher will convert and load the URDF/xacro into the robot_description topic it's providing the transformations between the links using static transforms from the URDF and dynamic transforms from real time joint_states topic

  • joint_state_publisher_gui is a joint_state_publisher with the small graphical UI to change joint angles. This node is responsible to update dynamic changes between links through the joint_states topic

We have to add launch to the CMakeLists.txt and rebuild the workspace to try this new launch file:

ros2 launch mec_mobile_gazebo spawn_robot.launch.py 

Right now, nothing publishes odometry for our robot so let's change the fixed frame to the robot_footprint in RViz.

We see that doesn't matter how we change the wheel joint angles it has no impact on the physical simulation. We did the first step, the robot is spawned into a Gazebo simulation, but the integration just starts from here.

Gazebo integration

To finally drive our robot in the physical simulation we have to do 2 things: 1. Adding a right Gazebo plugin that can move the specified robot 2. bridging messages between ROS and Gazebo.

1. Add Gazebo plugin

Let's include this new file in our robot's URDF. In the same way how we included the colors, let's add it to the top of our URDF within the <robot> tag.

 <xacro:include filename="$(find mec_mobile_description)/urdf/control/mec_mobile.gazebo"/>

Rebuild the workspace and then run it:

cd ~/ros2_ws
colcon build
source install/setup.bash
ros2 launch mec_mobile_gazebo spawn_robot.launch.py 

2. ROS gz bridge

First, remove the joint_state_publisher from the spawn_robot.launch.py because as soon as we can forward the messages between ROS and Gazebo, Gazebo will handle updating the joint_state topic.

After that we add another node the parameter_bridge from the ros_gz_bridge package.

Add this gz_bridge_node in spawn_robot.launch.py
    # Node to bridge messages like /cmd_vel and /odom
    gz_bridge_node = Node(
        package="ros_gz_bridge",
        executable="parameter_bridge",
        arguments=[
            "/clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock",
            "/cmd_vel@geometry_msgs/msg/Twist@gz.msgs.Twist",
            "/odom@nav_msgs/msg/Odometry@gz.msgs.Odometry",
            "/joint_states@sensor_msgs/msg/JointState@gz.msgs.Model",
            "/tf@tf2_msgs/msg/TFMessage@gz.msgs.Pose_V"
        ],
        output="screen",
        parameters=[
            {'use_sim_time': True},
        ]
    )

Make sure ros_gz_bridge is installed!

sudo apt install ros-jazzy-ros-gz-bridge

We forward the following topics:

  • /clock: The topic used for tracking simulation time or any custom time source.

  • /cmd_vel: We'll control the simulated robot from this ROS topic.

  • /odom: Gazebo's diff drive plugin provides this odometry topic for ROS consumers.

  • /joint_states: Gazebo's other plugin provides the dynamic transformation of the wheel joints.

  • /tf: Gazebo provides the real-time computation of the robot’s pose and the positions of its links, sensors, etc.

We forward the above messages bi-directionally between ROS2 and Gazebo except /clock. Clock should be published by Gazebo only if we are using simulated environment, but if another node already publishes to the /clock topic, the bi-directional bridge won't be created. So we make sure that /clock is forwarded only in the Gazebo → ROS2 direction, this we can achieve with using the [ symbol instead of @ in the arguments.

Don't forget to add the new node to the LaunchDescription() object:

    launchDescriptionObject.add_action(gz_bridge_node)

Then rebuild the workspace.

3. Driving around

Now it's time to launch the simulation:

ros2 launch mec_mobile_gazebo spawn_robot.launch.py 

Use the Gazebo teleop plugin or in another terminal start the teleop_twist_keyboard:

ros2 run teleop_twist_keyboard teleop_twist_keyboard

The friction between the wheels and the ground plane can be unrealistic, so let's add the following physical simulation parameters to the end of our URDF before the </robot> tag:

  <gazebo reference="base_link">
    <mu1>0.000002</mu1>
    <mu2>0.000002</mu2>
  </gazebo>

Mecanum wheel

Mecanum wheel uses special wheels with rollers mounted at a 45-degree angle to the wheel’s axis.

Note that description of friction is more complicated than before, the following line is needed to properly simulate the 45 degree rollers in the wheels:

To set the friction direction in Gazebo to <fdir1>0 1 0</fdir1>, you need to modify the surface element within your model's collision definition in the SDF (SDF format) file, specifying the fdir1 attribute with the vector 0 1 0, which indicates a friction force acting purely along the positive Y-axis in the local frame of the colliding object.

Starting in Gazebo Garden, you should use gz:expressed_in instead of ignition:expressed_in with the same change in the xmlns attribute. ignition:expressed_in is deprecated

The gz:expressed_in attribute is a custom attribute and uses the xml namespace gz, so you’ll need to add xmlns:gz="http://gazebosim.org/schema to your <robot> tag of your xacro file. So it would like like:

<robot name="my_robot" xmlns:xacro="http://www.ros.org/wiki/xacro" xmlns:gz="http://gazebosim.org/schema">

<fdir1 gz:expressed_in="base_footprint">1 -1 0</fdir1>

Let's create mec_mobile.gazebo with the additional odometry publisher plugin:

mec_mobile.gazebo
<?xml version="1.0"?>
<robot>
  <gazebo>
    <plugin
      filename="gz-sim-mecanum-drive-system"
      name="gz::sim::systems::MecanumDrive">
      <!-- Topic for the command input -->
      <topic>cmd_vel</topic>

      <!-- Wheel joints -->
      <front_left_joint>front_left_wheel_joint</front_left_joint>
      <front_right_joint>front_right_wheel_joint</front_right_joint>
      <back_left_joint>back_left_wheel_joint</back_left_joint>
      <back_right_joint>back_right_wheel_joint</back_right_joint>

      <!-- Wheel parameters -->
      <wheel_separation>0.3</wheel_separation>
      <wheelbase>0.3</wheelbase>
      <wheel_radius>0.1</wheel_radius>

      <!-- Control gains and limits (optional) -->
      <min_acceleration>-5</min_acceleration>
      <max_acceleration>5</max_acceleration>

      <!-- Other parameters (optional) -->
      <odom_topic>odom</odom_topic>
      <tf_topic>tf</tf_topic>
      <frame_id>odom</frame_id>
      <child_frame_id>base_footprint</child_frame_id>
      <odom_publish_frequency>30</odom_publish_frequency>
    </plugin>

    <plugin name="gz::sim::systems::OdometryPublisher" filename="gz-sim-odometry-publisher-system">
      <odom_topic>odom</odom_topic>
      <odom_frame>odom</odom_frame>
      <robot_base_frame>base_footprint</robot_base_frame>
      <publish_tf>true</publish_tf>
      <tf_topic>tf</tf_topic>
      <odom_publish_frequency>30</odom_publish_frequency>
      <xyz_offset>0 0 0</xyz_offset>
      <rpy_offset>0 0 0</rpy_offset>
    </plugin>

    <plugin
        filename="gz-sim-joint-state-publisher-system"
        name="gz::sim::systems::JointStatePublisher">
        <topic>joint_states</topic>
        <joint_name>front_left_wheel_joint</joint_name>
        <joint_name>front_right_wheel_joint</joint_name>
        <joint_name>back_left_wheel_joint</joint_name>
        <joint_name>back_right_wheel_joint</joint_name>
    </plugin>
  </gazebo>
</robot>

Rebuild the workspace, and we can launch with the same launch file as before, just overriding the model argument to the mecanum drive model:

ros2 launch mec_mobile_gazebo spawn_robot.launch.py

We can try to drive the robot with Gazebo teleop plugin or teleop_twist_keyboard node:

ros2 run teleop_twist_keyboard teleop_twist_keyboard 

If teleop_twist_keyboard is not installed yet, you can install it with the following command:

sudo apt install ros-jazzy-teleop-twist-keyboard

teleop_twist_keyboard support the control of mecanum robots, by pressing the shift key the robot moves sideways instead of turning in place.

If you see a Segmentation fault (Address not mapped to object [(nil)]) due to problems with Qt you can try to set the following environmental variable to force Qt to use X11 instead of Wayland.

If you run Gazebo in WSL2 or virtual machine the most common problem is with the 3D acceleration with the OGRE2 rendering engine of Gazebo. You can either try disabling HW acceleration (not recommended) or you can switch the older OGRE rendering engine with the following arguments.

If you run Ubuntu natively on a machine with an integrated Intel GPU and a discrete GPU you can check .

Introduction for the Gazebo GUI:

Gazebo has an online model database available , you can browse and download models from here. Normally this online model library is accessible within Gazebo although there might be issues in WSL2 or in virtual machines.

You have followed our previous tutorials: .

Create a folder such as gazebo_models for offline models. You can download modes .

To launch Gazebo and load the world using, create a launch folder within the mec_mobile_gazebo package. Inside this launch folder let's create a new launch file .

Let's create spawn_robot.launch.py in our launch folder inside mec_mobile_gazebo, and it will use the file we created just now to launch the simulation world:

We've used the robot_state_publisher and joint_state_publisher_gui in our RViz launch file check_urdf.launch.py. These nodes are used in the description.launch.py and display.launch.py files inside urdf_launch package .

Let's create a file in the URDF folder:

Full launch file:

You can find the detailed documentation of ros_gz_bridge . It explains the syntax of bridging topics in details also you can see what kind of messages can be bridged.

Gazebo has detailed , specifically to mecanum drive the documentation of the plugin can be found . Although, from the documentation it seems that mecanum drive is publishing odometry transformation, but unfortunately this feature is not properly implemented in Gazebo Harmonic as it's mentioned .

To do a workaround until this feature will be properly implemented in the future, we can use another Gazebo plugin, the .

Link
Link
this troubleshooting guide
here
Create a Mobile Robot with URDF
here
world.launch.py
world.launch.py
here
mec_mobile.gazebo
spawn_robot.launch.py
here
documentation for available plugins
here
in this GitHub issue
odometry publisher
previous instruction
https://youtu.be/g2hYkUEkpRQ