|
Package Summary
Tags | No category tags. |
Version | 0.244.16 |
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 | 2024-07-22 |
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/TwistStamped | ignition::msgs::Twist |
geometry_msgs/msg/TwistWithCovariance | ignition::msgs::TwistWithCovariance |
geometry_msgs/msg/TwistWithCovarianceStamped | ignition::msgs::TwistWithCovariance |
gps_msgs/GPSFix | ignition::msgs::NavSat |
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/EntityWrench | ignition::msgs::EntityWrench |
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 |
vision_msgs/msg/Detection3D | ignition::msgs::AnnotatedOriented3DBox |
vision_msgs/msg/Detection3DArray | ignition::msgs::AnnotatedOriented3DBox_V |
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/humble/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/humble/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/humble/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
Example 6: Using ROS namespace with the Bridge
When spawning multiple robots inside the same ROS environment, it is convenient to use namespaces to avoid overlapping topic names.
There are three main types of namespaces: relative, global (/
) and private (~/
). For more information, refer to ROS documentation.
Namespaces are applied to Gazebo topic both when specified as topic_name
as well as gz_topic_name
.
By default, the Bridge will not apply ROS namespace on the Gazebo topics. To enable this feature, use parameter expand_gz_topic_names
.
Let’s test our topic with namespace:
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge chatter@std_msgs/msg/String@ignition.msgs.StringMsg \
--ros-args -p expand_gz_topic_names:=true -r __ns:=/demo
Now we start the Gazebo Transport listener.
# Shell B:
ign topic -e -t /demo/chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/humble/setup.bash
ros2 topic pub /demo/chatter std_msgs/msg/String "data: 'Hi from inside of a namespace'" --once
By changing chatter
to /chatter
or ~/chatter
you can obtain different results.
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 -
expand_gz_topic_names
- Enable or disable ROS namespace applied on GZ topics.
Changelog for package ros_gz_bridge
0.244.16 (2024-07-22)
- Add support for gz.msgs.EntityWrench (base branch: ros2) (backport
#573)
(#575)
* Add support for gz.msgs.EntityWrench (base branch: ros2)
(#573) (cherry
picked from commit f9afb69d1163633dd978024bb7271a28cf7b551a) #
Conflicts: # ros_gz_bridge/README.md #
ros_gz_bridge/test/utils/gz_test_msg.hpp
- Fixed merge
* Update ros_gz_bridge/README.md Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>> ---------Co-authored-by: Victor T. Noppeney <<Vtn21@users.noreply.github.com>> Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
- Contributors: mergify[bot]
0.244.15 (2024-07-03)
- [backport Humble] Create bridge for GPSFix msg (#316) (#538) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- Contributors: Alejandro Hernández Cordero
0.244.14 (2024-04-08)
- Added conversion for Detection3D and Detection3DArray (#523) (#526) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- Add ROS namespaces to GZ topics (#512) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Correctly export ros_gz_bridge for downstream targets (#503) (#506)
- Add a virtual destructor to suppress compiler warning (#502) (#505) Co-authored-by: Michael Carroll <<mjcarroll@intrinsic.ai>>
-
Add option to change material color from ROS. (#486) * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. ---------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Addisu Z. Taddese <<addisuzt@intrinsic.ai>> Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
- Contributors: Alejandro Hernández Cordero, Benjamin Perseghetti, Krzysztof Wojciechowski, Michael Carroll
0.244.13 (2024-01-23)
0.244.12 (2023-12-13)
- Backport: Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468) (#470)
- Add support for Harmonic/Humble pairing (#462)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458)
- Fix double wait in ros_gz_bridge (#347) (#450)
- [backport humble] SensorNoise msg bridging (#417)
- [backport humble] Added Altimeter msg bridging (#413) (#414) (#426)
- [backport humble] Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, Arjun K Haridas, wittenator
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)
- 🏁 Dome EOL (#198)
- Contributors: Aditya Pande, Ivan Santiago Paunovic, Joep Tool, Louise Poubel, Michael Carroll
0.244.1 (2022-01-04)
- Improve modularity of ign/ros publisher tests (#194)
- Contributors: Michael Carroll
0.244.0 (2021-12-30)
- Default to Fortress for Rolling (future Humble) (#195)
- [ros2] 🏁 Dome EOL (#199)
- New Light Message, also bridge Color (#187)
- Statically link each translation unit (#193)
- Break apart convert and factories translation unit (#192)
- Fixed ROS subscriber test in ros_gz_bridge (#189)
- Enable QoS overrides (#181)
- Fixed ros ign bridge documentation (#178)
- Expose Contacts through ROS bridge (#175)
- Contributors: Alejandro Hernández Cordero, Guillaume Doisy, Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew
0.233.2 (2021-07-20)
- [ros2] Update version docs, add Galactic and Fortress (#164)
- Contributors: Louise Poubel
0.233.1 (2021-04-16)
- Default to Edifice for Rolling (#150)
- Ignore local publications for ROS 2 subscriber
(#146)
- Note: Does not work with all rmw implementations (e.g.: FastRTPS)
- Update documentation for installation instructions and bridge examples (#142)
- Edifice support (#140)
- Add JointTrajectory message conversion
(#121) Conversion
between
- ignition::msgs::JointTrajectory
- trajectory_msgs::msg::JointTrajectory
- Add TFMessage / Pose_V and Float64 / Double conversions (#117) Addresses issue #116
- Updated prereq & branch name (#113)
- Update releases (#108)
- Updated README.md (#104)
- Add support for Dome (#103)
- Contributors: Alejandro Hernández Cordero, Andrej Orsula, Florent Audonnet, Jenn, Louise Poubel, Luca Della Vedova
0.221.1 (2020-08-19)
- Add pkg-config as a buildtool dependency (#102)
- Port ros_gz_bridge tests to ROS 2 (#98)
- Rename test_utils.hpp (#98)
- Contributors: Louise Poubel, ahcorde
0.221.0 (2020-07-23)
- Install only what's necessary, rename builtin_interfaces (#95)
- Move headers to src, rename builtin_interfaces (#95)
- Integer support (#91) Adds Int32 to the bridge.
- [ros2] Fixed CI - Added Foxy (#89) Co-authored-by: Louise Poubel <<louise@openrobotics.org>>
- Ignore ros-args in parameter bridge (#65)
- Update Dashing docs (#62)
- Update dependencies to Citadel (#57)
- [WIP] Port ign_ros_gazebo_demos to ROS2 (#58) Port ros_gz_image to ROS2 Port ros_gz_sim_demos to ROS2
- Add support for std_msgs/Empty (#53)
- Add support for std_msgs/Bool (#50)
- [ros2] Port ros_gz_bridge to ROS2 (#45)
- Enable ROS2 CI for Dashing branch (#43)
- Make all API and comments ROS-version agnostic
- Rename packages and fix compilation + tests
- Move files ros1 -> ros
- Contributors: Addisu Taddese, Alejandro Hernández Cordero, Jose Luis Rivero, Louise Poubel, Luca Della Vedova, Michael Carroll, Mohamed Ahmed, Shivesh Khaitan, chapulina
0.7.0 (2019-08-15)
- Merge pull request #38 from osrf/unidirectional Support unidirectional bridge topics
- More examples
- Merge pull request #37 from osrf/debug Adding debug and error statements
- Switch to characters supported by ros
- Merge branch 'debug' into unidirectional
- More output, and rosconsole depend
- Support specification of bridge direction
- Adding debug and error statements
- Contributors: Nate Koenig
0.6.3 (2019-08-04)
0.6.2 (2019-08-04)
0.6.1 (2019-08-04)
- Update README.md
- Contributors: Carlos Agüero
0.6.0 (2019-08-02)
- Merge pull request #33 from osrf/issue_31 Fix issue #31
- Image bridge using image_transport
(#34)
- Image bridge using image_transport
- tests for image
- correct metapackage
* tests with catkin Signed-off-by: Louise Poubel <<louise@openrobotics.org>> * Revert changes from #32 Signed-off-by: Louise Poubel <<louise@openrobotics.org>>
- Use intra-process field from messageInfo.
- Contributors: Carlos Aguero, Nate Koenig, chapulina
- 0.5.0
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
0.4.0 (2019-07-16)
- tests and reverse bridge for pointcloud
- Bridge point cloud packed
- Contributors: Nate Koenig
0.3.1 (2019-07-01)
0.3.0 (2019-06-28)
- 0.2.0
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry
(#22)
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry.
- Update documentation.
- More time to run tests
- Cleaning test_utils.
- Remove explicit ROS dependencies for Travis.
- diff drive demo with cmd_vel and odom
- process child frame id
- Fluid pressure
(#20)
- screenshots
- missing IMU
- Fluid pressure
- Fix tests.
- Demos package
(#19)
- Start of demos package: camera
- IMU
- depth camera
- magnetometer
- lidar, base launch
- READMEs, RGBD camera
- screenshots
- missing IMU
- set plugin path env
- It's best to always set it
- Point clouds for RGBD cameras
(#17)
- Beginning of point cloud package
- Populating image data, but result is not correct. Must find out where's the source of the problem.
- RGB -> BGR: why?
- Cleanup code and example
- pointcloud -> point_cloud
- add keys - how was this working before?
- install wget
- well, we need ign-gz2 :sweat_smile:
- README update
- PR feedback
- .travis/build: rosdep skip ignition keys (#18)
- .travis/build: rosdep skip ignition keys
- Update build
- Move package to subfolder, add metapackage (#16)
- Contributors: Carlos Agüero, Nate Koenig, chapulina
0.2.2 (2019-05-20)
0.2.1 (2019-05-11)
0.2.0 (2019-05-09)
0.1.0 (2019-03-20)
Wiki Tutorials
Package Dependencies
System Dependencies
Launch files
Messages
Services
Plugins
Recent questions tagged ros_gz_bridge at Robotics Stack Exchange
|
Package Summary
Tags | No category tags. |
Version | 0.254.2 |
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 | iron |
Last Updated | 2024-07-03 |
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/TwistStamped | ignition::msgs::Twist |
geometry_msgs/msg/TwistWithCovariance | ignition::msgs::TwistWithCovariance |
geometry_msgs/msg/TwistWithCovarianceStamped | ignition::msgs::TwistWithCovariance |
gps_msgs/GPSFix | ignition::msgs::NavSat |
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/EntityWrench | ignition.msgs.EntityWrench |
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 |
vision_msgs/msg/Detection3D | ignition::msgs::AnnotatedOriented3DBox |
vision_msgs/msg/Detection3DArray | ignition::msgs::AnnotatedOriented3DBox_V |
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/iron/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/iron/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/iron/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
Example 6: Using ROS namespace with the Bridge
When spawning multiple robots inside the same ROS environment, it is convenient to use namespaces to avoid overlapping topic names.
There are three main types of namespaces: relative, global (/
) and private (~/
). For more information, refer to ROS documentation.
Namespaces are applied to Gazebo topic both when specified as topic_name
as well as gz_topic_name
.
By default, the Bridge will not apply ROS namespace on the Gazebo topics. To enable this feature, use parameter expand_gz_topic_names
.
Let’s test our topic with namespace:
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge chatter@std_msgs/msg/String@ignition.msgs.StringMsg \
--ros-args -p expand_gz_topic_names:=true -r __ns:=/demo
Now we start the Gazebo Transport listener.
# Shell B:
ign topic -e -t /demo/chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/iron/setup.bash
ros2 topic pub /demo/chatter std_msgs/msg/String "data: 'Hi from inside of a namespace'" --once
By changing chatter
to /chatter
or ~/chatter
you can obtain different results.
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 -
expand_gz_topic_names
- Enable or disable ROS namespace applied on GZ topics.
Changelog for package ros_gz_bridge
0.254.2 (2024-07-03)
-
Add support for gz.msgs.EntityWrench (base branch: ros2) (backport #573) (#576) * Add support for gz.msgs.EntityWrench (base branch: ros2) (#573) (cherry picked from commit f9afb69d1163633dd978024bb7271a28cf7b551a) # Conflicts: # ros_gz_bridge/README.md # ros_gz_bridge/test/utils/gz_test_msg.hpp * Fixed merge ---------Co-authored-by: Victor T. Noppeney <<Vtn21@users.noreply.github.com>> Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Merge pull request #564 from azeey/humble_to_iron Humble ➡️ Iron
- Merge humble -> iron
- populate imu covariances when converting (#375) (#540) Co-authored-by: El Jawad Alaa <<ejalaa12@gmail.com>>
- [backport Humble] Create bridge for GPSFix msg (#316) (#538) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- [backport Iron] Create bridge for GPSFix msg (#316) (#537) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- 0.244.14
- Changelog
- Added conversion for Detection3D and Detection3DArray (#523) (#526) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- Add ROS namespaces to GZ topics (#512) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Correctly export ros_gz_bridge for downstream targets (#503) (#506)
- Add a virtual destructor to suppress compiler warning (#502) (#505) Co-authored-by: Michael Carroll <<mjcarroll@intrinsic.ai>>
-
Add option to change material color from ROS. (#486) * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. ---------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Addisu Z. Taddese <<addisuzt@intrinsic.ai>> Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
- 0.244.13
- Changelog
- backport pr 374 (#489)
- populate imu covariances when converting (#488)
- 0.244.12
- Changelog
- Backport: Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468) (#470)
- Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, Benjamin Perseghetti, El Jawad Alaa, Krzysztof Wojciechowski, Michael Carroll, mergify[bot], wittenator
0.254.1 (2024-04-08)
- Added conversion for Detection3D and Detection3DArray (#523)
-
Add option to change material color from ROS. (#520) Forward port of #486 * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights.
- [forward iron] Add ROS namespaces to GZ topics (#516) Co-authored-by: Krzysztof Wojciechowski <<49921081+Kotochleb@users.noreply.github.com>>
- Correctly export ros_gz_bridge for downstream targets (#503) (#507)
- Add a virtual destructor to suppress compiler warning (#502) (#504) Co-authored-by: Michael Carroll <<mjcarroll@intrinsic.ai>>
- Contributors: Alejandro Hernández Cordero, Benjamin Perseghetti, Michael Carroll, wittenator
0.254.0 (2024-01-08)
- Backport: Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468) (#471)
- Forward Port: Add support for Harmonic/Humble pairing (#462)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458)
- Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, Arjun K Haridas, wittenator
0.247.0 (2023-11-02)
- Fix double wait in ros_gz_bridge (#347) (#449) Co-authored-by: ymd-stella <<7959916+ymd-stella@users.noreply.github.com>>
- [backport iron] SensorNoise msg bridging (#417) (#425) Co-authored-by: Aditya Pande <<aditya050995@gmail.com>>
- Merge pull request #420 from gazebosim/ahcorde/iron/backport/411 [backport iron] Update README.md (#411)
- Merge branch 'iron' into ahcorde/iron/backport/411
- [backport Iron] Added Altimeter msg bridging (#413) (#414) Co-authored-by: Aditya Pande <<aditya050995@gmail.com>>
- Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Contributors: Alejandro Hernández Cordero, Arjun K Haridas
0.245.0 (2023-05-23)
- Backport: Add missing rosidl_cmake dep to ros_gz_bridge (#391) (#396)
- Contributors: Michael Carroll, Yadu, Chris Lalancette
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)
- 🏁 Dome EOL (#198)
- Contributors: Aditya Pande, Ivan Santiago Paunovic, Joep Tool, Louise Poubel, Michael Carroll
0.244.1 (2022-01-04)
- Improve modularity of ign/ros publisher tests (#194)
- Contributors: Michael Carroll
0.244.0 (2021-12-30)
- Default to Fortress for Rolling (future Humble) (#195)
- [ros2] 🏁 Dome EOL (#199)
- New Light Message, also bridge Color (#187)
- Statically link each translation unit (#193)
- Break apart convert and factories translation unit (#192)
- Fixed ROS subscriber test in ros_gz_bridge (#189)
- Enable QoS overrides (#181)
- Fixed ros ign bridge documentation (#178)
- Expose Contacts through ROS bridge (#175)
- Contributors: Alejandro Hernández Cordero, Guillaume Doisy, Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew
0.233.2 (2021-07-20)
- [ros2] Update version docs, add Galactic and Fortress (#164)
- Contributors: Louise Poubel
0.233.1 (2021-04-16)
- Default to Edifice for Rolling (#150)
- Ignore local publications for ROS 2 subscriber
(#146)
- Note: Does not work with all rmw implementations (e.g.: FastRTPS)
- Update documentation for installation instructions and bridge examples (#142)
- Edifice support (#140)
- Add JointTrajectory message conversion
(#121) Conversion
between
- ignition::msgs::JointTrajectory
- trajectory_msgs::msg::JointTrajectory
- Add TFMessage / Pose_V and Float64 / Double conversions (#117) Addresses issue #116
- Updated prereq & branch name (#113)
- Update releases (#108)
- Updated README.md (#104)
- Add support for Dome (#103)
- Contributors: Alejandro Hernández Cordero, Andrej Orsula, Florent Audonnet, Jenn, Louise Poubel, Luca Della Vedova
0.221.1 (2020-08-19)
- Add pkg-config as a buildtool dependency (#102)
- Port ros_gz_bridge tests to ROS 2 (#98)
- Rename test_utils.hpp (#98)
- Contributors: Louise Poubel, ahcorde
0.221.0 (2020-07-23)
- Install only what's necessary, rename builtin_interfaces (#95)
- Move headers to src, rename builtin_interfaces (#95)
- Integer support (#91) Adds Int32 to the bridge.
- [ros2] Fixed CI - Added Foxy (#89) Co-authored-by: Louise Poubel <<louise@openrobotics.org>>
- Ignore ros-args in parameter bridge (#65)
- Update Dashing docs (#62)
- Update dependencies to Citadel (#57)
- [WIP] Port ign_ros_gazebo_demos to ROS2 (#58) Port ros_gz_image to ROS2 Port ros_gz_sim_demos to ROS2
- Add support for std_msgs/Empty (#53)
- Add support for std_msgs/Bool (#50)
- [ros2] Port ros_gz_bridge to ROS2 (#45)
- Enable ROS2 CI for Dashing branch (#43)
- Make all API and comments ROS-version agnostic
- Rename packages and fix compilation + tests
- Move files ros1 -> ros
- Contributors: Addisu Taddese, Alejandro Hernández Cordero, Jose Luis Rivero, Louise Poubel, Luca Della Vedova, Michael Carroll, Mohamed Ahmed, Shivesh Khaitan, chapulina
0.7.0 (2019-08-15)
- Merge pull request #38 from osrf/unidirectional Support unidirectional bridge topics
- More examples
- Merge pull request #37 from osrf/debug Adding debug and error statements
- Switch to characters supported by ros
- Merge branch 'debug' into unidirectional
- More output, and rosconsole depend
- Support specification of bridge direction
- Adding debug and error statements
- Contributors: Nate Koenig
0.6.3 (2019-08-04)
0.6.2 (2019-08-04)
0.6.1 (2019-08-04)
- Update README.md
- Contributors: Carlos Agüero
0.6.0 (2019-08-02)
- Merge pull request #33 from osrf/issue_31 Fix issue #31
- Image bridge using image_transport
(#34)
- Image bridge using image_transport
- tests for image
- correct metapackage
* tests with catkin Signed-off-by: Louise Poubel <<louise@openrobotics.org>> * Revert changes from #32 Signed-off-by: Louise Poubel <<louise@openrobotics.org>>
- Use intra-process field from messageInfo.
- Contributors: Carlos Aguero, Nate Koenig, chapulina
- 0.5.0
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
0.4.0 (2019-07-16)
- tests and reverse bridge for pointcloud
- Bridge point cloud packed
- Contributors: Nate Koenig
0.3.1 (2019-07-01)
0.3.0 (2019-06-28)
- 0.2.0
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry
(#22)
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry.
- Update documentation.
- More time to run tests
- Cleaning test_utils.
- Remove explicit ROS dependencies for Travis.
- diff drive demo with cmd_vel and odom
- process child frame id
- Fluid pressure
(#20)
- screenshots
- missing IMU
- Fluid pressure
- Fix tests.
- Demos package
(#19)
- Start of demos package: camera
- IMU
- depth camera
- magnetometer
- lidar, base launch
- READMEs, RGBD camera
- screenshots
- missing IMU
- set plugin path env
- It's best to always set it
- Point clouds for RGBD cameras
(#17)
- Beginning of point cloud package
- Populating image data, but result is not correct. Must find out where's the source of the problem.
- RGB -> BGR: why?
- Cleanup code and example
- pointcloud -> point_cloud
- add keys - how was this working before?
- install wget
- well, we need ign-gz2 :sweat_smile:
- README update
- PR feedback
- .travis/build: rosdep skip ignition keys (#18)
- .travis/build: rosdep skip ignition keys
- Update build
- Move package to subfolder, add metapackage (#16)
- Contributors: Carlos Agüero, Nate Koenig, chapulina
0.2.2 (2019-05-20)
0.2.1 (2019-05-11)
0.2.0 (2019-05-09)
0.1.0 (2019-03-20)
Wiki Tutorials
Package Dependencies
System Dependencies
Dependant Packages
Launch files
Messages
Services
Plugins
Recent questions tagged ros_gz_bridge at Robotics Stack Exchange
ros_gz_bridge package from ros_gz reporos_gz ros_gz_bridge ros_gz_image ros_gz_interfaces ros_gz_point_cloud ros_gz_sim ros_gz_sim_demos test_ros_gz_bridge |
|
Package Summary
Tags | No category tags. |
Version | 1.0.7 |
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 | jazzy |
Last Updated | 2024-11-08 |
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
- Aditya Pande
- Alejandro Hernandez
Authors
- Shivesh Khaitan
- Louise Poubel
- Carlos Agüero
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 Transport Type |
---|---|
actuator_msgs/msg/Actuators | gz.msgs.Actuators |
builtin_interfaces/msg/Time | gz.msgs.Time |
geometry_msgs/msg/Point | gz.msgs.Vector3d |
geometry_msgs/msg/Pose | gz.msgs.Pose |
geometry_msgs/msg/PoseArray | gz.msgs.Pose_V |
geometry_msgs/msg/PoseStamped | gz.msgs.Pose |
geometry_msgs/msg/PoseWithCovariance | gz.msgs.PoseWithCovariance |
geometry_msgs/msg/PoseWithCovarianceStamped | gz.msgs.PoseWithCovariance |
geometry_msgs/msg/Quaternion | gz.msgs.Quaternion |
geometry_msgs/msg/Transform | gz.msgs.Pose |
geometry_msgs/msg/TransformStamped | gz.msgs.Pose |
geometry_msgs/msg/Twist | gz.msgs.Twist |
geometry_msgs/msg/TwistStamped | gz.msgs.Twist |
geometry_msgs/msg/TwistWithCovariance | gz.msgs.TwistWithCovariance |
geometry_msgs/msg/TwistWithCovarianceStamped | gz.msgs.TwistWithCovariance |
geometry_msgs/msg/Vector3 | gz.msgs.Vector3d |
geometry_msgs/msg/Wrench | gz.msgs.Wrench |
geometry_msgs/msg/WrenchStamped | gz.msgs.Wrench |
gps_msgs/msg/GPSFix | gz.msgs.NavSat |
nav_msgs/msg/Odometry | gz.msgs.Odometry |
nav_msgs/msg/Odometry | gz.msgs.OdometryWithCovariance |
rcl_interfaces/msg/ParameterValue | gz.msgs.Any |
ros_gz_interfaces/msg/Altimeter | gz.msgs.Altimeter |
ros_gz_interfaces/msg/Contact | gz.msgs.Contact |
ros_gz_interfaces/msg/Contacts | gz.msgs.Contacts |
ros_gz_interfaces/msg/Dataframe | gz.msgs.Dataframe |
ros_gz_interfaces/msg/Entity | gz.msgs.Entity |
ros_gz_interfaces/msg/EntityWrench | gz.msgs.EntityWrench |
ros_gz_interfaces/msg/Float32Array | gz.msgs.Float_V |
ros_gz_interfaces/msg/GuiCamera | gz.msgs.GUICamera |
ros_gz_interfaces/msg/JointWrench | gz.msgs.JointWrench |
ros_gz_interfaces/msg/Light | gz.msgs.Light |
ros_gz_interfaces/msg/ParamVec | gz.msgs.Param |
ros_gz_interfaces/msg/ParamVec | gz.msgs.Param_V |
ros_gz_interfaces/msg/SensorNoise | gz.msgs.SensorNoise |
ros_gz_interfaces/msg/StringVec | gz.msgs.StringMsg_V |
ros_gz_interfaces/msg/TrackVisual | gz.msgs.TrackVisual |
ros_gz_interfaces/msg/VideoRecord | gz.msgs.VideoRecord |
rosgraph_msgs/msg/Clock | gz.msgs.Clock |
sensor_msgs/msg/BatteryState | gz.msgs.BatteryState |
sensor_msgs/msg/CameraInfo | gz.msgs.CameraInfo |
sensor_msgs/msg/FluidPressure | gz.msgs.FluidPressure |
sensor_msgs/msg/Image | gz.msgs.Image |
sensor_msgs/msg/Imu | gz.msgs.IMU |
sensor_msgs/msg/JointState | gz.msgs.Model |
sensor_msgs/msg/Joy | gz.msgs.Joy |
sensor_msgs/msg/LaserScan | gz.msgs.LaserScan |
sensor_msgs/msg/MagneticField | gz.msgs.Magnetometer |
sensor_msgs/msg/NavSatFix | gz.msgs.NavSat |
sensor_msgs/msg/PointCloud2 | gz.msgs.PointCloudPacked |
std_msgs/msg/Bool | gz.msgs.Boolean |
std_msgs/msg/ColorRGBA | gz.msgs.Color |
std_msgs/msg/Empty | gz.msgs.Empty |
std_msgs/msg/Float32 | gz.msgs.Float |
std_msgs/msg/Float64 | gz.msgs.Double |
std_msgs/msg/Header | gz.msgs.Header |
std_msgs/msg/Int32 | gz.msgs.Int32 |
std_msgs/msg/String | gz.msgs.StringMsg |
std_msgs/msg/UInt32 | gz.msgs.UInt32 |
tf2_msgs/msg/TFMessage | gz.msgs.Pose_V |
trajectory_msgs/msg/JointTrajectory | gz.msgs.JointTrajectory |
vision_msgs/msg/Detection2D | gz.msgs.AnnotatedAxisAligned2DBox |
vision_msgs/msg/Detection2DArray | gz.msgs.AnnotatedAxisAligned2DBox_V |
vision_msgs/msg/Detection3D | gz::msgs::AnnotatedOriented3DBox |
vision_msgs/msg/Detection3DArray | gz::msgs::AnnotatedOriented3DBox_V |
And the following for services:
ROS type | Gazebo request | Gazebo response |
---|---|---|
ros_gz_interfaces/srv/ControlWorld | gz.msgs.WorldControl | gz.msgs.Boolean |
Run ros2 run ros_gz_bridge parameter_bridge -h
for instructions.
NOTE: If during startup, gazebo detects that there is another publisher on /clock
, it will only create the fully qualified /world/<worldname>/clock topic
.
Gazebo would be the only /clock
publisher, the sole source of clock information.
You should create an unidirectional /clock
bridge:
ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
An alternative set-up can be using the bridge with the override_timestamps_with_wall_time
ros parameter set to true
(default=false
). In this set-up,
all header timestamps of the outgoing messages will be stamped with the wall time. This can be useful when the simulator has to communicate with an external system that requires wall times.
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@gz.msgs.StringMsg
Now we start the ROS listener.
# Shell B:
. /opt/ros/rolling/setup.bash
ros2 topic echo /chatter
Now we start the Gazebo Transport talker.
# Shell C:
gz topic -t /chatter -m gz.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@gz.msgs.StringMsg
Now we start the Gazebo Transport listener.
# Shell B:
gz topic -e -t /chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/rolling/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:
gz sim sensors_demo.sdf
Let’s see the topic where camera images are published.
# Shell B:
gz 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@gz.msgs.Image
Now we start the ROS GUI:
# Shell C:
. /opt/ros/rolling/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:
gz topic -t /chatter -m gz.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 Gazebo listener:
gz 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:
gz sim 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: "gz.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: "gz.msgs.StringMsg"
# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_gz"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.msgs.StringMsg"
# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_gz"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.msgs.StringMsg"
# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "gz_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.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 Gz topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Gz
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
Example 6: Using ROS namespace with the Bridge
When spawning multiple robots inside the same ROS environment, it is convenient to use namespaces to avoid overlapping topic names.
There are three main types of namespaces: relative, global (/
) and private (~/
). For more information, refer to ROS documentation.
Namespaces are applied to Gazebo topic both when specified as topic_name
as well as gz_topic_name
.
By default, the Bridge will not apply ROS namespace on the Gazebo topics. To enable this feature, use parameter expand_gz_topic_names
.
Let’s test our topic with namespace:
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge chatter@std_msgs/msg/String@ignition.msgs.StringMsg \
--ros-args -p expand_gz_topic_names:=true -r __ns:=/demo
Now we start the Gazebo Transport listener.
# Shell B:
gz topic -e -t /demo/chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/rolling/setup.bash
ros2 topic pub /demo/chatter std_msgs/msg/String "data: 'Hi from inside of a namespace'" --once
By changing chatter
to /chatter
or ~/chatter
you can obtain different results.
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 -
expand_gz_topic_names
- Enable or disable ROS namespace applied on GZ topics.
Changelog for package ros_gz_bridge
1.0.7 (2024-11-08)
1.0.6 (2024-10-31)
- Extra parameter to start a container (#616) (#618) (cherry picked from commit 8115ccaaedea718841367eb64e500e13df392fd7) Co-authored-by: Carlos Agüero <<caguero@openrobotics.org>>
- Contributors: mergify[bot]
1.0.5 (2024-10-14)
- Merge pull request #607 from Amronos/ros2-jazzy-backport
- Fix changelogs and versions
- adds deadline and liveliness QoSPolicyKinds to qos_overriding_options (#609) (#613)
- Remove default_value for required arguments (#602)
- Fix errors with name of bridge not being given (#600)
- Use optional parameters in actions (#601)
- Making use_composition true by default (#578)
- Use [ignoreLocalMessages]{.title-ref} in the bridge (#559)
- Update launch files with name parameter (#556)
- Ensure the same container is used for the bridge and gz_server (#553)
- Launch ros_gz_bridge from xml (#550)
- Launch gzserver and the bridge as composable nodes (#528)
- adds deadline and liveliness QoSPolicyKinds to qos_overriding_options (#609) (#613)
- Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Amronos, Carlos Agüero, mergify[bot]
1.0.4 (2024-08-29)
- feat: [override_timestamps_with_wall_time]{.title-ref} parameter (backport #562) (#584) Co-authored-by: Rein Appeldoorn <<rein.appeldoorn@nobleo.nl>>
- Use memcpy instead of std::copy when bridging images (#565) (#585) While testing ros <-> gz communication using the bridge I noticed that the bridge was talking quite a bit of time copying images from Gazebo to ROS. I found that the std::copy operation that we're doing is substantially slower than the memcpy alternative. I think that in principle this shouldn't happen but the numbers are quite clear. Perhaps std::copy is doing something that doesn't use cache effectively ---------Co-authored-by: Jose Luis Rivero <<jrivero@osrfoundation.org>> (cherry picked from commit a781b78852112246245c05481db6335388d4f736) Co-authored-by: Carlos Agüero <<caguero@openrobotics.org>>
- Contributors: mergify[bot]
1.0.3 (2024-07-22)
- Add support for gz.msgs.EntityWrench (base branch: ros2) (#573) (#574) (cherry picked from commit f9afb69d1163633dd978024bb7271a28cf7b551a) Co-authored-by: Victor T. Noppeney <<Vtn21@users.noreply.github.com>>
- Contributors: mergify[bot]
1.0.2 (2024-07-03)
- Merge pull request #569 from azeey/iron_to_jazzy Merge iron ➡️ jazzy
- Merge iron into jazzy
-
Add option to change material color from ROS. (#521) Forward port of #486. * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. (cherry picked from commit 78dc4823121f085594e6028a93f1e571eb04f58b)
- Merge pull request #564 from azeey/humble_to_iron Humble ➡️ Iron
- Merge humble -> iron
- populate imu covariances when converting (#375) (#540) Co-authored-by: El Jawad Alaa <<ejalaa12@gmail.com>>
- Prepare for 1.0.0 Release (#495)
- Use gz_vendor packages (#531)
- [backport Humble] Create bridge for GPSFix msg (#316) (#538) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- [backport Iron] Create bridge for GPSFix msg (#316) (#537) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- 0.244.14
- Changelog
- Added conversion for Detection3D and Detection3DArray (#523) (#526) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- Added conversion for Detection3D and Detection3DArray (#523) (#525) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- [Backport rolling] Add ROS namespaces to GZ topics (#517) Co-authored-by: Krzysztof Wojciechowski <<49921081+Kotochleb@users.noreply.github.com>>
- ign to gz (#519)
- Add ROS namespaces to GZ topics (#512) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Correctly export ros_gz_bridge for downstream targets (#503) (#506)
- Add a virtual destructor to suppress compiler warning (#502) (#505) Co-authored-by: Michael Carroll <<mjcarroll@intrinsic.ai>>
- Correctly export ros_gz_bridge for downstream targets (#503)
- Add a virtual destructor to suppress compiler warning (#502)
-
Add option to change material color from ROS. (#486) * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. ---------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Addisu Z. Taddese <<addisuzt@intrinsic.ai>> Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
- 0.244.13
- Changelog
- backport pr 374 (#489)
- populate imu covariances when converting (#488)
- 0.244.12
- Changelog
- Backport: Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468) (#470)
- Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458) (#466) Co-authored-by: Alejandro Hernandez Cordero <<ahcorde@gmail.com>>
- populate imu covariances when converting (#375)
- 0.246.0
- Update changelogs
- Add harmonic CI
(#447)
- Add harmonic CI
- Include garden options
- Add harmonic stanza
* Additional message headers ---------
- SensorNoise msg bridging (#417)
- Added Altimeter msg bridging (#413)
- Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Add missing rosidl_cmake dep to ros_gz_bridge (#391) Co-authored-by: Chris Lalancette <<clalancette@gmail.com>>
-
allow converting from/to TwistWithCovarianceStamped (#374) * allow converting from/to TwistWithCovarianceStamped --------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Added doc (#393)
- Port: humble to ros2 (#386)
- Merge branch 'humble' into mjcarroll/humble_to_ros2
- allow converting from/to PoseWithCovarianceStamped
(#381)
- allow converting from/to PoseWithCovarianceStamped
- Add actuator_msgs to bridge. (#378)
- Update maintainers (#376)
- Fix warning message (#371)
- Improve error messages around config loading (#356)
- Bringing the Joy to gazebo. (#350) Enable using the gazebo bridge with Joy.
- Fix double wait in ros_gz_bridge (#347)
- Create bridge for GPSFix msg (#316)
- Humble ➡️ ROS2 (#323) Humble ➡️ ROS2
- Merge branch 'humble' into ports/humble_to_ros2
- 0.245.0
- Changelog
- humble to ros2 (#311) Co-authored-by: Michael Carroll <<michael@openrobotics.org>>
- Remove Humble+ deprecations
(#312)
- Remove Humble+ deprecations
- Merge remote-tracking branch 'origin/humble' into ahcorde/humble_to_ros2
- Remove all ignition references on ROS 2 branch
(#302)
- Remove all shims
- Update CMakeLists and package.xml for garden
- Complete garden gz renaming
- Drop fortress CI
- Contributors: Addisu Z. Taddese, Aditya Pande, Alejandro Hernández Cordero, Arjun K Haridas, Benjamin Perseghetti, El Jawad Alaa, Jose Luis Rivero, Krzysztof Wojciechowski, Michael Carroll, Rousseau Vincent, Yadu, ahcorde, wittenator, ymd-stella
1.0.0 (2024-04-24)
- Use gz_vendor packages (#531)
- Added conversion for Detection3D and Detection3DArray (#523) (#525) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- [Backport rolling] Add ROS namespaces to GZ topics (#517) Co-authored-by: Krzysztof Wojciechowski <<49921081+Kotochleb@users.noreply.github.com>>
- ign to gz (#519)
- Correctly export ros_gz_bridge for downstream targets (#503)
- Add a virtual destructor to suppress compiler warning (#502)
- Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458) (#466) Co-authored-by: Alejandro Hernandez Cordero <<ahcorde@gmail.com>>
- populate imu covariances when converting (#375)
- Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, El Jawad Alaa, Michael Carroll
0.246.0 (2023-08-31)
- Add harmonic CI
(#447)
- Add harmonic CI
- Include garden options
- Add harmonic stanza
* Additional message headers ---------
- SensorNoise msg bridging (#417)
- Added Altimeter msg bridging (#413)
- Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Add missing rosidl_cmake dep to ros_gz_bridge (#391) Co-authored-by: Chris Lalancette <<clalancette@gmail.com>>
- allow converting from/to TwistWithCovarianceStamped (#374) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Added doc (#393)
- Port: humble to ros2 (#386)
- Merge branch 'humble' into mjcarroll/humble_to_ros2
- allow converting from/to PoseWithCovarianceStamped
(#381)
- allow converting from/to PoseWithCovarianceStamped
- Add actuator_msgs to bridge. (#378)
- Update maintainers (#376)
- Fix warning message (#371)
- Improve error messages around config loading (#356)
- Bringing the Joy to gazebo. (#350) Enable using the gazebo bridge with Joy.
- Fix double wait in ros_gz_bridge (#347)
- Create bridge for GPSFix msg (#316)
- Humble ➡️ ROS2 (#323)
- Contributors: Aditya Pande, Alejandro Hernández Cordero, Arjun K Haridas, Benjamin Perseghetti, El Jawad Alaa, Michael Carroll, Rousseau Vincent, Yadu, ahcorde, ymd-stella
0.245.0 (2022-10-12)
- humble to ros2 (#311) Co-authored-by: Michael Carroll <<michael@openrobotics.org>>
- Remove Humble+ deprecations
(#312)
- Remove Humble+ deprecations
- Merge remote-tracking branch 'origin/humble' into ahcorde/humble_to_ros2
- Remove all ignition references on ROS 2 branch
(#302)
- Remove all shims
- Update CMakeLists and package.xml for garden
- Complete garden gz renaming
- Drop fortress CI
- Contributors: Alejandro Hernández Cordero, Michael Carroll, ahcorde
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)
- 🏁 Dome EOL (#198)
- Contributors: Aditya Pande, Ivan Santiago Paunovic, Joep Tool, Louise Poubel, Michael Carroll
0.244.1 (2022-01-04)
- Improve modularity of ign/ros publisher tests (#194)
- Contributors: Michael Carroll
0.244.0 (2021-12-30)
- Default to Fortress for Rolling (future Humble) (#195)
- [ros2] 🏁 Dome EOL (#199)
- New Light Message, also bridge Color (#187)
- Statically link each translation unit (#193)
- Break apart convert and factories translation unit (#192)
- Fixed ROS subscriber test in ros_gz_bridge (#189)
- Enable QoS overrides (#181)
- Fixed ros ign bridge documentation (#178)
- Expose Contacts through ROS bridge (#175)
- Contributors: Alejandro Hernández Cordero, Guillaume Doisy, Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew
0.233.2 (2021-07-20)
- [ros2] Update version docs, add Galactic and Fortress (#164)
- Contributors: Louise Poubel
0.233.1 (2021-04-16)
- Default to Edifice for Rolling (#150)
- Ignore local publications for ROS 2 subscriber
(#146)
- Note: Does not work with all rmw implementations (e.g.: FastRTPS)
- Update documentation for installation instructions and bridge examples (#142)
- Edifice support (#140)
- Add JointTrajectory message conversion
(#121) Conversion
between
- ignition::msgs::JointTrajectory
- trajectory_msgs::msg::JointTrajectory
- Add TFMessage / Pose_V and Float64 / Double conversions (#117) Addresses issue #116
- Updated prereq & branch name (#113)
- Update releases (#108)
- Updated README.md (#104)
- Add support for Dome (#103)
- Contributors: Alejandro Hernández Cordero, Andrej Orsula, Florent Audonnet, Jenn, Louise Poubel, Luca Della Vedova
0.221.1 (2020-08-19)
- Add pkg-config as a buildtool dependency (#102)
- Port ros_gz_bridge tests to ROS 2 (#98)
- Rename test_utils.hpp (#98)
- Contributors: Louise Poubel, ahcorde
0.221.0 (2020-07-23)
- Install only what's necessary, rename builtin_interfaces (#95)
- Move headers to src, rename builtin_interfaces (#95)
- Integer support (#91) Adds Int32 to the bridge.
- [ros2] Fixed CI - Added Foxy (#89) Co-authored-by: Louise Poubel <<louise@openrobotics.org>>
- Ignore ros-args in parameter bridge (#65)
- Update Dashing docs (#62)
- Update dependencies to Citadel (#57)
- [WIP] Port ign_ros_gazebo_demos to ROS2 (#58) Port ros_gz_image to ROS2 Port ros_gz_sim_demos to ROS2
- Add support for std_msgs/Empty (#53)
- Add support for std_msgs/Bool (#50)
- [ros2] Port ros_gz_bridge to ROS2 (#45)
- Enable ROS2 CI for Dashing branch (#43)
- Make all API and comments ROS-version agnostic
- Rename packages and fix compilation + tests
- Move files ros1 -> ros
- Contributors: Addisu Taddese, Alejandro Hernández Cordero, Jose Luis Rivero, Louise Poubel, Luca Della Vedova, Michael Carroll, Mohamed Ahmed, Shivesh Khaitan, chapulina
0.7.0 (2019-08-15)
- Merge pull request #38 from osrf/unidirectional Support unidirectional bridge topics
- More examples
- Merge pull request #37 from osrf/debug Adding debug and error statements
- Switch to characters supported by ros
- Merge branch 'debug' into unidirectional
- More output, and rosconsole depend
- Support specification of bridge direction
- Adding debug and error statements
- Contributors: Nate Koenig
0.6.3 (2019-08-04)
0.6.2 (2019-08-04)
0.6.1 (2019-08-04)
- Update README.md
- Contributors: Carlos Agüero
0.6.0 (2019-08-02)
- Merge pull request #33 from osrf/issue_31 Fix issue #31
- Image bridge using image_transport
(#34)
- Image bridge using image_transport
- tests for image
- correct metapackage
* tests with catkin Signed-off-by: Louise Poubel <<louise@openrobotics.org>> * Revert changes from #32 Signed-off-by: Louise Poubel <<louise@openrobotics.org>>
- Use intra-process field from messageInfo.
- Contributors: Carlos Aguero, Nate Koenig, chapulina
- 0.5.0
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
0.4.0 (2019-07-16)
- tests and reverse bridge for pointcloud
- Bridge point cloud packed
- Contributors: Nate Koenig
0.3.1 (2019-07-01)
0.3.0 (2019-06-28)
- 0.2.0
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry
(#22)
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry.
- Update documentation.
- More time to run tests
- Cleaning test_utils.
- Remove explicit ROS dependencies for Travis.
- diff drive demo with cmd_vel and odom
- process child frame id
- Fluid pressure
(#20)
- screenshots
- missing IMU
- Fluid pressure
- Fix tests.
- Demos package
(#19)
- Start of demos package: camera
- IMU
- depth camera
- magnetometer
- lidar, base launch
- READMEs, RGBD camera
- screenshots
- missing IMU
- set plugin path env
- It's best to always set it
- Point clouds for RGBD cameras
(#17)
- Beginning of point cloud package
- Populating image data, but result is not correct. Must find out where's the source of the problem.
- RGB -> BGR: why?
- Cleanup code and example
- pointcloud -> point_cloud
- add keys - how was this working before?
- install wget
- well, we need ign-gz2 :sweat_smile:
- README update
- PR feedback
- .travis/build: rosdep skip ignition keys (#18)
- .travis/build: rosdep skip ignition keys
- Update build
- Move package to subfolder, add metapackage (#16)
- Contributors: Carlos Agüero, Nate Koenig, chapulina
0.2.2 (2019-05-20)
0.2.1 (2019-05-11)
0.2.0 (2019-05-09)
0.1.0 (2019-03-20)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
pkg-config |
Launch files
- launch/ros_gz_bridge.launch
-
- bridge_name
- config_file
- container_name [default: ros_gz_container]
- create_own_container [default: False]
- namespace [default: ]
- use_composition [default: False]
- use_respawn [default: False]
- log_level [default: info]
Messages
Services
Plugins
Recent questions tagged ros_gz_bridge at Robotics Stack Exchange
ros_gz_bridge package from ros_gz reporos_gz ros_gz_bridge ros_gz_image ros_gz_interfaces ros_gz_point_cloud ros_gz_sim ros_gz_sim_demos test_ros_gz_bridge |
|
Package Summary
Tags | No category tags. |
Version | 2.1.2 |
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 | ros2 |
Last Updated | 2024-11-14 |
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
- Aditya Pande
- Alejandro Hernandez
Authors
- Shivesh Khaitan
- Louise Poubel
- Carlos Agüero
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 Transport Type |
---|---|
actuator_msgs/msg/Actuators | gz.msgs.Actuators |
builtin_interfaces/msg/Time | gz.msgs.Time |
geometry_msgs/msg/Point | gz.msgs.Vector3d |
geometry_msgs/msg/Pose | gz.msgs.Pose |
geometry_msgs/msg/PoseArray | gz.msgs.Pose_V |
geometry_msgs/msg/PoseStamped | gz.msgs.Pose |
geometry_msgs/msg/PoseWithCovariance | gz.msgs.PoseWithCovariance |
geometry_msgs/msg/PoseWithCovarianceStamped | gz.msgs.PoseWithCovariance |
geometry_msgs/msg/Quaternion | gz.msgs.Quaternion |
geometry_msgs/msg/Transform | gz.msgs.Pose |
geometry_msgs/msg/TransformStamped | gz.msgs.Pose |
geometry_msgs/msg/Twist | gz.msgs.Twist |
geometry_msgs/msg/TwistStamped | gz.msgs.Twist |
geometry_msgs/msg/TwistWithCovariance | gz.msgs.TwistWithCovariance |
geometry_msgs/msg/TwistWithCovarianceStamped | gz.msgs.TwistWithCovariance |
geometry_msgs/msg/Vector3 | gz.msgs.Vector3d |
geometry_msgs/msg/Wrench | gz.msgs.Wrench |
geometry_msgs/msg/WrenchStamped | gz.msgs.Wrench |
gps_msgs/msg/GPSFix | gz.msgs.NavSat |
nav_msgs/msg/Odometry | gz.msgs.Odometry |
nav_msgs/msg/Odometry | gz.msgs.OdometryWithCovariance |
rcl_interfaces/msg/ParameterValue | gz.msgs.Any |
ros_gz_interfaces/msg/Altimeter | gz.msgs.Altimeter |
ros_gz_interfaces/msg/Contact | gz.msgs.Contact |
ros_gz_interfaces/msg/Contacts | gz.msgs.Contacts |
ros_gz_interfaces/msg/Dataframe | gz.msgs.Dataframe |
ros_gz_interfaces/msg/Entity | gz.msgs.Entity |
ros_gz_interfaces/msg/EntityWrench | gz.msgs.EntityWrench |
ros_gz_interfaces/msg/Float32Array | gz.msgs.Float_V |
ros_gz_interfaces/msg/GuiCamera | gz.msgs.GUICamera |
ros_gz_interfaces/msg/JointWrench | gz.msgs.JointWrench |
ros_gz_interfaces/msg/Light | gz.msgs.Light |
ros_gz_interfaces/msg/ParamVec | gz.msgs.Param |
ros_gz_interfaces/msg/ParamVec | gz.msgs.Param_V |
ros_gz_interfaces/msg/SensorNoise | gz.msgs.SensorNoise |
ros_gz_interfaces/msg/StringVec | gz.msgs.StringMsg_V |
ros_gz_interfaces/msg/TrackVisual | gz.msgs.TrackVisual |
ros_gz_interfaces/msg/VideoRecord | gz.msgs.VideoRecord |
rosgraph_msgs/msg/Clock | gz.msgs.Clock |
sensor_msgs/msg/BatteryState | gz.msgs.BatteryState |
sensor_msgs/msg/CameraInfo | gz.msgs.CameraInfo |
sensor_msgs/msg/FluidPressure | gz.msgs.FluidPressure |
sensor_msgs/msg/Image | gz.msgs.Image |
sensor_msgs/msg/Imu | gz.msgs.IMU |
sensor_msgs/msg/JointState | gz.msgs.Model |
sensor_msgs/msg/Joy | gz.msgs.Joy |
sensor_msgs/msg/LaserScan | gz.msgs.LaserScan |
sensor_msgs/msg/MagneticField | gz.msgs.Magnetometer |
sensor_msgs/msg/NavSatFix | gz.msgs.NavSat |
sensor_msgs/msg/PointCloud2 | gz.msgs.PointCloudPacked |
std_msgs/msg/Bool | gz.msgs.Boolean |
std_msgs/msg/ColorRGBA | gz.msgs.Color |
std_msgs/msg/Empty | gz.msgs.Empty |
std_msgs/msg/Float32 | gz.msgs.Float |
std_msgs/msg/Float64 | gz.msgs.Double |
std_msgs/msg/Header | gz.msgs.Header |
std_msgs/msg/Int32 | gz.msgs.Int32 |
std_msgs/msg/String | gz.msgs.StringMsg |
std_msgs/msg/UInt32 | gz.msgs.UInt32 |
tf2_msgs/msg/TFMessage | gz.msgs.Pose_V |
trajectory_msgs/msg/JointTrajectory | gz.msgs.JointTrajectory |
vision_msgs/msg/Detection2D | gz.msgs.AnnotatedAxisAligned2DBox |
vision_msgs/msg/Detection2DArray | gz.msgs.AnnotatedAxisAligned2DBox_V |
vision_msgs/msg/Detection3D | gz::msgs::AnnotatedOriented3DBox |
vision_msgs/msg/Detection3DArray | gz::msgs::AnnotatedOriented3DBox_V |
And the following for services:
ROS type | Gazebo request | Gazebo response |
---|---|---|
ros_gz_interfaces/srv/ControlWorld | gz.msgs.WorldControl | gz.msgs.Boolean |
Run ros2 run ros_gz_bridge parameter_bridge -h
for instructions.
NOTE: If during startup, gazebo detects that there is another publisher on /clock
, it will only create the fully qualified /world/<worldname>/clock topic
.
Gazebo would be the only /clock
publisher, the sole source of clock information.
You should create an unidirectional /clock
bridge:
ros2 run ros_gz_bridge parameter_bridge /clock@rosgraph_msgs/msg/Clock[gz.msgs.Clock
An alternative set-up can be using the bridge with the override_timestamps_with_wall_time
ros parameter set to true
(default=false
). In this set-up,
all header timestamps of the outgoing messages will be stamped with the wall time. This can be useful when the simulator has to communicate with an external system that requires wall times.
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@gz.msgs.StringMsg
Now we start the ROS listener.
# Shell B:
. /opt/ros/rolling/setup.bash
ros2 topic echo /chatter
Now we start the Gazebo Transport talker.
# Shell C:
gz topic -t /chatter -m gz.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@gz.msgs.StringMsg
Now we start the Gazebo Transport listener.
# Shell B:
gz topic -e -t /chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/rolling/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:
gz sim sensors_demo.sdf
Let’s see the topic where camera images are published.
# Shell B:
gz 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@gz.msgs.Image
Now we start the ROS GUI:
# Shell C:
. /opt/ros/rolling/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:
gz topic -t /chatter -m gz.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 Gazebo listener:
gz 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:
gz sim 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: "gz.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: "gz.msgs.StringMsg"
# Set just GZ topic name, applies to both
- gz_topic_name: "chatter_gz"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.msgs.StringMsg"
# Set each topic name explicitly
- ros_topic_name: "chatter_both_ros"
gz_topic_name: "chatter_both_gz"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.msgs.StringMsg"
# Full set of configurations
- ros_topic_name: "ros_chatter"
gz_topic_name: "gz_chatter"
ros_type_name: "std_msgs/msg/String"
gz_type_name: "gz.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 Gz topic to ROS
# "ROS_TO_GZ" - Bridge ROS topic to Gz
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
Example 6: Using ROS namespace with the Bridge
When spawning multiple robots inside the same ROS environment, it is convenient to use namespaces to avoid overlapping topic names.
There are three main types of namespaces: relative, global (/
) and private (~/
). For more information, refer to ROS documentation.
Namespaces are applied to Gazebo topic both when specified as topic_name
as well as gz_topic_name
.
By default, the Bridge will not apply ROS namespace on the Gazebo topics. To enable this feature, use parameter expand_gz_topic_names
.
Let’s test our topic with namespace:
# Shell A:
. ~/bridge_ws/install/setup.bash
ros2 run ros_gz_bridge parameter_bridge chatter@std_msgs/msg/String@ignition.msgs.StringMsg \
--ros-args -p expand_gz_topic_names:=true -r __ns:=/demo
Now we start the Gazebo Transport listener.
# Shell B:
gz topic -e -t /demo/chatter
Now we start the ROS talker.
# Shell C:
. /opt/ros/rolling/setup.bash
ros2 topic pub /demo/chatter std_msgs/msg/String "data: 'Hi from inside of a namespace'" --once
By changing chatter
to /chatter
or ~/chatter
you can obtain different results.
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 -
expand_gz_topic_names
- Enable or disable ROS namespace applied on GZ topics.
Changelog for package ros_gz_bridge
2.1.2 (2024-10-31)
2.1.1 (2024-10-14)
- Extra parameter to start a container (#616)
- adds deadline and liveliness QoSPolicyKinds to qos_overriding_options (#609) Co-authored-by: nora <<nko@bogaertsgl.com>>
- Contributors: Carlos Agüero, norakon
2.1.0 (2024-09-12)
- Remove default_value for required arguments
(#602)
- Remove default_value for config_file
- Fix errors with name of bridge not being given
(#600)
- Add argument bridge_name to fix errors
- Use optional parameters in actions (#601)
- Contributors: Amronos, Carlos Agüero
2.0.1 (2024-08-29)
- Stamp all outgoing headers with the wall time if parameter override_timestamps_with_wall_time is set to true (#562)
- Contributors: Rein Appeldoorn
2.0.0 (2024-07-22)
- Making use_composition true by default (#578)
- Contributors: Addisu Z. Taddese
1.0.1 (2024-07-03)
- Add support for gz.msgs.EntityWrench (base branch: ros2) (#573)
- Merge pull request #571 from azeey/jazzy_to_ros2 Merge jazzy ➡️ ros2
- Merge branch 'ros2' into jazzy_to_ros2
- Use memcpy instead of std::copy when bridging images (#565) While testing ros <-> gz communication using the bridge I noticed that the bridge was talking quite a bit of time copying images from Gazebo to ROS. I found that the std::copy operation that we're doing is substantially slower than the memcpy alternative. I think that in principle this shouldn't happen but the numbers are quite clear. Perhaps std::copy is doing something that doesn't use cache effectively ---------Co-authored-by: Jose Luis Rivero <<jrivero@osrfoundation.org>>
- Merge jazzy into ros2
- Merge pull request #569 from azeey/iron_to_jazzy Merge iron ➡️ jazzy
- Merge iron into jazzy
-
Add option to change material color from ROS. (#521) Forward port of #486. * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. (cherry picked from commit 78dc4823121f085594e6028a93f1e571eb04f58b)
- Merge pull request #564 from azeey/humble_to_iron Humble ➡️ Iron
- Merge humble -> iron
- Use [ignoreLocalMessages]{.title-ref} in the bridge
(#559)
- Ignore local messages
- Update launch files with name parameter
(#556)
- Name is required.
- Ensure the same container is used for the bridge and gz_server (#553) This also adds a required [name]{.title-ref} parameter for the bridge so that multiple different bridges can be created without name collision
- Launch ros_gz_bridge from xml
(#550)
- Add gzserver with ability to load an SDF file or string
- Launch gzserver and the bridge as composable nodes
(#528)
- Add gzserver with ability to load an SDF file or string
-
Add option to change material color from ROS. (#521) Forward port of #486. * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights.
- populate imu covariances when converting (#375) (#540) Co-authored-by: El Jawad Alaa <<ejalaa12@gmail.com>>
- Prepare for 1.0.0 Release (#495)
- Use gz_vendor packages (#531)
- [backport Humble] Create bridge for GPSFix msg (#316) (#538) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- [backport Iron] Create bridge for GPSFix msg (#316) (#537) Co-authored-by: Rousseau Vincent <<vincentrou@gmail.com>>
- 0.244.14
- Changelog
- Added conversion for Detection3D and Detection3DArray (#523) (#526) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- Added conversion for Detection3D and Detection3DArray (#523) (#525) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- [Backport rolling] Add ROS namespaces to GZ topics (#517) Co-authored-by: Krzysztof Wojciechowski <<49921081+Kotochleb@users.noreply.github.com>>
- ign to gz (#519)
- Add ROS namespaces to GZ topics (#512) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Correctly export ros_gz_bridge for downstream targets (#503) (#506)
- Add a virtual destructor to suppress compiler warning (#502) (#505) Co-authored-by: Michael Carroll <<mjcarroll@intrinsic.ai>>
- Correctly export ros_gz_bridge for downstream targets (#503)
- Add a virtual destructor to suppress compiler warning (#502)
-
Add option to change material color from ROS. (#486) * Message and bridge for MaterialColor. This allows bridging MaterialColor from ROS to GZ and is important for allowing simulation users to create status lights. ---------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Addisu Z. Taddese <<addisuzt@intrinsic.ai>> Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
- 0.244.13
- Changelog
- backport pr 374 (#489)
- populate imu covariances when converting (#488)
- 0.244.12
- Changelog
- Backport: Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468) (#470)
- Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458) (#466) Co-authored-by: Alejandro Hernandez Cordero <<ahcorde@gmail.com>>
- populate imu covariances when converting (#375)
- 0.246.0
- Update changelogs
- Add harmonic CI
(#447)
- Add harmonic CI
- Include garden options
- Add harmonic stanza
* Additional message headers ---------
- SensorNoise msg bridging (#417)
- Added Altimeter msg bridging (#413)
- Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Add missing rosidl_cmake dep to ros_gz_bridge (#391) Co-authored-by: Chris Lalancette <<clalancette@gmail.com>>
-
allow converting from/to TwistWithCovarianceStamped (#374) * allow converting from/to TwistWithCovarianceStamped --------Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Added doc (#393)
- Port: humble to ros2 (#386)
- Merge branch 'humble' into mjcarroll/humble_to_ros2
- allow converting from/to PoseWithCovarianceStamped
(#381)
- allow converting from/to PoseWithCovarianceStamped
- Add actuator_msgs to bridge. (#378)
- Update maintainers (#376)
- Fix warning message (#371)
- Improve error messages around config loading (#356)
- Bringing the Joy to gazebo. (#350) Enable using the gazebo bridge with Joy.
- Fix double wait in ros_gz_bridge (#347)
- Create bridge for GPSFix msg (#316)
- Humble ➡️ ROS2 (#323) Humble ➡️ ROS2
- Merge branch 'humble' into ports/humble_to_ros2
- 0.245.0
- Changelog
- humble to ros2 (#311) Co-authored-by: Michael Carroll <<michael@openrobotics.org>>
- Remove Humble+ deprecations
(#312)
- Remove Humble+ deprecations
- Merge remote-tracking branch 'origin/humble' into ahcorde/humble_to_ros2
- Remove all ignition references on ROS 2 branch
(#302)
- Remove all shims
- Update CMakeLists and package.xml for garden
- Complete garden gz renaming
- Drop fortress CI
- Contributors: Addisu Z. Taddese, Aditya Pande, Alejandro Hernández Cordero, Arjun K Haridas, Benjamin Perseghetti, Carlos Agüero, El Jawad Alaa, Jose Luis Rivero, Krzysztof Wojciechowski, Michael Carroll, Rousseau Vincent, Victor T. Noppeney, Yadu, ahcorde, wittenator, ymd-stella
1.0.0 (2024-04-24)
- Use gz_vendor packages (#531)
- Added conversion for Detection3D and Detection3DArray (#523) (#525) Co-authored-by: wittenator <<9154515+wittenator@users.noreply.github.com>>
- [Backport rolling] Add ROS namespaces to GZ topics (#517) Co-authored-by: Krzysztof Wojciechowski <<49921081+Kotochleb@users.noreply.github.com>>
- ign to gz (#519)
- Correctly export ros_gz_bridge for downstream targets (#503)
- Add a virtual destructor to suppress compiler warning (#502)
- Add conversion for geometry_msgs/msg/TwistStamped <-> gz.msgs.Twist (#468)
- Added messages for 2D Bounding Boxes to ros_gz_bridge (#458) (#466) Co-authored-by: Alejandro Hernandez Cordero <<ahcorde@gmail.com>>
- populate imu covariances when converting (#375)
- Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, El Jawad Alaa, Michael Carroll
0.246.0 (2023-08-31)
- Add harmonic CI
(#447)
- Add harmonic CI
- Include garden options
- Add harmonic stanza
* Additional message headers ---------
- SensorNoise msg bridging (#417)
- Added Altimeter msg bridging (#413)
- Update README.md (#411) The ROS type for gz.msgs.NavSat messages should be sensor_msgs/msg/NavSatFix instead of sensor_msgs/msg/NavSatFixed
- Add missing rosidl_cmake dep to ros_gz_bridge (#391) Co-authored-by: Chris Lalancette <<clalancette@gmail.com>>
- allow converting from/to TwistWithCovarianceStamped (#374) Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>
- Added doc (#393)
- Port: humble to ros2 (#386)
- Merge branch 'humble' into mjcarroll/humble_to_ros2
- allow converting from/to PoseWithCovarianceStamped
(#381)
- allow converting from/to PoseWithCovarianceStamped
- Add actuator_msgs to bridge. (#378)
- Update maintainers (#376)
- Fix warning message (#371)
- Improve error messages around config loading (#356)
- Bringing the Joy to gazebo. (#350) Enable using the gazebo bridge with Joy.
- Fix double wait in ros_gz_bridge (#347)
- Create bridge for GPSFix msg (#316)
- Humble ➡️ ROS2 (#323)
- Contributors: Aditya Pande, Alejandro Hernández Cordero, Arjun K Haridas, Benjamin Perseghetti, El Jawad Alaa, Michael Carroll, Rousseau Vincent, Yadu, ahcorde, ymd-stella
0.245.0 (2022-10-12)
- humble to ros2 (#311) Co-authored-by: Michael Carroll <<michael@openrobotics.org>>
- Remove Humble+ deprecations
(#312)
- Remove Humble+ deprecations
- Merge remote-tracking branch 'origin/humble' into ahcorde/humble_to_ros2
- Remove all ignition references on ROS 2 branch
(#302)
- Remove all shims
- Update CMakeLists and package.xml for garden
- Complete garden gz renaming
- Drop fortress CI
- Contributors: Alejandro Hernández Cordero, Michael Carroll, ahcorde
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)
- 🏁 Dome EOL (#198)
- Contributors: Aditya Pande, Ivan Santiago Paunovic, Joep Tool, Louise Poubel, Michael Carroll
0.244.1 (2022-01-04)
- Improve modularity of ign/ros publisher tests (#194)
- Contributors: Michael Carroll
0.244.0 (2021-12-30)
- Default to Fortress for Rolling (future Humble) (#195)
- [ros2] 🏁 Dome EOL (#199)
- New Light Message, also bridge Color (#187)
- Statically link each translation unit (#193)
- Break apart convert and factories translation unit (#192)
- Fixed ROS subscriber test in ros_gz_bridge (#189)
- Enable QoS overrides (#181)
- Fixed ros ign bridge documentation (#178)
- Expose Contacts through ROS bridge (#175)
- Contributors: Alejandro Hernández Cordero, Guillaume Doisy, Louise Poubel, Michael Carroll, Vatan Aksoy Tezer, William Lew
0.233.2 (2021-07-20)
- [ros2] Update version docs, add Galactic and Fortress (#164)
- Contributors: Louise Poubel
0.233.1 (2021-04-16)
- Default to Edifice for Rolling (#150)
- Ignore local publications for ROS 2 subscriber
(#146)
- Note: Does not work with all rmw implementations (e.g.: FastRTPS)
- Update documentation for installation instructions and bridge examples (#142)
- Edifice support (#140)
- Add JointTrajectory message conversion
(#121) Conversion
between
- ignition::msgs::JointTrajectory
- trajectory_msgs::msg::JointTrajectory
- Add TFMessage / Pose_V and Float64 / Double conversions (#117) Addresses issue #116
- Updated prereq & branch name (#113)
- Update releases (#108)
- Updated README.md (#104)
- Add support for Dome (#103)
- Contributors: Alejandro Hernández Cordero, Andrej Orsula, Florent Audonnet, Jenn, Louise Poubel, Luca Della Vedova
0.221.1 (2020-08-19)
- Add pkg-config as a buildtool dependency (#102)
- Port ros_gz_bridge tests to ROS 2 (#98)
- Rename test_utils.hpp (#98)
- Contributors: Louise Poubel, ahcorde
0.221.0 (2020-07-23)
- Install only what's necessary, rename builtin_interfaces (#95)
- Move headers to src, rename builtin_interfaces (#95)
- Integer support (#91) Adds Int32 to the bridge.
- [ros2] Fixed CI - Added Foxy (#89) Co-authored-by: Louise Poubel <<louise@openrobotics.org>>
- Ignore ros-args in parameter bridge (#65)
- Update Dashing docs (#62)
- Update dependencies to Citadel (#57)
- [WIP] Port ign_ros_gazebo_demos to ROS2 (#58) Port ros_gz_image to ROS2 Port ros_gz_sim_demos to ROS2
- Add support for std_msgs/Empty (#53)
- Add support for std_msgs/Bool (#50)
- [ros2] Port ros_gz_bridge to ROS2 (#45)
- Enable ROS2 CI for Dashing branch (#43)
- Make all API and comments ROS-version agnostic
- Rename packages and fix compilation + tests
- Move files ros1 -> ros
- Contributors: Addisu Taddese, Alejandro Hernández Cordero, Jose Luis Rivero, Louise Poubel, Luca Della Vedova, Michael Carroll, Mohamed Ahmed, Shivesh Khaitan, chapulina
0.7.0 (2019-08-15)
- Merge pull request #38 from osrf/unidirectional Support unidirectional bridge topics
- More examples
- Merge pull request #37 from osrf/debug Adding debug and error statements
- Switch to characters supported by ros
- Merge branch 'debug' into unidirectional
- More output, and rosconsole depend
- Support specification of bridge direction
- Adding debug and error statements
- Contributors: Nate Koenig
0.6.3 (2019-08-04)
0.6.2 (2019-08-04)
0.6.1 (2019-08-04)
- Update README.md
- Contributors: Carlos Agüero
0.6.0 (2019-08-02)
- Merge pull request #33 from osrf/issue_31 Fix issue #31
- Image bridge using image_transport
(#34)
- Image bridge using image_transport
- tests for image
- correct metapackage
* tests with catkin Signed-off-by: Louise Poubel <<louise@openrobotics.org>> * Revert changes from #32 Signed-off-by: Louise Poubel <<louise@openrobotics.org>>
- Use intra-process field from messageInfo.
- Contributors: Carlos Aguero, Nate Koenig, chapulina
- 0.5.0
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
- Battery state (#30)
- Packed demo
(#29)
- adding demo for point cloud packed bridge
- correct rviz file
- RGBD bridged cloud demo
- Merge pull request #28 from osrf/pointcloudpacked Bridge point cloud packed
- Contributors: Nate Koenig, chapulina
0.4.0 (2019-07-16)
- tests and reverse bridge for pointcloud
- Bridge point cloud packed
- Contributors: Nate Koenig
0.3.1 (2019-07-01)
0.3.0 (2019-06-28)
- 0.2.0
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry
(#22)
- Conversion between nav_msgs/Odometry and ignition::msgs::Odometry.
- Update documentation.
- More time to run tests
- Cleaning test_utils.
- Remove explicit ROS dependencies for Travis.
- diff drive demo with cmd_vel and odom
- process child frame id
- Fluid pressure
(#20)
- screenshots
- missing IMU
- Fluid pressure
- Fix tests.
- Demos package
(#19)
- Start of demos package: camera
- IMU
- depth camera
- magnetometer
- lidar, base launch
- READMEs, RGBD camera
- screenshots
- missing IMU
- set plugin path env
- It's best to always set it
- Point clouds for RGBD cameras
(#17)
- Beginning of point cloud package
- Populating image data, but result is not correct. Must find out where's the source of the problem.
- RGB -> BGR: why?
- Cleanup code and example
- pointcloud -> point_cloud
- add keys - how was this working before?
- install wget
- well, we need ign-gz2 :sweat_smile:
- README update
- PR feedback
- .travis/build: rosdep skip ignition keys (#18)
- .travis/build: rosdep skip ignition keys
- Update build
- Move package to subfolder, add metapackage (#16)
- Contributors: Carlos Agüero, Nate Koenig, chapulina
0.2.2 (2019-05-20)
0.2.1 (2019-05-11)
0.2.0 (2019-05-09)
0.1.0 (2019-03-20)
Wiki Tutorials
Package Dependencies
System Dependencies
Name |
---|
pkg-config |
Dependant Packages
Launch files
- launch/ros_gz_bridge.launch
-
- bridge_name
- config_file
- container_name [default: ros_gz_container]
- create_own_container [default: False]
- namespace [default: ]
- use_composition [default: False]
- use_respawn [default: False]
- log_level [default: info]