Use ROS 2 to interact with Gazebo#
In this tutorial we will learn how to use ROS 2 to communicate with Gazebo. This can help in many aspects; we can receive data (like joint states, TFs) or commands from ROS and apply it to Gazebo and vice versa. This can also help to enable RViz to visualize a robot model simulatenously simulated by a Gazebo world.
ros_gz_bridge#
ros_gz_bridge
provides a network bridge which enables the exchange of messages between ROS 2 and Gazebo Transport. Its support is limited to only certain message types. Please, check this README to verify if your message type is supported by the bridge.
Example uses of the bridge can be found in ros_gz_sim_demos
, including demo launch files with bridging of all major actuation and sensor types.
Launching the bridge manually#
We can initialize a bidirectional bridge so we can have ROS as the publisher and Gazebo as the subscriber or vice versa. The syntax is /TOPIC@ROS_MSG@GZ_MSG
, such that TOPIC
is the Gazebo internal topic, ROS_MSG
is the ROS message type for this topic, and GZ_MSG
is the Gazebo message type.
For example:
ros2 run ros_gz_bridge parameter_bridge /scan@sensor_msgs/msg/LaserScan@gz.msgs.LaserScan
The ros2 run ros_gz_bridge parameter_bridge
command simply runs the parameter_bridge
code from the ros_gz_bridge
package. Then, we specify our topic /TOPIC
over which the messages will be sent. The first @
symbol delimits the topic name from the message types. Following the first @
symbol is the ROS message type.
The ROS message type is followed by an @
, [
, or ]
symbol where:
@
is a bidirectional bridge.[
is a bridge from Gazebo to ROS.]
is a bridge from ROS to Gazebo.
Have a look at these examples explaining how to make communication connections from ROS to Gazebo and vice versa.
It is also possible to use ROS Launch with the ros_gz_bridge
and represent the topics in yaml format to be given to the bridge at launch time.
- ros_topic_name: "scan"
gz_topic_name: "/scan"
ros_type_name: "sensor_msgs/msg/LaserScan"
gz_type_name: "gz.msgs.LaserScan"
direction: GZ_TO_ROS # BIDIRECTIONAL or ROS_TO_GZ
The configuration file is a YAML file that contains the mapping between the ROS and Gazebo topics to be bridged. For each pair of topics to be bridged, the following parameters are accepted:
ros_topic_name
: The topic name on the ROS side.gz_topic_name
: The corresponding topic name on the Gazebo side.ros_type_name
: The type of this ROS topic.gz_type_name
: The type of this Gazebo topic.subscriber_queue
: The size of the ROS subscriber queue.publisher_queue
: The size of the ROS publisher queue.lazy
: Whether there’s a lazy subscriber or not. If there’s no real subscribers the bridge won’t create the internal subscribers either. This should speedup performance.direction
: It’s possible to specifyGZ_TO_ROS
,ROS_TO_GZ
andBIDIRECTIONAL
.
See this example for a valid configuration file.
Launching the bridge using the launch files included in ros_gz_bridge
package.#
The package ros_gz_bridge
contains a launch file named
ros_gz_bridge.launch.py
. You can use it to start a ROS 2 and Gazebo bridge.
Here’s an example:
ros2 launch ros_gz_bridge ros_gz_bridge.launch.py bridge_name:=ros_gz_bridge config_file:=<path_to_your_YAML_file>
Launching with composition:
ros2 launch ros_gz_bridge ros_gz_bridge.launch.py bridge_name:=ros_gz_bridge config_file:=<path_to_your_YAML_file> use_composition:=True create_own_container:=True
Alternatively, if an existing container is already running, you can pass its name
when launching the bridge using the container_name
parameter. More info about composition can be viewed here
Check this block from the source code to know all the different parameters accepted by this launch file.
Launching the bridge from a custom launch file in XML.#
It’s also possible to trigger the bridge from your custom launch file. For that
purpose we have created the <ros_gz_bridge/>
tag that can be used from you
XML or YAML launch file. In this case, the arguments are passed as attributes
within this tag. Here’s an example:
<launch>
<arg name="bridge_name" />
<arg name="config_file" />
<arg name="container_name" default="ros_gz_container" />
<arg name="create_own_container" default="False" />
<arg name="namespace" default="" />
<arg name="use_composition" default="False" />
<arg name="use_respawn" default="False" />
<arg name="log_level" default="info" />
<ros_gz_bridge
bridge_name="$(var bridge_name)"
config_file="$(var config_file)"
container_name="$(var container_name)"
create_own_container="$(var create_own_container)"
namespace="$(var namespace)"
use_composition="$(var use_composition)"
use_respawn="$(var use_respawn)"
log_level="$(var log_level)">
</ros_gz_bridge>
</launch>
In this case the <ros_gz_bridge>
parameters are read from the command line.
That’s an option but not strictly necessary as you could decide to hardcode some
of the values or not even use all the parameters.
Launching the bridge from a custom launch file in Python.#
Here’s a simplified example of a Python launch file used to load a bridge from Python:
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration, TextSubstitution
from ros_gz_bridge.actions import RosGzBridge
def generate_launch_description():
bridge_name = LaunchConfiguration('bridge_name')
config_file = LaunchConfiguration('config_file')
declare_bridge_name_cmd = DeclareLaunchArgument(
'bridge_name', description='Name of ros_gz_bridge node'
)
declare_config_file_cmd = DeclareLaunchArgument(
'config_file', description='YAML config file'
)
# Create the launch description and populate
ld = LaunchDescription([
RosGzBridge(
bridge_name=LaunchConfiguration('bridge_name'),
config_file=LaunchConfiguration('config_file'),
),
])
# Declare the launch options
ld.add_action(declare_bridge_name_cmd)
ld.add_action(declare_config_file_cmd)
return ld
Publish key strokes to ROS#
Let’s send messages to ROS using the Key Publisher
an Gazebo plugin.
Note: Make sure to have all workspaces you need (ROS, Gazebo and, ros_gz
…) sourced.
First we will start a bridge between ROS and Gazebo specifying the topic
at which the Key Publisher
plugin sends messages and also the type
of the messages as follows:
ros2 run ros_gz_bridge parameter_bridge /keyboard/keypress@std_msgs/msg/Int32@gz.msgs.Int32
We started a bridge on /keyboard/keypress
topic with message of type Int32
.
For ROS it is std_msgs/msg/Int32
and for Gazebo it is gz.msgs.Int32
In another terminal launch an Gazebo Sim world, for example the empty.sdf
world:
gz sim empty.sdf
Then add the Key Publisher
plugin from the dropdown menu on the top right corner.
In another terminal start the ROS listener:
ros2 topic echo /keyboard/keypress
This command listens to the messages sent over the /keyboard/keypress
topic.
On the Gazebo window, press on the keyboard keys and you should find data on the listener terminal.
Now it’s your turn! Try to send data from ROS to Gazebo. You can also try different data types and different directions of communication.
Video walk-through#
A video walk-through of this tutorial is available from our YouTube channel: Gazebo tutorials: ROS 2 Foxy integration.
Visualize in RViz#
Take a step further and try out demos from ros_gz_sim_demos
.
For the sdf_parser
demo, install ros_gz
and the parser plugin sdformat_urdf
from source in a colcon workspace.
Read more about sdformat_urdf
here.
Run the demo launch file with the rviz launch argument set:
ros2 launch ros_gz_sim_demos sdf_parser.launch.py rviz:=True
Start the simulation in Gazebo and wait a few seconds for TFs to be published.
In another terminal, send either ROS or Gazebo commands for the vehicle to move in circles:
gz topic -t "/model/vehicle/cmd_vel" -m gz.msgs.Twist -p "linear: {x: 1.0}, angular: {z: -0.1}"
ros2 topic pub /model/vehicle/cmd_vel geometry_msgs/msg/Twist "{linear: {x: 5.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: -0.1}}
And verify the vehicle matching its trajectory in Gazebo and RViz.
For more details on implementation of this demo see ROS 2 Interoperability.