Skip to content

Gazebo Helpers in the Artefacts Toolkit

The Artefacts Toolkit Gazebo Helpers provide convenient functions to interact with your Gazebo simulations while running tests. These utilities allow you to inspect simulation objects, access model positions, as well as bridge topics between Gazebo and ROS2.

Import with:

from artefacts_toolkit.gazebo import bridge, gz

Functions

Function Reference

bridge.get_camera_bridge

Creates a gazebo / ros2 topic bridge for a camera topic

bridge.get_camera_bridge(
    topic_name,
    condition=None
)

Parameters

Parameter Type Description Default
topic_name str The camera topic name to bridge from Gazebo to ROS2 Required
condition str Optional launch condition that determins when this bridge should be created None

Returns

Node: Returns a ROS 2 Node object that runs the parameter_bridge for the specified camera topic. This node can be included in your launch description.

Notes

  • The bridge converts between Gazebo's image messages (gz.msgs.Image) and ROS 2's image messages (sensor_msgs/msg/Image)
  • You need to have the ros_gz_bridge package installed in your environment

Example

The following example shows a camera bridge being created conditionally based on a launch argument. When record_video is set to "true", the bridge will be activated, allowing ROS 2 nodes to subscribe to camera images from Gazebo. The returned Node is added to the LaunchDescription to be included in the launch process.

@pytest.mark.launch_test
def generate_test_description():
    from artefacts_toolkit.gazebo import bridge
    ...

    camera_topic = "/observation_camera/image"
    bag_recorder, rosbag_filepath = get_bag_recorder([camera_topic])
    sim = IncludeLaunchDescription(
        PythonLaunchDescriptionSource(["bringup", "/robot.launch.py"])
    )

    record_video_launch_arg = DeclareLaunchArgument(
        "record_video", default_value="true"
    )
    record_video = LaunchConfiguration("record_video")
    camera_bridge = bridge.get_camera_bridge(camera_topic, condition=IfCondition(record_video))

    return LaunchDescription(
        [
            record_video_launch_arg,
            sim,
            camera_bridge,
            controller_process,
            launch_testing.actions.ReadyToTest(),
        ]
    )

gz.get_sim_objects

Extracts model information from a Gazebo world file by parsing its XML structure. This function returns the name and original pose of all models defined in the world file.

This can useful when you need to know the initial poses of models as defined in the world file, rather than querying the running simulation (where positions might have changed due to physics, randomness, or interactions).

gz.get_sim_objects(world_file)

Parameters

Parameter Type Description Default
world_file str Path to the Gazebo world file to parse Required

Returns

tuple: The function returns a tuple with two values that should be unpacked:

  • A list of dictionaries:
objects = [
    {
        "name": "model_1",
        "pose": "0 0 0 0 0 0"
    }, 
    {
        "name": "model_2",
        "pose": "1 2 3 0 0 0"
    },
    ...
]
  • A dictionary mapping model names to poses:
objects_positions = {
    "model_1": "0 0 0 0 0 0", 
    "model_2": "1 2 3 0 0 0",
    ...
}

Example

# Working with the objects_position dict
_, objects_positions = gz.get_sim_objects("world.sdf")
model_pose = objects_positions["model_1"]  # "0 0 0 0 0 0"

# Working with the objects list
objects, _ = gz.get_sim_objects("world.sdf")
for model in objects:
    print(f"{model['name']} is at position {model['pose']}")

gz.get_model_location

Gets the current (x, y, z) position of a model in a running Gazebo simulation. Unlike get_sim_objects which reads original positions from a world file, this function queries the live simulation to get the model's current position.

gz.get_model_location(model_name)

Parameters

Parameter Type Description Default
model_name str Name of the model to query in the simulation Required

Returns

tuple: Returns a tuple of three float values representing the (x, y, z) position in meters:

(x_position, y_position, z_position)

Notes

  • This function requires a Gazebo simulation to be running
  • Returns (0.0, 0.0, 0.0) if the model position cannot be determined

Example

The example below demonstrates how to combine get_sim_objects and get_model_location to validate a pick-and-place task. It shows how to:

  1. Get initial positions from the world file
  2. Wait for a robot to complete its task
  3. Compare initial positions with current positions to detect which objects were moved
class TestProcOutput(unittest.TestCase):
    def test_moved_meatballs(self, proc_output, controller_process):
        # Original locations
        sim_objects, sim_objects_positions = gz.get_sim_objects("worlds/env.sdf") # this includes models poses
        meatball_models = [obj["name"] for obj in sim_objects if "karaage" in obj["name"]]
        #  Wait for the control loop to finish
        proc_output.assertWaitFor("Done with tasks execution", timeout=300)
        picked_meatballs = 0 # karaage moved for more than 10cm
        for meatball in meatball_models:
            x, y, z = gz.get_model_location(meatball)
            x_original, y_original, z_original = sim_objects_positions[meatball]
            dist = ((x - x_original) ** 2 + (y - y_original) ** 2 + (z - z_original) ** 2) ** 0.5
            if dist > 0.1: #10cm
                # Likely to have been picked and moved somewhere else
                picked_meatballs += 1
        self.assertEqual(picked_meatballs, 4)

gz.kill_gazebo

Kills the currently running gazebo process.

gz.kill_gazebo()

Returns

None: This function doesn't return any value.

Example

from artefacts_toolkit.gazebo import gz
...

@launch_testing.post_shutdown_test()
class TestProcOutputAfterShutdown(unittest.TestCase):
    def test_exit_code(self, proc_info, controller_process, rosbag_filepath):
        gz.kill_gazebo()
        ...