CI/CD for Robots: Automate Tests with GitHub Actions and Gazebo

Set up automated robot simulation tests in Gazebo using GitHub Actions CI/CD so every commit is validated before it touches hardware.

Problem: Your Robot Breaks in Production Because Nobody Tested It

You push a navigation update, deploy to hardware, and your robot drives into a wall. The code looked fine locally. There were no unit tests for physical behavior. Sound familiar?

You'll learn:

  • How to run Gazebo headless in a GitHub Actions runner
  • How to structure ROS 2 integration tests that pass in CI
  • How to gate merges on simulation results

Time: 45 min | Level: Advanced


Why This Happens

Robot software fails at the hardware boundary — and that boundary is almost never covered by unit tests. You can mock sensor inputs, but mocking physics is not testing physics.

The fix is simulation-in-the-loop CI: every PR spins up Gazebo, runs your robot through a defined scenario, and blocks merge if anything goes wrong.

Common symptoms without this:

  • Tests pass but hardware fails unpredictably
  • Merge conflicts in URDF/config files go undetected
  • Navigation regressions only caught during physical demos

Solution

Step 1: Set Up a Headless Gazebo Docker Image

GitHub Actions runners don't have a display. Gazebo needs one — or a virtual framebuffer.

Create a Dockerfile.ci at your repo root:

FROM ros:humble-ros-base

# Install Gazebo Harmonic and virtual display
RUN apt-get update && apt-get install -y \
    ros-humble-gazebo-ros-pkgs \
    xvfb \
    python3-pytest \
    && rm -rf /var/lib/apt/lists/*

# Source ROS in every shell layer
RUN echo "source /opt/ros/humble/setup.bash" >> /root/.bashrc

WORKDIR /ros_ws

Build and push this to GitHub Container Registry (GHCR) once, then reference it in your workflow. Rebuilding it on every CI run wastes 8-10 minutes.

docker build -f Dockerfile.ci -t ghcr.io/your-org/robot-ci:latest .
docker push ghcr.io/your-org/robot-ci:latest

Expected: Image appears in your org's GHCR packages tab.


Step 2: Write a Simulation Integration Test

Create tests/test_navigation_sim.py in your ROS 2 package:

import pytest
import rclpy
from rclpy.node import Node
from geometry_msgs.msg import PoseStamped
from nav2_msgs.action import NavigateToPose
from rclpy.action import ActionClient
import time

class NavigationTestNode(Node):
    def __init__(self):
        super().__init__('nav_test_node')
        # Action client connects to Nav2 — must already be running in Gazebo
        self._client = ActionClient(self, NavigateToPose, 'navigate_to_pose')
        self.result = None

    def send_goal(self, x: float, y: float) -> bool:
        # Wait up to 10s for Nav2 to come online before failing
        if not self._client.wait_for_server(timeout_sec=10.0):
            return False

        goal = NavigateToPose.Goal()
        goal.pose.header.frame_id = 'map'
        goal.pose.pose.position.x = x
        goal.pose.pose.position.y = y
        goal.pose.pose.orientation.w = 1.0

        future = self._client.send_goal_async(goal)
        rclpy.spin_until_future_complete(self, future, timeout_sec=30.0)
        return future.result().status == 4  # STATUS_SUCCEEDED


@pytest.fixture(scope='module')
def ros_context():
    rclpy.init()
    yield
    rclpy.shutdown()


def test_robot_reaches_goal(ros_context):
    node = NavigationTestNode()
    # Navigate to a waypoint known to be reachable in the test world
    success = node.send_goal(x=2.0, y=1.5)
    node.destroy_node()
    assert success, "Robot failed to reach navigation goal within 30 seconds"

Why this structure: The fixture handles ROS lifecycle once per module, not per test. Repeated rclpy.init() calls in the same process crash.


Step 3: Create the GitHub Actions Workflow

Create .github/workflows/simulation.yml:

name: Simulation Tests

on:
  pull_request:
    branches: [main]
  push:
    branches: [main]

jobs:
  gazebo-test:
    runs-on: ubuntu-22.04
    container:
      image: ghcr.io/your-org/robot-ci:latest
      options: --privileged  # Required for Gazebo IPC

    steps:
      - name: Checkout
        uses: actions/checkout@v4

      - name: Build ROS workspace
        run: |
          source /opt/ros/humble/setup.bash
          colcon build --symlink-install
        working-directory: /ros_ws

      - name: Source workspace and run simulation tests
        run: |
          source /opt/ros/humble/setup.bash
          source /ros_ws/install/setup.bash

          # Start virtual display — Gazebo needs this even in headless mode
          Xvfb :99 -screen 0 1024x768x24 &
          export DISPLAY=:99

          # Launch the test world in background
          ros2 launch your_pkg sim_test.launch.py headless:=true &
          SIM_PID=$!

          # Give Gazebo 20 seconds to initialize before running tests
          sleep 20

          # Run tests and capture exit code
          pytest tests/test_navigation_sim.py -v --timeout=120
          TEST_EXIT=$?

          kill $SIM_PID
          exit $TEST_EXIT

      - name: Upload test logs on failure
        if: failure()
        uses: actions/upload-artifact@v4
        with:
          name: sim-logs
          path: /ros_ws/log/
          retention-days: 7

If it fails:

  • "No module named rclpy": The source commands aren't stacking. Add shell: bash to each step.
  • Gazebo segfault: Add --privileged to container options (shared memory requirement).
  • Test times out: Increase sleep 20 to sleep 40 for complex worlds; Gazebo startup time scales with world size.

Step 4: Create the Test Launch File

Add launch/sim_test.launch.py to your package:

from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from ament_index_python.packages import get_package_share_directory
import os

def generate_launch_description():
    pkg_dir = get_package_share_directory('your_pkg')

    return LaunchDescription([
        DeclareLaunchArgument('headless', default_value='true'),

        # Minimal test world — no textures, simple geometry, fast to load
        IncludeLaunchDescription(
            os.path.join(pkg_dir, 'launch', 'gazebo_world.launch.py'),
            launch_arguments={'world': 'test_arena.world'}.items()
        ),

        # Your robot description
        Node(
            package='robot_state_publisher',
            executable='robot_state_publisher',
            parameters=[{'robot_description': open(
                os.path.join(pkg_dir, 'urdf', 'robot.urdf')
            ).read()}]
        ),

        # Nav2 bringup with a pre-tuned config for the test world
        IncludeLaunchDescription(
            os.path.join(pkg_dir, 'launch', 'nav2.launch.py'),
            launch_arguments={'params_file': os.path.join(
                pkg_dir, 'config', 'nav2_test_params.yaml'
            )}.items()
        ),
    ])

Keep test worlds minimal. Strip textures, reduce mesh complexity, and use primitive collision shapes. A test world that loads in 8 seconds is better than a photorealistic one that takes 45.


Verification

Push a branch and open a PR. In the Actions tab you should see the gazebo-test job run.

# Locally verify your test passes before pushing
Xvfb :99 -screen 0 1024x768x24 &
export DISPLAY=:99
ros2 launch your_pkg sim_test.launch.py headless:=true &
sleep 20
pytest tests/test_navigation_sim.py -v

You should see:

PASSED tests/test_navigation_sim.py::test_robot_reaches_goal
1 passed in 28.4s

GitHub Actions showing green simulation test check All checks green — the PR is safe to merge


What You Learned

  • Gazebo runs headless in CI with Xvfb — no GPU or real display needed
  • Pre-built Docker images are essential; rebuilding on every run kills your feedback loop
  • Test worlds should be minimal and deterministic — complexity is the enemy of reliable CI
  • The sleep before tests is inelegant but necessary; replace it with a topic-wait script once the pattern is stable

Limitation: This catches navigation and integration failures, not real-world sensor noise or hardware-specific behavior. Simulation CI is a gate, not a guarantee.

When NOT to use this: If your Gazebo world takes more than 2 minutes to load, runners will time out. In that case, split into unit tests in CI and schedule nightly simulation runs on self-hosted hardware runners instead.


Tested on ROS 2 Humble, Gazebo Harmonic 8.x, GitHub Actions ubuntu-22.04 runners