Skip to main content

Chapter 2: Introduction to Gazebo Simulation

Overview

Welcome to Module 2! In this chapter, you'll learn how to create digital twins of robots using Gazebo, a powerful physics simulation environment.

What is Gazebo?

Gazebo is an open-source 3D robotics simulator that provides:

  • Realistic physics simulation using engines like ODE, Bullet, and Simbody
  • High-fidelity sensor simulation (cameras, LiDAR, IMU, force/torque)
  • ROS 2 integration for seamless robot control
  • Plugin system for custom functionality
  • Distributed simulation for complex scenarios

Why Simulate?

Benefits of Simulation

  1. Cost-Effective: Test algorithms without physical hardware
  2. Safe: Experiment with risky behaviors in a virtual environment
  3. Rapid Iteration: Quickly test multiple scenarios
  4. Reproducible: Reset and repeat experiments exactly
  5. Scalable: Run multiple simulations in parallel

The Sim-to-Real Gap

While simulation is powerful, there's always a gap between simulation and reality:

  • Physics fidelity: Real-world physics is more complex
  • Sensor noise: Real sensors have noise and delays
  • Contact dynamics: Grasping and manipulation are challenging to simulate accurately
  • Environmental factors: Wind, lighting, terrain variations

Goal: Minimize this gap through careful modeling and domain randomization.

Gazebo Architecture

┌─────────────────────────────────────┐
│ User Interface (GUI) │
└──────────────┬──────────────────────┘

┌──────────────┴──────────────────────┐
│ Gazebo Server │
│ (Physics Engine, Sensor Sim) │
└──────────────┬──────────────────────┘

┌──────────────┴──────────────────────┐
│ Plugin Layer │
│ (ROS 2 Integration, Controllers) │
└──────────────┬──────────────────────┘

┌──────────────┴──────────────────────┐
│ World Models (SDF) │
│ (Robots, Objects, Environments) │
└─────────────────────────────────────┘

Key Concepts

1. World Files (.world / .sdf)

World files define the simulation environment using SDF (Simulation Description Format):

  • Models: Robots, objects, and structures
  • Lights: Illumination sources
  • Physics: Gravity, time step, solver parameters
  • Plugins: Custom behaviors and interfaces

2. Robot Models (URDF/SDF)

URDF (Unified Robot Description Format):

  • XML format for robot structure
  • Defines links (rigid bodies) and joints
  • Includes visual and collision geometries
  • Specifies inertial properties

SDF (Simulation Description Format):

  • More expressive than URDF
  • Supports complete world descriptions
  • Better physics specifications
  • Gazebo's native format

3. Physics Simulation

Gazebo simulates:

  • Rigid body dynamics: Forces, torques, collisions
  • Joint constraints: Revolute, prismatic, fixed, etc.
  • Contact forces: Friction, bounce, surface properties
  • Gravity and external forces

4. Sensor Simulation

Gazebo can simulate various sensors:

  • Cameras: RGB, depth, stereo
  • LiDAR: 2D and 3D laser scanners
  • IMU: Acceleration and angular velocity
  • Force/Torque: Contact sensing
  • GPS: Position sensing

Installation

# Install Gazebo Fortress
sudo apt-get install ros-humble-ros-gz

# Install additional packages
sudo apt-get install ros-humble-gazebo-ros-pkgs

Verify Installation

# Launch Gazebo
gz sim

# Or with ROS 2 integration
ros2 launch gazebo_ros gazebo.launch.py

Your First Simulation

Let's create a simple world with a ground plane and a sphere:

Create a World File

<?xml version="1.0" ?>
<sdf version="1.8">
<world name="simple_world">

<!-- Physics -->
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>

<!-- Lighting -->
<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.2 0.2 0.2 1</specular>
</light>

<!-- Ground Plane -->
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
</visual>
</link>
</model>

<!-- Bouncing Ball -->
<model name="ball">
<pose>0 0 2 0 0 0</pose>
<link name="link">
<inertial>
<mass>1.0</mass>
<inertia>
<ixx>0.04</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>0.04</iyy>
<iyz>0</iyz>
<izz>0.04</izz>
</inertia>
</inertial>
<collision name="collision">
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
<surface>
<bounce>
<restitution_coefficient>0.8</restitution_coefficient>
</bounce>
</surface>
</collision>
<visual name="visual">
<geometry>
<sphere>
<radius>0.2</radius>
</sphere>
</geometry>
<material>
<ambient>1 0 0 1</ambient>
<diffuse>1 0 0 1</diffuse>
</material>
</visual>
</link>
</model>

</world>
</sdf>

Launch the Simulation

gz sim simple_world.sdf

Understanding URDF

Let's create a simple robot arm:

<?xml version="1.0"?>
<robot name="simple_arm">

<!-- Base Link -->
<link name="base_link">
<visual>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
<material name="blue">
<color rgba="0 0 1 1"/>
</material>
</visual>
<collision>
<geometry>
<cylinder length="0.1" radius="0.2"/>
</geometry>
</collision>
<inertial>
<mass value="1.0"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0" izz="0.02"/>
</inertial>
</link>

<!-- First Arm Link -->
<link name="arm_link">
<visual>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.5"/>
</geometry>
<material name="red">
<color rgba="1 0 0 1"/>
</material>
</visual>
<collision>
<origin xyz="0 0 0.25" rpy="0 0 0"/>
<geometry>
<box size="0.05 0.05 0.5"/>
</geometry>
</collision>
<inertial>
<mass value="0.5"/>
<inertia ixx="0.01" ixy="0.0" ixz="0.0"
iyy="0.01" iyz="0.0" izz="0.001"/>
</inertial>
</link>

<!-- Joint connecting base to arm -->
<joint name="base_to_arm" type="revolute">
<parent link="base_link"/>
<child link="arm_link"/>
<origin xyz="0 0 0.05" rpy="0 0 0"/>
<axis xyz="0 0 1"/>
<limit effort="10" lower="-3.14" upper="3.14" velocity="1.0"/>
</joint>

</robot>

Exercises

Exercise 1: Explore Gazebo GUI

  1. Launch Gazebo with an empty world
  2. Insert models from the model database
  3. Manipulate objects using the transform tools
  4. Adjust physics parameters (gravity, time step)

Exercise 2: Modify the Bouncing Ball

Modify the ball world file to:

  1. Change the ball's starting height
  2. Adjust the restitution coefficient (bounciness)
  3. Add multiple balls at different positions
  4. Change the ball's color and size

Exercise 3: Build a Simple Robot

Create a two-wheeled robot with:

  1. A cylindrical body
  2. Two cylindrical wheels
  3. Revolute joints for the wheels
  4. Appropriate mass and inertia values

Key Takeaways

  • Gazebo provides realistic physics simulation for robotics
  • SDF and URDF are the primary formats for describing worlds and robots
  • Simulation enables rapid, safe, and cost-effective development
  • Understanding the sim-to-real gap is crucial for deployment

Next Steps

In the next chapter, we'll cover:

  • Adding sensors to your robot (cameras, LiDAR)
  • ROS 2 integration with Gazebo
  • Controlling robots through ROS 2 topics
  • Creating custom Gazebo plugins

Additional Resources


Continue learning: Next Chapter → | Back to Module Overview