When working with robot control stacks, it can become repetitive to manually start the Gazebo simulation by clicking the Run button.
Note: The content of this article applies to Gazebo Harmonic 8.6.0. Same or similar principles apply to other versions of Gazebo, though the specific implementation details may differ.
A recent commit to ros_gz
introduced support for bridging ROS 2 services using ros_gz_bridge
. With this feature, you can call the ros_gz_interfaces/srv/ControlWorld
service, which maps to gz.msgs.WorldControl
. This allows you to unpause (i.e., run) the simulation programmatically.
Below are the steps required to set this up.
First, create a bridge to expose Gazebo services as ROS 2 services using the parameter_bridge
:
ros2 run ros_gz_bridge parameter_bridge /world/<world_name>/control@ros_gz_interfaces/srv/ControlWorld
If you prefer using a YAML configuration file, add the following lines to your ros_gz_bridge
configuration file:
- service_name: "/world/<world_name>/control"
ros_type_name: "ros_gz_interfaces/srv/ControlWorld"
gz_req_type_name: "gz.msgs.WorldControl"
gz_rep_type_name: "gz.msgs.Boolean"
Bring-up ros_gz_bridge
/parameter_bridge
via launch file:
ld = LaunchDescription()
# ...
gazebo_ros_bridge = Node(
package='ros_gz_bridge',
executable='parameter_bridge',
parameters=[
{'config_file': os.path.join(get_package_share_directory('<my_gz_sim_pkg>'), 'config', 'ros_gz_bridge.yaml')},
]
)
ld.add_action(gazebo_ros_bridge)
Verify that unpausing works by invoking the ROS 2 service manually:
ros2 service call /world/<world_name>/control \
ros_gz_interfaces/srv/ControlWorld \
"{world_control: {pause: false}}"
If successful, the simulation should start running.
To automatically unpause the simulation after spawning your robot, extend your launch file as follows:
from launch.actions import RegisterEventHandler, ExecuteProcess
from launch.substitutions import FindExecutable
# ...
gazebo_spawn_robot = Node(
package='ros_gz_sim',
executable='create',
# ...
gazebo_unpause = ExecuteProcess(
cmd=[
[
FindExecutable(name="ros2"),
" service call ",
"/world/<world_name>/control ",
"ros_gz_interfaces/srv/ControlWorld ",
"\"{world_control: {pause: false}}\"",
]
],
shell=True,
)
ld.add_action(
RegisterEventHandler(
event_handler=OnProcessExit(
target_action=gazebo_spawn_robot,
on_exit=[gazebo_unpause])
)
)
Finally, it's worth mentioning that you can also unpause/run the simulation by directly invoking the Gazebo service API:
gz service -s /world/<world_name>/control \
--reqtype gz.msgs.WorldControl \
--reptype gz.msgs.Boolean \
--timeout 3000 \
--req 'pause: false'