Robot Simulation with Gazebo

Practice safely with physics-accurate virtual robot


Tutorial Overview

🎯 Learning Objectives

By the end of this tutorial, you will:

  • βœ… Understand URDF (robot description format)

  • βœ… Visualize robot in RViz without hardware

  • βœ… Launch Gazebo simulation environment

  • βœ… Control virtual robot with keyboard/joystick

  • βœ… Modify robot parameters and see effects

  • βœ… Compare simulation vs. real robot behavior

  • βœ… Use simulation for algorithm development

  • βœ… Create custom worlds and obstacles

⏱️ Time Required

  • Reading & Concepts: 20 minutes

  • RViz Visualization: 15 minutes

  • Gazebo Simulation: 30 minutes

  • Experimentation: 20 minutes

  • Total: ~85 minutes

πŸ“š Prerequisites

  • βœ… Completed ROS2 Communication & Tools

  • βœ… Laptop with ROS2 Jazzy installed

  • βœ… Can communicate with robot (for comparing)

  • ⚠️ Robot NOT required - all simulation on laptop!

  • βœ… 2GB+ free RAM for Gazebo

πŸ› οΈ What You'll Need

  • βœ… Laptop with ROS2 Jazzy

  • βœ… Gazebo Harmonic installed

  • βœ… Keyboard or joystick (for control)

  • ⏸️ Physical robot (optional - for comparison)


Part 1: Understanding URDF

What is URDF?

URDF = Unified Robot Description Format

Analogy: Like a blueprint for your robot

  • Describes physical structure (links and joints)

  • Defines dimensions, masses, inertias

  • Specifies sensor locations

  • Includes visual meshes (3D models)

  • Contains collision geometries

XML-based format readable by both humans and robots


URDF Structure

Key concepts:

Links (Rigid Bodies)

  • Base chassis

  • Wheels

  • Sensor mounts

  • Camera

  • LiDAR

Joints (Connections Between Links)

  • Fixed: No motion (camera β†’ chassis)

  • Continuous: Unlimited rotation (wheels)

  • Revolute: Limited rotation (steering, arms)

  • Prismatic: Sliding motion (telescoping)

Transforms (Spatial Relationships)

  • Where is camera relative to chassis?

  • How high is LiDAR from ground?

  • What's the wheelbase?


Beetlebot URDF Overview

Your robot's description includes:

Links:

  • base_footprint - Ground projection point

  • base_link - Main chassis (reference point)

  • fl_link, fr_link, bl_link, br_link - Four wheels

  • lidar_link - RPLidar C1 position

  • camera_link - Pi Camera position

  • imu_link - IMU sensor location

Joints:

  • base_footprint_joint - Fixed (ground β†’ chassis)

  • fl_joint, fr_joint, bl_joint, br_joint - Continuous (rotating wheels)

  • lidar_joint - Fixed (chassis β†’ LiDAR)

  • camera_joint - Fixed (chassis β†’ camera)

  • imu_joint - Fixed (chassis β†’ IMU)

Key measurements:

  • Ground clearance: 16.3cm (base_footprint β†’ base_link)

  • Wheelbase: 18.1cm (front-back distance)

  • Track width: 29cm (left-right distance)

  • Wheel diameter: 13cm

  • LiDAR height: 20.6cm from ground

  • Camera height: 8.8cm from ground


Part 2: Visualization in RViz

Launch Robot State Publisher

On your laptop:

What launches:

  • robot_state_publisher - Publishes TF tree from URDF

  • joint_state_publisher_gui - Interactive joint control

  • rviz2 - 3D visualization

[PLACEHOLDER: Screenshot of RViz showing Beetlebot model]


Explore the Model in RViz

What you see:

  1. 3D robot model - Gray chassis, blue wheels

  2. Coordinate frames - Red/Green/Blue axes (TF)

  3. Joint slider panel - Control wheel rotations

Interactive exploration:


Understanding the TF Tree

View frame relationships:

Expected tree:

Key insight: All sensor positions defined relative to base_link!


Exercise 3.1: Measure Robot Dimensions

Task: Use RViz to verify robot dimensions

Verify matches specifications:

  • Wheelbase: ~18cm βœ…

  • Track width: ~29cm βœ…

  • Wheel height: ~9.8cm below chassis βœ…


Part 3: Gazebo Simulation Basics

Installing Gazebo Harmonic

Check if installed:

If not installed:


Launch Beetlebot in Gazebo

What launches:

  • Gazebo simulator with physics engine

  • ROS2-Gazebo bridge (connects ROS topics ↔ Gazebo)

  • Robot model spawned in world

  • /cmd_vel topic available for control

[PLACEHOLDER: Screenshot of Gazebo with Beetlebot in empty world]


Gazebo Interface Tour

Main window sections:

Scene (center):

  • 3D world view

  • Robot model with physics

  • Ground plane, lighting

World Tree (left):

  • Scene hierarchy

  • Robot parts listed

  • Plugins shown

Entity Tree (right):

  • Select objects to inspect

  • View properties

  • Modify parameters

Toolbar (top):

  • Translate, rotate, scale tools

  • Play/pause simulation

  • Reset world


Camera Controls


Exercise 3.2: Physics Exploration

Task: Understand Gazebo physics

Test 1: Gravity

Test 2: Collisions

Test 3: Wheel Physics


Part 4: Controlling Simulated Robot

Keyboard Teleop

Launch teleop:

Drive with keyboard:

Try driving patterns:

  • Straight line (press 'i', wait, press 'k')

  • Square (i, j, i, j, i, j, i, j)

  • Circle (i + j held together)


Joystick Control

If you have the Cosmic Byte controller:

Note: Same controls as real robot!


Exercise 3.3: Compare Sim vs Real

Task: Drive same path in simulation and real robot

Path: 1 meter forward, turn 90Β° left, repeat 4Γ— (square)

In Simulation:

On Real Robot:

Compare:

  • Did both end near starting position?

  • Which had more drift?

  • Why differences?

Expected results

Simulation: Near-perfect square (minimal drift)

  • Ideal physics, no slip

  • Perfect wheel diameters

  • No encoder noise

Real robot: Some drift (~10-20cm)

  • Wheel slip on turns

  • Floor friction variations

  • Encoder quantization

Key lesson: Simulation is optimistic! Real world has imperfections.


Part 5: Modifying Robot Parameters

Change Wheel Size Experiment

Goal: See how wheel diameter affects motion

Edit URDF temporarily:

Observe in RViz:

  • Wheels look bigger

  • Ground clearance increased

  • Check with tf2_echo

Predict: If wheels are bigger, robot will go ___ (faster/slower) for same motor RPM?

Answer

**Faster!** Bigger wheels = more distance per revolution Formula: distance = 2 Γ— Ο€ Γ— radius 0.065m radius β†’ 0.408m per revolution 0.080m radius β†’ 0.503m per revolution (+23% faster)


Exercise 3.4: Wheelbase Experiment

Task: Change wheelbase (front-back distance), observe turning

Modify URDF:

Test in Gazebo:

  • Launch modified robot

  • Drive in circle

  • Compare turning radius

Wider wheelbase = ___ turning radius (larger/smaller)?

Answer

**Larger turning radius!** Wider wheelbase = harder to turn (need more space) Like the difference between a sports car (tight turns) and a truck (wide turns)


Part 6: Creating Custom Worlds

Empty World (Default)

Features:

  • Flat ground plane

  • Sun lighting

  • No obstacles

  • Good for basic testing


Adding Obstacles

Manually in Gazebo:

Build a simple maze:

  • 8Γ— boxes arranged in maze pattern

  • Each box: 2m Γ— 0.2m Γ— 0.5m

  • Space between: 1m (robot width + clearance)

[PLACEHOLDER: Diagram of simple maze layout]


Saving Custom World


Exercise 3.5: Obstacle Course Challenge

Task: Create and navigate obstacle course

Setup:

  1. Create world with 5 obstacles

  2. Place target zone (use colored box as goal)

  3. Start position: 3 meters from goal

Challenge:

  • Navigate from start to goal

  • Avoid all obstacles

  • Fastest time wins!

Practice first in simulation, then try on real robot!


Part 7: Sensor Simulation

LiDAR in Gazebo

Check if LiDAR active:

Visualize in RViz:

[PLACEHOLDER: Screenshot of RViz showing simulated LiDAR]

Drive toward obstacle in Gazebo, watch RViz:

  • Red/orange = close obstacles

  • Green/blue = far obstacles

  • Black = no return (infinite distance)


Camera in Gazebo

Check camera topic:

View image:

Select topic: /pi_camera/image_raw

[PLACEHOLDER: Screenshot of simulated camera view]


IMU Simulation

Test IMU:

  • Drive robot in simulation

  • Watch angular_velocity change during turns

  • Watch linear_acceleration during acceleration


Part 8: Simulation Limitations

What Simulation Does Well

βœ… Physics basics:

  • Gravity, collisions, friction (approximately)

  • Mass and inertia effects

  • Wheel dynamics

βœ… Sensor geometry:

  • LiDAR beam positions

  • Camera field of view

  • Coordinate transforms

βœ… Algorithm development:

  • Test navigation logic

  • Develop mapping algorithms

  • Prototype behaviors

βœ… Safety:

  • No battery drain

  • No mechanical wear

  • No crashes damage hardware


What Simulation Doesn't Capture

❌ Real-world imperfections:

  • Wheel slip varies by surface

  • Encoder noise and quantization

  • Motor response delays

  • Voltage drop under load

❌ Sensor noise:

  • LiDAR reflectivity variations

  • Camera exposure, motion blur

  • IMU drift over time

  • Temperature effects

❌ Unexpected behaviors:

  • Cable snag

  • Wheel stuck on obstacle edge

  • Battery suddenly low

  • WiFi dropout

❌ Timing issues:

  • Real hardware latencies

  • USB device delays

  • Network jitter


The Reality Gap

Simulation-to-Reality Transfer:

Algorithms developed in simulation may need tuning on real hardware:

Example: Navigation

  • Sim: Robot stops exactly at goal (perfect)

  • Real: Oscillates around goal (needs larger tolerance)

Example: Turning

  • Sim: 90Β° turn = exactly 90Β°

  • Real: 90Β° turn = 88-92Β° (needs calibration)

Best practice:

  1. Develop algorithm in simulation (safe, fast iteration)

  2. Test on real robot (find real-world issues)

  3. Adjust parameters based on real performance

  4. Validate in multiple real environments


Part 9: Practical Simulation Workflows

Workflow 1: Algorithm Development

Example: Path following algorithm

  • Simulate 100 iterations in 10 minutes

  • Would take hours on real robot (battery, space)


Workflow 2: Teaching and Demos

Safe demonstrations:

  • Show navigation concepts

  • Demonstrate SLAM

  • Explain control algorithms

  • No risk of damaging robot

Parallel operation:

  • Students use simulation

  • Instructor uses real robot

  • Compare results


Workflow 3: Testing Edge Cases

Scenarios hard to test on real robot:

  • Very tight spaces

  • Steep ramps (beyond hardware capability)

  • High-speed maneuvers

  • Extreme lighting conditions

  • Multiple robots (need multiple units)

Test in simulation first:

  • Validate algorithm handles edge case

  • Then carefully test on hardware


Part 10: Advanced Simulation Topics

Multi-Robot Simulation

Launch multiple robots:

Use cases:

  • Multi-robot coordination

  • Leader-follower algorithms

  • Swarm behaviors


Recording Simulation Data

Save simulation for replay:

Benefits:

  • Analyze behavior offline

  • Share scenarios with team

  • Debug without re-running sim


Procedural World Generation

Python script to generate random obstacles:


Part 11: Troubleshooting Simulation

Gazebo Won't Launch

Check installation:


Robot Falls Through Ground

Cause: Collision meshes missing

Fix:


Robot Doesn't Move

Checklist:


Performance Issues (Slow Simulation)

Reduce complexity:


General Troubleshooting

Most simulation issues fixed by:

  1. Restart Gazebo

  1. Clear Gazebo cache

  1. Check ROS2 daemon


Part 12: Knowledge Check

Concept Quiz

  1. What does URDF stand for?

  2. What's the difference between a 'link' and a 'joint'?

  3. Why is simulation useful if it's not perfectly accurate?

  4. Name 3 things simulation doesn't capture well:

  5. How can you make wheels bigger in simulation?


Hands-On Challenge

Task: Create a navigable environment and test it

Requirements:

  1. Custom Gazebo world with 10+ obstacles

  2. Clear path from start (0,0) to goal (5,5)

  3. Record rosbag of successful navigation

  4. Visualize in RViz during playback

Deliverable:

  • Screenshot of Gazebo world

  • Screenshot of RViz showing trajectory

  • Rosbag file of run


Part 13: What You've Learned

βœ… Congratulations!

You now understand:

URDF & Robot Description:

  • βœ… What URDF files contain

  • βœ… Links, joints, and transforms

  • βœ… How robot structure is defined

  • βœ… Modifying robot parameters

Visualization:

  • βœ… Using RViz to view robot model

  • βœ… Understanding TF trees

  • βœ… Checking spatial relationships

Simulation:

  • βœ… Launching Gazebo

  • βœ… Controlling simulated robot

  • βœ… Creating custom worlds

  • βœ… Adding obstacles

Practical Skills:

  • βœ… Comparing sim vs real behavior

  • βœ… Testing algorithms safely

  • βœ… Recording simulation data

  • βœ… Troubleshooting simulation issues

Limitations:

  • βœ… What simulation models well

  • βœ… What it doesn't capture

  • βœ… When to use sim vs hardware


Next Steps

🎯 You're Now Ready For:

Development:

  • Write navigation algorithms in simulation

  • Test in Gazebo before deploying to robot

  • Iterate quickly without hardware wear

Learning: β†’ Sensor Data Visualization - Work with real LiDAR and camera β†’ SLAM Mapping - Build maps (sim first, then real) β†’ Autonomous Navigation - Full path planning

Advanced Topics:

  • Multi-robot coordination (simulation)

  • Custom sensor plugins

  • Procedural world generation


Quick Reference

Common Gazebo Commands


URDF Quick Edits


Completed Robot Simulation! πŸŽ‰

β†’ Continue to Sensor Data Visualization β†’ Or return to Tutorial Index


Last Updated: January 2026 Tutorial 3 of 11 - Beginner Level Estimated completion time: 85 minutes

Last updated