Lab 09-03: Gazebo Simulation Integration
Objectives​
By the end of this lab, you will be able to:
- Configure Gazebo simulation environments for robot testing
- Create ROS2-Gazebo bridges for sensor and actuator data
- Implement controllers that work in both simulation and reality
- Debug and optimize sim-to-real transfer issues
Prerequisites​
- Completed Labs 09-01 and 09-02
- Understanding of URDF robot descriptions
- Familiarity with physics simulation concepts
Materials​
| Type | Name | Tier | Notes |
|---|---|---|---|
| software | Gazebo Fortress | required | gz-sim |
| software | ROS2 Humble | required | ros_gz_bridge |
| software | Python 3.10+ | required | Control nodes |
| model | Robot URDF/SDF | required | Robot description |
Background​
Why Simulation?​
Simulation enables:
- Safe development without hardware damage
- Parallelized testing across scenarios
- Perfect ground truth for debugging
- Reproducible experiments
Gazebo-ROS2 Integration​
Modern stack uses:
- Gazebo (Ignition): Physics simulation, rendering
- ros_gz_bridge: Topic/service bridging
- ros_gz_sim: Spawn and control interface
- ros2_control: Hardware abstraction layer
Sim-to-Real Gap​
Challenges in transfer:
- Physics model inaccuracies
- Sensor noise differences
- Timing and latency
- Environmental variations
Instructions​
Step 1: Set Up Gazebo Environment​
Create a simulation world:
<?xml version="1.0" ?>
<!-- world.sdf -->
<sdf version="1.8">
<world name="robot_world">
<!-- Physics configuration -->
<physics name="1ms" type="ignored">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<!-- Plugins -->
<plugin
filename="gz-sim-physics-system"
```python
```python
name="gz::sim::systems::Physics">
</plugin>
<plugin
filename="gz-sim-sensors-system"
```python
```python
name="gz::sim::systems::Sensors">
<render_engine>ogre2</render_engine>
</plugin>
<plugin
filename="gz-sim-scene-broadcaster-system"
```python
```python
name="gz::sim::systems::SceneBroadcaster">
</plugin>
<plugin
filename="gz-sim-user-commands-system"
```python
```python
name="gz::sim::systems::UserCommands">
</plugin>
<!-- 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>
<direction>-0.5 0.1 -0.9</direction>
</light>
<!-- Ground plane -->
<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<surface>
<friction>
<ode>
<mu>0.8</mu>
<mu2>0.8</mu2>
</ode>
</friction>
</surface>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.3 0.3 0.3 1</ambient>
</material>
</visual>
</link>
</model>
<!-- Test objects -->
<include>
<uri>model://box</uri>
<name>target_box</name>
<pose>1 0 0.05 0 0 0</pose>
</include>
</world>
</sdf>
Launch Gazebo:
# Set Gazebo resource path
export GZ_SIM_RESOURCE_PATH=/path/to/models
# Launch world
gz sim world.sdf
Expected: Gazebo opens with ground plane and lighting visible.
Step 2: Create Robot Model with Sensors​
Define robot with sensors in SDF:
<?xml version="1.0" ?>
<!-- robot.sdf -->
<sdf version="1.8">
<model name="simple_arm">
<pose>0 0 0.1 0 0 0</pose>
<!-- Base link -->
<link name="base_link">
<inertial>
<mass>5.0</mass>
<inertia>
<ixx>0.1</ixx>
<iyy>0.1</iyy>
<izz>0.1</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
</visual>
<collision name="collision">
<geometry>
<cylinder>
<radius>0.1</radius>
<length>0.2</length>
</cylinder>
</geometry>
</collision>
</link>
<!-- Link 1 -->
<link name="link1">
<pose relative_to="joint1">0 0 0.2 0 0 0</pose>
<inertial>
<mass>2.0</mass>
<inertia>
<ixx>0.02</ixx>
<iyy>0.02</iyy>
<izz>0.01</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.05 0.05 0.4</size>
</box>
</geometry>
<material>
<ambient>0.2 0.2 0.8 1</ambient>
</material>
</visual>
<collision name="collision">
<geometry>
<box>
<size>0.05 0.05 0.4</size>
</box>
</geometry>
</collision>
</link>
<!-- Joint 1 -->
<joint name="joint1" type="revolute">
<parent>base_link</parent>
<child>link1</child>
<pose>0 0 0.1 0 0 0</pose>
<axis>
<xyz>0 0 1</xyz>
<limit>
<lower>-3.14</lower>
<upper>3.14</upper>
<effort>50</effort>
<velocity>2</velocity>
</limit>
<dynamics>
<damping>0.5</damping>
<friction>0.1</friction>
</dynamics>
</axis>
</joint>
<!-- Link 2 -->
<link name="link2">
<pose relative_to="joint2">0 0 0.15 0 0 0</pose>
<inertial>
<mass>1.5</mass>
<inertia>
<ixx>0.01</ixx>
<iyy>0.01</iyy>
<izz>0.005</izz>
</inertia>
</inertial>
<visual name="visual">
<geometry>
<box>
<size>0.04 0.04 0.3</size>
</box>
</geometry>
<material>
<ambient>0.2 0.8 0.2 1</ambient>
</material>
</visual>
<collision name="collision">
<geometry>
<box>
<size>0.04 0.04 0.3</size>
</box>
</geometry>
</collision>
<!-- Camera sensor -->
<sensor name="camera" type="camera">
<pose>0 0 0.15 0 0 0</pose>
<camera>
<horizontal_fov>1.047</horizontal_fov>
<image>
<width>640</width>
<height>480</height>
</image>
<clip>
<near>0.1</near>
<far>10</far>
</clip>
</camera>
<always_on>1</always_on>
<update_rate>30</update_rate>
<topic>camera</topic>
</sensor>
</link>
<!-- Joint 2 -->
<joint name="joint2" type="revolute">
<parent>link1</parent>
<child>link2</child>
<pose relative_to="link1">0 0 0.2 0 0 0</pose>
<axis>
<xyz>0 1 0</xyz>
<limit>
<lower>-2.0</lower>
<upper>2.0</upper>
<effort>30</effort>
<velocity>2</velocity>
</limit>
<dynamics>
<damping>0.3</damping>
<friction>0.1</friction>
</dynamics>
</axis>
</joint>
<!-- Joint state publisher plugin -->
<plugin
filename="gz-sim-joint-state-publisher-system"
```python
```python
name="gz::sim::systems::JointStatePublisher">
<joint_name>joint1</joint_name>
<joint_name>joint2</joint_name>
<topic>joint_states</topic>
<update_rate>100</update_rate>
</plugin>
<!-- Joint position controller plugin -->
<plugin
filename="gz-sim-joint-position-controller-system"
```python
```python
name="gz::sim::systems::JointPositionController">
<joint_name>joint1</joint_name>
<topic>joint1_cmd</topic>
<p_gain>100</p_gain>
<d_gain>10</d_gain>
</plugin>
<plugin
filename="gz-sim-joint-position-controller-system"
```python
```python
name="gz::sim::systems::JointPositionController">
<joint_name>joint2</joint_name>
<topic>joint2_cmd</topic>
<p_gain>80</p_gain>
<d_gain>8</d_gain>
</plugin>
</model>
</sdf>
Expected: Robot model spawns with two joints and camera sensor.
Step 3: Configure ROS-Gazebo Bridge​
Set up topic bridges:
# bridge_config.yaml
# ROS2-Gazebo bridge configuration
- ros_topic_name: "/joint_states"
gz_topic_name: "/world/robot_world/model/simple_arm/joint_states"
ros_type_name: "sensor_msgs/msg/JointState"
gz_type_name: "gz.msgs.Model"
direction: GZ_TO_ROS
- ros_topic_name: "/joint1_cmd"
gz_topic_name: "/model/simple_arm/joint/joint1/cmd_pos"
ros_type_name: "std_msgs/msg/Float64"
gz_type_name: "gz.msgs.Double"
direction: ROS_TO_GZ
- ros_topic_name: "/joint2_cmd"
gz_topic_name: "/model/simple_arm/joint/joint2/cmd_pos"
ros_type_name: "std_msgs/msg/Float64"
gz_type_name: "gz.msgs.Double"
direction: ROS_TO_GZ
- ros_topic_name: "/camera/image_raw"
gz_topic_name: "/camera"
ros_type_name: "sensor_msgs/msg/Image"
gz_type_name: "gz.msgs.Image"
direction: GZ_TO_ROS
- ros_topic_name: "/camera/camera_info"
gz_topic_name: "/camera_info"
ros_type_name: "sensor_msgs/msg/CameraInfo"
gz_type_name: "gz.msgs.CameraInfo"
direction: GZ_TO_ROS
Launch bridge:
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=bridge_config.yaml
Expected: ROS2 topics appear for joint states, commands, and camera.
Step 4: Create Simulation Controller Node​
Implement a controller that works with simulation:
#!/usr/bin/env python3
"""
gazebo_controller.py
Controller node for Gazebo simulation.
"""
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import JointState, Image
from std_msgs.msg import Float64
from geometry_msgs.msg import Pose
from cv_bridge import CvBridge
import numpy as np
class GazeboController(Node):
"""Control robot in Gazebo simulation."""
def __init__(self):
super().__init__('gazebo_controller')
# Parameters
self.declare_parameter('control_rate', 100.0)
self.declare_parameter('use_sim_time', True)
control_rate = self.get_parameter('control_rate').value
# Publishers for joint commands
self.joint1_pub = self.create_publisher(Float64, '/joint1_cmd', 10)
self.joint2_pub = self.create_publisher(Float64, '/joint2_cmd', 10)
# Subscribers
self.joint_sub = self.create_subscription(
JointState,
'/joint_states',
self.joint_callback,
10
)
self.image_sub = self.create_subscription(
Image,
'/camera/image_raw',
self.image_callback,
10
)
# State
self.current_joints = np.zeros(2)
self.target_joints = np.zeros(2)
self.cv_bridge = CvBridge()
self.last_image = None
# Control timer
self.timer = self.create_timer(1.0 / control_rate, self.control_loop)
self.time = 0.0
# Trajectory parameters
self.trajectory_mode = 'sinusoidal'
self.get_logger().info('Gazebo controller initialized')
def joint_callback(self, msg):
"""Update current joint positions."""
```python
```python
if len(msg.position) >= 2:
self.current_joints = np.array(msg.position[:2])
def image_callback(self, msg):
"""Process camera image."""
try:
self.last_image = self.cv_bridge.imgmsg_to_cv2(msg, 'bgr8')
except Exception as e:
self.get_logger().error(f'Image conversion failed: {e}')
def control_loop(self):
"""Main control loop."""
self.time += 0.01
# Generate trajectory
```python
```python
if self.trajectory_mode == 'sinusoidal':
self.target_joints[0] = 1.0 * np.sin(2 * np.pi * 0.2 * self.time)
self.target_joints[1] = 0.5 * np.sin(2 * np.pi * 0.3 * self.time)
elif self.trajectory_mode == 'step':
```python
```python
if int(self.time) % 4 < 2:
self.target_joints = np.array([0.5, 0.3])
else:
self.target_joints = np.array([-0.5, -0.3])
# Publish commands
msg1 = Float64()
msg1.data = float(self.target_joints[0])
self.joint1_pub.publish(msg1)
msg2 = Float64()
msg2.data = float(self.target_joints[1])
self.joint2_pub.publish(msg2)
# Compute and log error
error = self.target_joints - self.current_joints
```python
```python
if int(self.time * 10) % 50 == 0:
self.get_logger().info(
f't={self.time:.1f}s: error=[{error[0]:.3f}, {error[1]:.3f}]'
)
def set_trajectory_mode(self, mode):
"""Set trajectory generation mode."""
if mode in ['sinusoidal', 'step', 'waypoint']:
self.trajectory_mode = mode
self.get_logger().info(f'Trajectory mode: {mode}')
def main(args=None):
rclpy.init(args=args)
node = GazeboController()
try:
rclpy.spin(node)
except KeyboardInterrupt:
pass
finally:
node.destroy_node()
rclpy.shutdown()
```python
```python
if __name__ == '__main__':
main()
Expected: Robot follows sinusoidal trajectory in Gazebo, tracking error displayed.
Step 5: Implement Sensor Processing​
Process simulated sensors:
#!/usr/bin/env python3
"""
sensor_processor.py
Process sensor data from Gazebo.
"""
import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image, CameraInfo, LaserScan
from geometry_msgs.msg import PoseArray, Pose
from cv_bridge import CvBridge
import cv2
import numpy as np
class SensorProcessor(Node):
"""Process simulated sensor data."""
def __init__(self):
super().__init__('sensor_processor')
self.cv_bridge = CvBridge()
# Camera subscriber
self.image_sub = self.create_subscription(
Image,
'/camera/image_raw',
self.image_callback,
10
)
self.camera_info_sub = self.create_subscription(
CameraInfo,
'/camera/camera_info',
self.camera_info_callback,
10
)
# Detection publisher
self.detection_pub = self.create_publisher(
PoseArray,
'/detections',
10
)
# Camera intrinsics
self.camera_matrix = None
self.get_logger().info('Sensor processor started')
def camera_info_callback(self, msg):
"""Store camera intrinsics."""
self.camera_matrix = np.array(msg.k).reshape(3, 3)
def image_callback(self, msg):
"""Process camera image for object detection."""
try:
# Convert to OpenCV
cv_image = self.cv_bridge.imgmsg_to_cv2(msg, 'bgr8')
# Simple color-based detection (for demo)
detections = self.detect_colored_objects(cv_image)
# Publish detections
if detections:
pose_array = PoseArray()
pose_array.header = msg.header
for det in detections:
pose = Pose()
pose.position.x = det['center'][0]
pose.position.y = det['center'][1]
pose.position.z = det['area']
pose_array.poses.append(pose)
self.detection_pub.publish(pose_array)
self.get_logger().info(f'Detected {len(detections)} objects')
except Exception as e:
self.get_logger().error(f'Image processing failed: {e}')
def detect_colored_objects(self, image):
"""Detect colored objects in image."""
detections = []
# Convert to HSV
hsv = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)
# Define color ranges (red objects)
lower_red = np.array([0, 100, 100])
upper_red = np.array([10, 255, 255])
# Create mask
mask = cv2.inRange(hsv, lower_red, upper_red)
# Find contours
contours, _ = cv2.findContours(
mask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE
)
for contour in contours:
area = cv2.contourArea(contour)
```python
```python
if area > 100: # Minimum area threshold
M = cv2.moments(contour)
```python
```python
if M['m00'] > 0:
cx = int(M['m10'] / M['m00'])
cy = int(M['m01'] / M['m00'])
detections.append({
'center': (cx, cy),
'area': area,
'contour': contour
})
return detections
def main(args=None):
rclpy.init(args=args)
node = SensorProcessor()
rclpy.spin(node)
node.destroy_node()
rclpy.shutdown()
```python
```python
if __name__ == '__main__':
main()
Expected: Colored objects detected in camera feed, detections published.
Step 6: Create Complete Launch System​
Integrated launch file:
#!/usr/bin/env python3
"""
simulation_launch.py
Complete simulation launch file.
"""
from launch import LaunchDescription
from launch.actions import (
DeclareLaunchArgument,
ExecuteProcess,
IncludeLaunchDescription,
SetEnvironmentVariable
)
from launch.launch_description_sources import PythonLaunchDescriptionSource
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
import os
def generate_launch_description():
"""Generate complete simulation launch."""
# Environment variables
gz_resource_path = SetEnvironmentVariable(
'GZ_SIM_RESOURCE_PATH',
'/path/to/models'
)
# Arguments
world_arg = DeclareLaunchArgument(
'world',
default_value='robot_world.sdf',
description='World file'
)
use_sim_time_arg = DeclareLaunchArgument(
'use_sim_time',
default_value='true',
description='Use simulation time'
)
# Gazebo simulation
gazebo = ExecuteProcess(
cmd=['gz', 'sim', '-r', LaunchConfiguration('world')],
output='screen'
)
# Spawn robot
spawn_robot = ExecuteProcess(
cmd=[
'gz', 'service', '-s', '/world/robot_world/create',
'--reqtype', 'gz.msgs.EntityFactory',
'--reptype', 'gz.msgs.Boolean',
'--timeout', '5000',
'--req', 'sdf_filename: "robot.sdf" name: "simple_arm"'
],
output='screen'
)
# ROS-Gazebo bridge
bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
arguments=[
'/joint_states@sensor_msgs/msg/JointState[gz.msgs.Model',
'/joint1_cmd@std_msgs/msg/Float64]gz.msgs.Double',
'/joint2_cmd@std_msgs/msg/Float64]gz.msgs.Double',
'/camera@sensor_msgs/msg/Image[gz.msgs.Image',
],
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen'
)
# Robot controller
controller = Node(
package='physical_ai_textbook',
executable='gazebo_controller',
name='gazebo_controller',
parameters=[{
'use_sim_time': LaunchConfiguration('use_sim_time'),
'control_rate': 100.0
}],
output='screen'
)
# Sensor processor
sensor_proc = Node(
package='physical_ai_textbook',
executable='sensor_processor',
name='sensor_processor',
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen'
)
# TF broadcaster
tf_broadcaster = Node(
package='physical_ai_textbook',
executable='dynamic_tf_broadcaster',
name='tf_broadcaster',
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen'
)
# RViz
rviz = Node(
package='rviz2',
executable='rviz2',
arguments=['-d', 'simulation.rviz'],
parameters=[{'use_sim_time': LaunchConfiguration('use_sim_time')}],
output='screen'
)
return LaunchDescription([
gz_resource_path,
world_arg,
use_sim_time_arg,
gazebo,
spawn_robot,
bridge,
controller,
sensor_proc,
tf_broadcaster,
rviz
])
Expected: Full system launches with Gazebo, ROS2 nodes, and RViz.
Expected Outcomes​
After completing this lab, you should have:
-
Code artifacts:
world.sdf: Simulation worldrobot.sdf: Robot with sensorsbridge_config.yaml: ROS-Gazebo bridgesgazebo_controller.py: Robot controllersensor_processor.py: Sensor processingsimulation_launch.py: Complete launch
-
Understanding:
- Gazebo-ROS2 integration architecture
- SDF model creation with sensors
- Bridge configuration for data flow
- Simulation time synchronization
-
Running system:
- Robot controlled via ROS2 in Gazebo
- Sensor data available in ROS2
- Visualization in RViz
Rubric​
| Criterion | Points | Description |
|---|---|---|
| World Setup | 15 | Physics, lighting, ground plane |
| Robot Model | 25 | Joints, links, sensors working |
| ROS Bridge | 20 | Bidirectional data flow |
| Controller | 20 | Trajectory tracking in sim |
| Integration | 20 | Launch file, full system |
| Total | 100 |
Common Errors​
Error: Bridge not connecting Solution: Check topic names match exactly, verify Gazebo plugins loaded.
Error: Robot falls through ground Solution: Check collision geometry, verify physics plugin enabled.
Error: Sensors not publishing Solution: Verify sensor plugins in SDF, check update rates.
Extensions​
For advanced students:
- Domain Randomization: Vary physics parameters for robustness
- Multi-Robot: Spawn and coordinate multiple robots
- Terrain Generation: Procedural terrain for testing
- Hardware-in-Loop: Mix real sensors with simulated robot
Related Content​
- Theory: Module 09 theory.md, Section 9.3 (Simulation)
- Previous Lab: Lab 09-02 (tf2)
- Next Module: Module 10 (Sim-to-Real Transfer)