|
Package Summary
Tags | No category tags. |
Version | 0.244.11 |
License | Apache 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/gazebosim/ros_gz.git |
VCS Type | git |
VCS Version | humble |
Last Updated | 2023-09-21 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Louise Poubel
Authors
- Shivesh Khaitan
Bridge communication between ROS and Gazebo
This package provides a network bridge which enables the exchange of messages between ROS and Gazebo Transport.
The following message types can be bridged for topics:
ROS type | Gazebo type |
---|---|
builtin_interfaces/msg/Time | ignition::msgs::Time |
std_msgs/msg/Bool | ignition::msgs::Boolean |
std_msgs/msg/ColorRGBA | ignition::msgs::Color |
std_msgs/msg/Empty | ignition::msgs::Empty |
std_msgs/msg/Float32 | ignition::msgs::Float |
std_msgs/msg/Float64 | ignition::msgs::Double |
std_msgs/msg/Header | ignition::msgs::Header |
std_msgs/msg/Int32 | ignition::msgs::Int32 |
std_msgs/msg/UInt32 | ignition::msgs::UInt32 |
std_msgs/msg/String | ignition::msgs::StringMsg |
geometry_msgs/msg/Wrench | ignition::msgs::Wrench |
geometry_msgs/msg/WrenchStamped | ignition::msgs::Wrench |
geometry_msgs/msg/Quaternion | ignition::msgs::Quaternion |
geometry_msgs/msg/Vector3 | ignition::msgs::Vector3d |
geometry_msgs/msg/Point | ignition::msgs::Vector3d |
geometry_msgs/msg/Pose | ignition::msgs::Pose |
geometry_msgs/msg/PoseArray | ignition::msgs::Pose_V |
geometry_msgs/msg/PoseWithCovariance | ignition::msgs::PoseWithCovariance |
geometry_msgs/msg/PoseStamped | ignition::msgs::Pose |
geometry_msgs/msg/Transform | ignition::msgs::Pose |
geometry_msgs/msg/TransformStamped | ignition::msgs::Pose |
geometry_msgs/msg/Twist | ignition::msgs::Twist |
geometry_msgs/msg/TwistWithCovariance | ignition::msgs::TwistWithCovariance |
nav_msgs/msg/Odometry | ignition::msgs::Odometry |
nav_msgs/msg/Odometry | ignition::msgs::OdometryWithCovariance |
rcl_interfaces/msg/ParameterValue | ignition::msgs::Any |
ros_gz_interfaces/msg/Altimeter | ignition::msgs::Altimeter |
ros_gz_interfaces/msg/Contact | ignition::msgs::Contact |
ros_gz_interfaces/msg/Contacts | ignition::msgs::Contacts |
ros_gz_interfaces/msg/Dataframe | ignition::msgs::Dataframe |
ros_gz_interfaces/msg/Entity | ignition::msgs::Entity |
ros_gz_interfaces/msg/Float32Array | ignition::msgs::Float_V |
ros_gz_interfaces/msg/GuiCamera | ignition::msgs::GUICamera |
ros_gz_interfaces/msg/JointWrench | ignition::msgs::JointWrench |
ros_gz_interfaces/msg/Light | ignition::msgs::Light |
ros_gz_interfaces/msg/SensorNoise | ignition::msgs::SensorNoise |
ros_gz_interfaces/msg/StringVec | ignition::msgs::StringMsg_V |
ros_gz_interfaces/msg/TrackVisual | ignition::msgs::TrackVisual |
ros_gz_interfaces/msg/VideoRecord | ignition::msgs::VideoRecord |
ros_gz_interfaces/msg/WorldControl | ignition::msgs::WorldControl |
rosgraph_msgs/msg/Clock | ignition::msgs::Clock |
sensor_msgs/msg/BatteryState | ignition::msgs::BatteryState |
sensor_msgs/msg/CameraInfo | ignition::msgs::CameraInfo |
sensor_msgs/msg/FluidPressure | ignition::msgs::FluidPressure |
sensor_msgs/msg/Imu | ignition::msgs::IMU |
sensor_msgs/msg/Image | ignition::msgs::Image |
sensor_msgs/msg/JointState | ignition::msgs::Model |
sensor_msgs/msg/Joy | ignition::msgs::Joy |
sensor_msgs/msg/LaserScan | ignition::msgs::LaserScan |
sensor_msgs/msg/MagneticField | ignition::msgs::Magnetometer |
sensor_msgs/msg/NavSatFix | ignition::msgs::NavSat |
sensor_msgs/msg/PointCloud2 | ignition::msgs::PointCloudPacked |
tf2_msgs/msg/TFMessage | ignition::msgs::Pose_V |
trajectory_msgs/msg/JointTrajectory | ignition::msgs::JointTrajectory |
And the following for services:
ROS type | Gazebo request | Gazebo response |
---|---|---|
ros_gz_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean |
Run ros2 run ros_gz_bridge parameter_bridge -h
for instructions.
Example 1a: Gazebo Transport talker and ROS 2 listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the ROS listener.
# Shell B:
. /opt/ros/galactic/setup.bash
ros2 topic echo /chatter
Now we start the Gazebo Transport talker.
# Shell C:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
Example 1b: ROS 2 talker and Gazebo Transport listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the Gazebo Transport listener.
# Shell B:
ign topic -e -t /chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 topic pub /chatter std_msgs/msg/String "data: 'Hi'" --once
Example 2: Run the bridge and exchange images
In this example, we're going to generate Gazebo Transport images using
Gazebo Sim, that will be converted into ROS images, and visualized with
rqt_image_viewer
.
First we start Gazebo Sim (don't forget to hit play, or Gazebo Sim won't generate any images).
# Shell A:
ign gazebo sensors_demo.sdf
Let's see the topic where camera images are published.
# Shell B:
ign topic -l | grep image
/rgbd_camera/depth_image
/rgbd_camera/image
Then we start the parameter bridge with the previous topic.
# Shell B:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image
Now we start the ROS GUI:
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 run rqt_image_view rqt_image_view /rgbd_camera/image
You should see the current images in rqt_image_view
which are coming from
Gazebo (published as Gazebo Msgs over Gazebo Transport).
The screenshot shows all the shell windows and their expected content (it was taken using ROS 2 Galactic and Gazebo Fortress):
Example 3: Static bridge
In this example, we're going to run an executable that starts a bidirectional
bridge for a specific topic and message type. We'll use the static_bridge
executable that is installed with the bridge.
The example's code can be found under ros_gz_bridge/src/static_bridge.cpp
.
In the code, it's possible to see how the bridge is hardcoded to bridge string
messages published on the /chatter
topic.
Let's give it a try, starting with Gazebo -> ROS 2.
On terminal A, start the bridge:
ros2 run ros_gz_bridge static_bridge
On terminal B, we start a ROS 2 listener:
ros2 topic echo /chatter std_msgs/msg/String
And terminal C, publish an Gazebo message:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
At this point, you should see the ROS 2 listener echoing the message.
Now let's try the other way around, ROS 2 -> Gazebo.
On terminal D, start an Igntion listener:
ign topic -e -t /chatter
And on terminal E, publish a ROS 2 message:
ros2 topic pub /chatter std_msgs/msg/String 'data: "Hello"' -1
You should see the Gazebo listener echoing the message.
Example 4: Service bridge
It's possible to make ROS service requests into Gazebo. Let's try unpausing the simulation.
On terminal A, start the service bridge:
ros2 run ros_gz_bridge parameter_bridge /world/shapes/control@ros_gz_interfaces/srv/ControlWorld
On terminal B, start Gazebo, it will be paused by default:
ign gazebo shapes.sdf
On terminal C, make a ROS request to unpause simulation:
ros2 service call /world/<world_name>/control ros_gz_interfaces/srv/ControlWorld "{world_control: {pause: false}}"
Example 5: Configuring the Bridge via YAML
When configuring many topics, it is easier to use a file-based configuration in a markup
language. In this case, the ros_gz
bridge supports using a YAML file to configure the
various parameters.
The configuration file must be a YAML array of maps. An example configuration for 5 bridges is below, showing the various ways that a bridge may be specified:
# Set just topic name, applies to both
- topic_name: "chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just ROS topic name, applies to both
- ros_topic_name: "chatter_ros"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "ign_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
subscriber_queue: 5 # Default 10
publisher_queue: 6 # Default 10
lazy: true # Default "false"
direction: BIDIRECTIONAL # Default "BIDIRECTIONAL" - Bridge both directions
# "GZ_TO_ROS" - Bridge Ignition topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Ignition
To run the bridge node with the above configuration:
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=$WORKSPACE/ros_gz/ros_gz_bridge/test/config/full.yaml
API
ROS 2 Parameters:
-
subscription_heartbeat
- Period at which the node checks for new subscribers for lazy bridges. -
config_file
- YAML file to be loaded as the bridge configuration
Changelog for package ros_gz_bridge
0.244.11 (2023-05-23)
- Add actuator_msgs to humble bridge. (#394)
- Contributors: Benjamin Perseghetti
0.244.10 (2023-05-03)
- Fix warning message (#371)
- Introduce WrenchStamped into bridge (#327)
- Humbly bringing the Joy to gazebo. (#353)
- Make the bridge aware of both gz and ignition msgs (#349)
- Contributors: Benjamin Perseghetti, El Jawad Alaa, Michael Carroll, livanov93
0.244.9 (2022-11-03)
0.244.8 (2022-10-28)
0.244.7 (2022-10-12)
- Make sure that ign_* yaml configs work as well (#310)
Bridge between msgs::Float_V and ros_gz_interfaces/Float32Array msg types (#306) * bridge float_v and float32_multi_array msg type Co-authored-by: Ian Chen <ichen@openrobotics.org>
Bridge between msgs::Pose_V and geometry_msgs/PoseArray msg types (#305)
replace ign with gz in ros_gz_bridge README (#303)
Merge pull request #275 (Galactic to Humble) Galactic to Humble
Fix merge
Merge branch \'ros2\' into ports/galactic_to_ros2
Contributors: Ian Chen, Michael Carroll, Olivier Kermorgant
0.244.6 (2022-09-14)
0.244.5 (2022-09-12)
- Fix missing msgs include and packages.xml deps
(#292)
- Fix missing msgs include and packages.xml deps
- Add additional conditions to support gz sim invocation
- Fix cpplint
- Add missing GZ_VERSION ticktocks (#289)
- Support ros_ign migration (#282) Clean up shared libraries, and tick-tock RosGzPointCloud Tick-tock launch args Hard-tock ign_ in sources Migrate ign, ign_, IGN_ for sources, launch, and test files Migrate IGN_XXX_VER, IGN_T, header guards Migrate launchfile, launchfile args, and test source references Migrate ros_ign_XXX and gz_gazebo -> gz_sim Migrate ros_ign_XXX project names Migrate Ign, ign-, IGN_DEPS, ign-gazebo Migrate ignitionrobotics, ignitionrobotics/ros_ign, osrf/ros_ign Migrate ignition-version, IGNITION_VERSION, Ignition <LIB>, ros_ign_ci
- Move packages and files to gz (#282)
- Contributors: methylDragon
0.244.3 (2022-05-19)
- Feature: set QoS options to override durability (#250) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- [ros2] README updates (service bridge, Gazebo rename) (#252)
- Fix linter tests (#251) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- Adds pose and twist with covariance messages bridging
(#222)
- Added pose, twist and odometry with covariance messages bridging
- Contributors: Aditya Pande, Daisuke Nishimatsu, Louise Poubel
0.244.2 (2022-04-25)
- Support bridging services (#211)
- Added reminder to hit play to receive images. (#237)
- Updated [ign topic]{.title-ref} commnds on README (#221)
- Add conversions for ros_gz_interfaces/WorldControl and builtin_interfaces/Time (#216)
- [ros_gz_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (#214)
- Break apart ros_subscriber test translation unit (#212)
- Bring ros2 branch up-to-date with Rolling (#213)
- Add missing dependency on rclcpp (#209)
- Separate galactic branch from ros2 branch (#201)
Wiki Tutorials
Source Tutorials
Package Dependencies
Deps | Name | |
---|---|---|
1 | ament_cmake | |
1 | ament_cmake_gtest | |
1 | ament_lint_auto | |
1 | ament_lint_common | |
1 | launch_testing_ament_cmake | |
2 | launch_ros | |
1 | launch_testing | |
1 | actuator_msgs | |
2 | geometry_msgs | |
2 | nav_msgs | |
1 | rclcpp | |
1 | rclcpp_components | |
2 | ros_gz_interfaces | |
3 | rosgraph_msgs | |
2 | sensor_msgs | |
2 | std_msgs | |
3 | tf2_msgs | |
2 | trajectory_msgs | |
1 | yaml_cpp_vendor | |
0 | gz-msgs9 | |
0 | gz-transport12 |
System Dependencies
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged ros_gz_bridge at answers.ros.org
|
Package Summary
Tags | No category tags. |
Version | 0.244.11 |
License | Apache 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/gazebosim/ros_gz.git |
VCS Type | git |
VCS Version | humble |
Last Updated | 2023-09-21 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Louise Poubel
Authors
- Shivesh Khaitan
Bridge communication between ROS and Gazebo
This package provides a network bridge which enables the exchange of messages between ROS and Gazebo Transport.
The following message types can be bridged for topics:
ROS type | Gazebo type |
---|---|
builtin_interfaces/msg/Time | ignition::msgs::Time |
std_msgs/msg/Bool | ignition::msgs::Boolean |
std_msgs/msg/ColorRGBA | ignition::msgs::Color |
std_msgs/msg/Empty | ignition::msgs::Empty |
std_msgs/msg/Float32 | ignition::msgs::Float |
std_msgs/msg/Float64 | ignition::msgs::Double |
std_msgs/msg/Header | ignition::msgs::Header |
std_msgs/msg/Int32 | ignition::msgs::Int32 |
std_msgs/msg/UInt32 | ignition::msgs::UInt32 |
std_msgs/msg/String | ignition::msgs::StringMsg |
geometry_msgs/msg/Wrench | ignition::msgs::Wrench |
geometry_msgs/msg/WrenchStamped | ignition::msgs::Wrench |
geometry_msgs/msg/Quaternion | ignition::msgs::Quaternion |
geometry_msgs/msg/Vector3 | ignition::msgs::Vector3d |
geometry_msgs/msg/Point | ignition::msgs::Vector3d |
geometry_msgs/msg/Pose | ignition::msgs::Pose |
geometry_msgs/msg/PoseArray | ignition::msgs::Pose_V |
geometry_msgs/msg/PoseWithCovariance | ignition::msgs::PoseWithCovariance |
geometry_msgs/msg/PoseStamped | ignition::msgs::Pose |
geometry_msgs/msg/Transform | ignition::msgs::Pose |
geometry_msgs/msg/TransformStamped | ignition::msgs::Pose |
geometry_msgs/msg/Twist | ignition::msgs::Twist |
geometry_msgs/msg/TwistWithCovariance | ignition::msgs::TwistWithCovariance |
nav_msgs/msg/Odometry | ignition::msgs::Odometry |
nav_msgs/msg/Odometry | ignition::msgs::OdometryWithCovariance |
rcl_interfaces/msg/ParameterValue | ignition::msgs::Any |
ros_gz_interfaces/msg/Altimeter | ignition::msgs::Altimeter |
ros_gz_interfaces/msg/Contact | ignition::msgs::Contact |
ros_gz_interfaces/msg/Contacts | ignition::msgs::Contacts |
ros_gz_interfaces/msg/Dataframe | ignition::msgs::Dataframe |
ros_gz_interfaces/msg/Entity | ignition::msgs::Entity |
ros_gz_interfaces/msg/Float32Array | ignition::msgs::Float_V |
ros_gz_interfaces/msg/GuiCamera | ignition::msgs::GUICamera |
ros_gz_interfaces/msg/JointWrench | ignition::msgs::JointWrench |
ros_gz_interfaces/msg/Light | ignition::msgs::Light |
ros_gz_interfaces/msg/SensorNoise | ignition::msgs::SensorNoise |
ros_gz_interfaces/msg/StringVec | ignition::msgs::StringMsg_V |
ros_gz_interfaces/msg/TrackVisual | ignition::msgs::TrackVisual |
ros_gz_interfaces/msg/VideoRecord | ignition::msgs::VideoRecord |
ros_gz_interfaces/msg/WorldControl | ignition::msgs::WorldControl |
rosgraph_msgs/msg/Clock | ignition::msgs::Clock |
sensor_msgs/msg/BatteryState | ignition::msgs::BatteryState |
sensor_msgs/msg/CameraInfo | ignition::msgs::CameraInfo |
sensor_msgs/msg/FluidPressure | ignition::msgs::FluidPressure |
sensor_msgs/msg/Imu | ignition::msgs::IMU |
sensor_msgs/msg/Image | ignition::msgs::Image |
sensor_msgs/msg/JointState | ignition::msgs::Model |
sensor_msgs/msg/Joy | ignition::msgs::Joy |
sensor_msgs/msg/LaserScan | ignition::msgs::LaserScan |
sensor_msgs/msg/MagneticField | ignition::msgs::Magnetometer |
sensor_msgs/msg/NavSatFix | ignition::msgs::NavSat |
sensor_msgs/msg/PointCloud2 | ignition::msgs::PointCloudPacked |
tf2_msgs/msg/TFMessage | ignition::msgs::Pose_V |
trajectory_msgs/msg/JointTrajectory | ignition::msgs::JointTrajectory |
And the following for services:
ROS type | Gazebo request | Gazebo response |
---|---|---|
ros_gz_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean |
Run ros2 run ros_gz_bridge parameter_bridge -h
for instructions.
Example 1a: Gazebo Transport talker and ROS 2 listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the ROS listener.
# Shell B:
. /opt/ros/galactic/setup.bash
ros2 topic echo /chatter
Now we start the Gazebo Transport talker.
# Shell C:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
Example 1b: ROS 2 talker and Gazebo Transport listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the Gazebo Transport listener.
# Shell B:
ign topic -e -t /chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 topic pub /chatter std_msgs/msg/String "data: 'Hi'" --once
Example 2: Run the bridge and exchange images
In this example, we're going to generate Gazebo Transport images using
Gazebo Sim, that will be converted into ROS images, and visualized with
rqt_image_viewer
.
First we start Gazebo Sim (don't forget to hit play, or Gazebo Sim won't generate any images).
# Shell A:
ign gazebo sensors_demo.sdf
Let's see the topic where camera images are published.
# Shell B:
ign topic -l | grep image
/rgbd_camera/depth_image
/rgbd_camera/image
Then we start the parameter bridge with the previous topic.
# Shell B:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image
Now we start the ROS GUI:
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 run rqt_image_view rqt_image_view /rgbd_camera/image
You should see the current images in rqt_image_view
which are coming from
Gazebo (published as Gazebo Msgs over Gazebo Transport).
The screenshot shows all the shell windows and their expected content (it was taken using ROS 2 Galactic and Gazebo Fortress):
Example 3: Static bridge
In this example, we're going to run an executable that starts a bidirectional
bridge for a specific topic and message type. We'll use the static_bridge
executable that is installed with the bridge.
The example's code can be found under ros_gz_bridge/src/static_bridge.cpp
.
In the code, it's possible to see how the bridge is hardcoded to bridge string
messages published on the /chatter
topic.
Let's give it a try, starting with Gazebo -> ROS 2.
On terminal A, start the bridge:
ros2 run ros_gz_bridge static_bridge
On terminal B, we start a ROS 2 listener:
ros2 topic echo /chatter std_msgs/msg/String
And terminal C, publish an Gazebo message:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
At this point, you should see the ROS 2 listener echoing the message.
Now let's try the other way around, ROS 2 -> Gazebo.
On terminal D, start an Igntion listener:
ign topic -e -t /chatter
And on terminal E, publish a ROS 2 message:
ros2 topic pub /chatter std_msgs/msg/String 'data: "Hello"' -1
You should see the Gazebo listener echoing the message.
Example 4: Service bridge
It's possible to make ROS service requests into Gazebo. Let's try unpausing the simulation.
On terminal A, start the service bridge:
ros2 run ros_gz_bridge parameter_bridge /world/shapes/control@ros_gz_interfaces/srv/ControlWorld
On terminal B, start Gazebo, it will be paused by default:
ign gazebo shapes.sdf
On terminal C, make a ROS request to unpause simulation:
ros2 service call /world/<world_name>/control ros_gz_interfaces/srv/ControlWorld "{world_control: {pause: false}}"
Example 5: Configuring the Bridge via YAML
When configuring many topics, it is easier to use a file-based configuration in a markup
language. In this case, the ros_gz
bridge supports using a YAML file to configure the
various parameters.
The configuration file must be a YAML array of maps. An example configuration for 5 bridges is below, showing the various ways that a bridge may be specified:
# Set just topic name, applies to both
- topic_name: "chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just ROS topic name, applies to both
- ros_topic_name: "chatter_ros"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "ign_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
subscriber_queue: 5 # Default 10
publisher_queue: 6 # Default 10
lazy: true # Default "false"
direction: BIDIRECTIONAL # Default "BIDIRECTIONAL" - Bridge both directions
# "GZ_TO_ROS" - Bridge Ignition topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Ignition
To run the bridge node with the above configuration:
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=$WORKSPACE/ros_gz/ros_gz_bridge/test/config/full.yaml
API
ROS 2 Parameters:
-
subscription_heartbeat
- Period at which the node checks for new subscribers for lazy bridges. -
config_file
- YAML file to be loaded as the bridge configuration
Changelog for package ros_gz_bridge
0.244.11 (2023-05-23)
- Add actuator_msgs to humble bridge. (#394)
- Contributors: Benjamin Perseghetti
0.244.10 (2023-05-03)
- Fix warning message (#371)
- Introduce WrenchStamped into bridge (#327)
- Humbly bringing the Joy to gazebo. (#353)
- Make the bridge aware of both gz and ignition msgs (#349)
- Contributors: Benjamin Perseghetti, El Jawad Alaa, Michael Carroll, livanov93
0.244.9 (2022-11-03)
0.244.8 (2022-10-28)
0.244.7 (2022-10-12)
- Make sure that ign_* yaml configs work as well (#310)
Bridge between msgs::Float_V and ros_gz_interfaces/Float32Array msg types (#306) * bridge float_v and float32_multi_array msg type Co-authored-by: Ian Chen <ichen@openrobotics.org>
Bridge between msgs::Pose_V and geometry_msgs/PoseArray msg types (#305)
replace ign with gz in ros_gz_bridge README (#303)
Merge pull request #275 (Galactic to Humble) Galactic to Humble
Fix merge
Merge branch \'ros2\' into ports/galactic_to_ros2
Contributors: Ian Chen, Michael Carroll, Olivier Kermorgant
0.244.6 (2022-09-14)
0.244.5 (2022-09-12)
- Fix missing msgs include and packages.xml deps
(#292)
- Fix missing msgs include and packages.xml deps
- Add additional conditions to support gz sim invocation
- Fix cpplint
- Add missing GZ_VERSION ticktocks (#289)
- Support ros_ign migration (#282) Clean up shared libraries, and tick-tock RosGzPointCloud Tick-tock launch args Hard-tock ign_ in sources Migrate ign, ign_, IGN_ for sources, launch, and test files Migrate IGN_XXX_VER, IGN_T, header guards Migrate launchfile, launchfile args, and test source references Migrate ros_ign_XXX and gz_gazebo -> gz_sim Migrate ros_ign_XXX project names Migrate Ign, ign-, IGN_DEPS, ign-gazebo Migrate ignitionrobotics, ignitionrobotics/ros_ign, osrf/ros_ign Migrate ignition-version, IGNITION_VERSION, Ignition <LIB>, ros_ign_ci
- Move packages and files to gz (#282)
- Contributors: methylDragon
0.244.3 (2022-05-19)
- Feature: set QoS options to override durability (#250) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- [ros2] README updates (service bridge, Gazebo rename) (#252)
- Fix linter tests (#251) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- Adds pose and twist with covariance messages bridging
(#222)
- Added pose, twist and odometry with covariance messages bridging
- Contributors: Aditya Pande, Daisuke Nishimatsu, Louise Poubel
0.244.2 (2022-04-25)
- Support bridging services (#211)
- Added reminder to hit play to receive images. (#237)
- Updated [ign topic]{.title-ref} commnds on README (#221)
- Add conversions for ros_gz_interfaces/WorldControl and builtin_interfaces/Time (#216)
- [ros_gz_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (#214)
- Break apart ros_subscriber test translation unit (#212)
- Bring ros2 branch up-to-date with Rolling (#213)
- Add missing dependency on rclcpp (#209)
- Separate galactic branch from ros2 branch (#201)
Wiki Tutorials
Source Tutorials
Package Dependencies
Deps | Name | |
---|---|---|
1 | ament_cmake | |
1 | ament_cmake_gtest | |
1 | ament_lint_auto | |
1 | ament_lint_common | |
1 | launch_testing_ament_cmake | |
2 | launch_ros | |
1 | launch_testing | |
1 | actuator_msgs | |
2 | geometry_msgs | |
2 | nav_msgs | |
1 | rclcpp | |
1 | rclcpp_components | |
2 | ros_gz_interfaces | |
3 | rosgraph_msgs | |
2 | sensor_msgs | |
2 | std_msgs | |
3 | tf2_msgs | |
2 | trajectory_msgs | |
1 | yaml_cpp_vendor | |
0 | gz-msgs9 | |
0 | gz-transport12 |
System Dependencies
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged ros_gz_bridge at answers.ros.org
|
Package Summary
Tags | No category tags. |
Version | 0.244.11 |
License | Apache 2.0 |
Build type | AMENT_CMAKE |
Use | RECOMMENDED |
Repository Summary
Checkout URI | https://github.com/gazebosim/ros_gz.git |
VCS Type | git |
VCS Version | humble |
Last Updated | 2023-09-21 |
Dev Status | MAINTAINED |
CI status | No Continuous Integration |
Released | RELEASED |
Tags | No category tags. |
Contributing |
Help Wanted (0)
Good First Issues (0) Pull Requests to Review (0) |
Package Description
Additional Links
Maintainers
- Louise Poubel
Authors
- Shivesh Khaitan
Bridge communication between ROS and Gazebo
This package provides a network bridge which enables the exchange of messages between ROS and Gazebo Transport.
The following message types can be bridged for topics:
ROS type | Gazebo type |
---|---|
builtin_interfaces/msg/Time | ignition::msgs::Time |
std_msgs/msg/Bool | ignition::msgs::Boolean |
std_msgs/msg/ColorRGBA | ignition::msgs::Color |
std_msgs/msg/Empty | ignition::msgs::Empty |
std_msgs/msg/Float32 | ignition::msgs::Float |
std_msgs/msg/Float64 | ignition::msgs::Double |
std_msgs/msg/Header | ignition::msgs::Header |
std_msgs/msg/Int32 | ignition::msgs::Int32 |
std_msgs/msg/UInt32 | ignition::msgs::UInt32 |
std_msgs/msg/String | ignition::msgs::StringMsg |
geometry_msgs/msg/Wrench | ignition::msgs::Wrench |
geometry_msgs/msg/WrenchStamped | ignition::msgs::Wrench |
geometry_msgs/msg/Quaternion | ignition::msgs::Quaternion |
geometry_msgs/msg/Vector3 | ignition::msgs::Vector3d |
geometry_msgs/msg/Point | ignition::msgs::Vector3d |
geometry_msgs/msg/Pose | ignition::msgs::Pose |
geometry_msgs/msg/PoseArray | ignition::msgs::Pose_V |
geometry_msgs/msg/PoseWithCovariance | ignition::msgs::PoseWithCovariance |
geometry_msgs/msg/PoseStamped | ignition::msgs::Pose |
geometry_msgs/msg/Transform | ignition::msgs::Pose |
geometry_msgs/msg/TransformStamped | ignition::msgs::Pose |
geometry_msgs/msg/Twist | ignition::msgs::Twist |
geometry_msgs/msg/TwistWithCovariance | ignition::msgs::TwistWithCovariance |
nav_msgs/msg/Odometry | ignition::msgs::Odometry |
nav_msgs/msg/Odometry | ignition::msgs::OdometryWithCovariance |
rcl_interfaces/msg/ParameterValue | ignition::msgs::Any |
ros_gz_interfaces/msg/Altimeter | ignition::msgs::Altimeter |
ros_gz_interfaces/msg/Contact | ignition::msgs::Contact |
ros_gz_interfaces/msg/Contacts | ignition::msgs::Contacts |
ros_gz_interfaces/msg/Dataframe | ignition::msgs::Dataframe |
ros_gz_interfaces/msg/Entity | ignition::msgs::Entity |
ros_gz_interfaces/msg/Float32Array | ignition::msgs::Float_V |
ros_gz_interfaces/msg/GuiCamera | ignition::msgs::GUICamera |
ros_gz_interfaces/msg/JointWrench | ignition::msgs::JointWrench |
ros_gz_interfaces/msg/Light | ignition::msgs::Light |
ros_gz_interfaces/msg/SensorNoise | ignition::msgs::SensorNoise |
ros_gz_interfaces/msg/StringVec | ignition::msgs::StringMsg_V |
ros_gz_interfaces/msg/TrackVisual | ignition::msgs::TrackVisual |
ros_gz_interfaces/msg/VideoRecord | ignition::msgs::VideoRecord |
ros_gz_interfaces/msg/WorldControl | ignition::msgs::WorldControl |
rosgraph_msgs/msg/Clock | ignition::msgs::Clock |
sensor_msgs/msg/BatteryState | ignition::msgs::BatteryState |
sensor_msgs/msg/CameraInfo | ignition::msgs::CameraInfo |
sensor_msgs/msg/FluidPressure | ignition::msgs::FluidPressure |
sensor_msgs/msg/Imu | ignition::msgs::IMU |
sensor_msgs/msg/Image | ignition::msgs::Image |
sensor_msgs/msg/JointState | ignition::msgs::Model |
sensor_msgs/msg/Joy | ignition::msgs::Joy |
sensor_msgs/msg/LaserScan | ignition::msgs::LaserScan |
sensor_msgs/msg/MagneticField | ignition::msgs::Magnetometer |
sensor_msgs/msg/NavSatFix | ignition::msgs::NavSat |
sensor_msgs/msg/PointCloud2 | ignition::msgs::PointCloudPacked |
tf2_msgs/msg/TFMessage | ignition::msgs::Pose_V |
trajectory_msgs/msg/JointTrajectory | ignition::msgs::JointTrajectory |
And the following for services:
ROS type | Gazebo request | Gazebo response |
---|---|---|
ros_gz_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean |
Run ros2 run ros_gz_bridge parameter_bridge -h
for instructions.
Example 1a: Gazebo Transport talker and ROS 2 listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the ROS listener.
# Shell B:
. /opt/ros/galactic/setup.bash
ros2 topic echo /chatter
Now we start the Gazebo Transport talker.
# Shell C:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
Example 1b: ROS 2 talker and Gazebo Transport listener
Start the parameter bridge which will watch the specified topics.
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg
Now we start the Gazebo Transport listener.
# Shell B:
ign topic -e -t /chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 topic pub /chatter std_msgs/msg/String "data: 'Hi'" --once
Example 2: Run the bridge and exchange images
In this example, we're going to generate Gazebo Transport images using
Gazebo Sim, that will be converted into ROS images, and visualized with
rqt_image_viewer
.
First we start Gazebo Sim (don't forget to hit play, or Gazebo Sim won't generate any images).
# Shell A:
ign gazebo sensors_demo.sdf
Let's see the topic where camera images are published.
# Shell B:
ign topic -l | grep image
/rgbd_camera/depth_image
/rgbd_camera/image
Then we start the parameter bridge with the previous topic.
# Shell B:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge /rgbd_camera/image@sensor_msgs/msg/Image@ignition.msgs.Image
Now we start the ROS GUI:
# Shell C:
. /opt/ros/galactic/setup.bash
ros2 run rqt_image_view rqt_image_view /rgbd_camera/image
You should see the current images in rqt_image_view
which are coming from
Gazebo (published as Gazebo Msgs over Gazebo Transport).
The screenshot shows all the shell windows and their expected content (it was taken using ROS 2 Galactic and Gazebo Fortress):
Example 3: Static bridge
In this example, we're going to run an executable that starts a bidirectional
bridge for a specific topic and message type. We'll use the static_bridge
executable that is installed with the bridge.
The example's code can be found under ros_gz_bridge/src/static_bridge.cpp
.
In the code, it's possible to see how the bridge is hardcoded to bridge string
messages published on the /chatter
topic.
Let's give it a try, starting with Gazebo -> ROS 2.
On terminal A, start the bridge:
ros2 run ros_gz_bridge static_bridge
On terminal B, we start a ROS 2 listener:
ros2 topic echo /chatter std_msgs/msg/String
And terminal C, publish an Gazebo message:
ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'
At this point, you should see the ROS 2 listener echoing the message.
Now let's try the other way around, ROS 2 -> Gazebo.
On terminal D, start an Igntion listener:
ign topic -e -t /chatter
And on terminal E, publish a ROS 2 message:
ros2 topic pub /chatter std_msgs/msg/String 'data: "Hello"' -1
You should see the Gazebo listener echoing the message.
Example 4: Service bridge
It's possible to make ROS service requests into Gazebo. Let's try unpausing the simulation.
On terminal A, start the service bridge:
ros2 run ros_gz_bridge parameter_bridge /world/shapes/control@ros_gz_interfaces/srv/ControlWorld
On terminal B, start Gazebo, it will be paused by default:
ign gazebo shapes.sdf
On terminal C, make a ROS request to unpause simulation:
ros2 service call /world/<world_name>/control ros_gz_interfaces/srv/ControlWorld "{world_control: {pause: false}}"
Example 5: Configuring the Bridge via YAML
When configuring many topics, it is easier to use a file-based configuration in a markup
language. In this case, the ros_gz
bridge supports using a YAML file to configure the
various parameters.
The configuration file must be a YAML array of maps. An example configuration for 5 bridges is below, showing the various ways that a bridge may be specified:
# Set just topic name, applies to both
- topic_name: "chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just ROS topic name, applies to both
- ros_topic_name: "chatter_ros"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_ign"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "ign_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "ignition.msgs.StringMsg"
subscriber_queue: 5 # Default 10
publisher_queue: 6 # Default 10
lazy: true # Default "false"
direction: BIDIRECTIONAL # Default "BIDIRECTIONAL" - Bridge both directions
# "GZ_TO_ROS" - Bridge Ignition topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Ignition
To run the bridge node with the above configuration:
ros2 run ros_gz_bridge parameter_bridge --ros-args -p config_file:=$WORKSPACE/ros_gz/ros_gz_bridge/test/config/full.yaml
API
ROS 2 Parameters:
-
subscription_heartbeat
- Period at which the node checks for new subscribers for lazy bridges. -
config_file
- YAML file to be loaded as the bridge configuration
Changelog for package ros_gz_bridge
0.244.11 (2023-05-23)
- Add actuator_msgs to humble bridge. (#394)
- Contributors: Benjamin Perseghetti
0.244.10 (2023-05-03)
- Fix warning message (#371)
- Introduce WrenchStamped into bridge (#327)
- Humbly bringing the Joy to gazebo. (#353)
- Make the bridge aware of both gz and ignition msgs (#349)
- Contributors: Benjamin Perseghetti, El Jawad Alaa, Michael Carroll, livanov93
0.244.9 (2022-11-03)
0.244.8 (2022-10-28)
0.244.7 (2022-10-12)
- Make sure that ign_* yaml configs work as well (#310)
Bridge between msgs::Float_V and ros_gz_interfaces/Float32Array msg types (#306) * bridge float_v and float32_multi_array msg type Co-authored-by: Ian Chen <ichen@openrobotics.org>
Bridge between msgs::Pose_V and geometry_msgs/PoseArray msg types (#305)
replace ign with gz in ros_gz_bridge README (#303)
Merge pull request #275 (Galactic to Humble) Galactic to Humble
Fix merge
Merge branch \'ros2\' into ports/galactic_to_ros2
Contributors: Ian Chen, Michael Carroll, Olivier Kermorgant
0.244.6 (2022-09-14)
0.244.5 (2022-09-12)
- Fix missing msgs include and packages.xml deps
(#292)
- Fix missing msgs include and packages.xml deps
- Add additional conditions to support gz sim invocation
- Fix cpplint
- Add missing GZ_VERSION ticktocks (#289)
- Support ros_ign migration (#282) Clean up shared libraries, and tick-tock RosGzPointCloud Tick-tock launch args Hard-tock ign_ in sources Migrate ign, ign_, IGN_ for sources, launch, and test files Migrate IGN_XXX_VER, IGN_T, header guards Migrate launchfile, launchfile args, and test source references Migrate ros_ign_XXX and gz_gazebo -> gz_sim Migrate ros_ign_XXX project names Migrate Ign, ign-, IGN_DEPS, ign-gazebo Migrate ignitionrobotics, ignitionrobotics/ros_ign, osrf/ros_ign Migrate ignition-version, IGNITION_VERSION, Ignition <LIB>, ros_ign_ci
- Move packages and files to gz (#282)
- Contributors: methylDragon
0.244.3 (2022-05-19)
- Feature: set QoS options to override durability (#250) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- [ros2] README updates (service bridge, Gazebo rename) (#252)
- Fix linter tests (#251) Co-authored-by: Louise Poubel <louise@openrobotics.org>
- Adds pose and twist with covariance messages bridging
(#222)
- Added pose, twist and odometry with covariance messages bridging
- Contributors: Aditya Pande, Daisuke Nishimatsu, Louise Poubel
0.244.2 (2022-04-25)
- Support bridging services (#211)
- Added reminder to hit play to receive images. (#237)
- Updated [ign topic]{.title-ref} commnds on README (#221)
- Add conversions for ros_gz_interfaces/WorldControl and builtin_interfaces/Time (#216)
- [ros_gz_interfaces] Add GuiCamera, StringVec, TrackVisual, VideoRecord (#214)
- Break apart ros_subscriber test translation unit (#212)
- Bring ros2 branch up-to-date with Rolling (#213)
- Add missing dependency on rclcpp (#209)
- Separate galactic branch from ros2 branch (#201)
Wiki Tutorials
Source Tutorials
Package Dependencies
Deps | Name | |
---|---|---|
1 | ament_cmake | |
1 | ament_cmake_gtest | |
1 | ament_lint_auto | |
1 | ament_lint_common | |
1 | launch_testing_ament_cmake | |
2 | launch_ros | |
1 | launch_testing | |
1 | actuator_msgs | |
2 | geometry_msgs | |
2 | nav_msgs | |
1 | rclcpp | |
1 | rclcpp_components | |
2 | ros_gz_interfaces | |
3 | rosgraph_msgs | |
2 | sensor_msgs | |
2 | std_msgs | |
3 | tf2_msgs | |
2 | trajectory_msgs | |
1 | yaml_cpp_vendor | |
0 | gz-msgs9 | |
0 | gz-transport12 |