Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 1.0.15
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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/LogicalCameraImage gz.msgs.LogicalCameraImage
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
sensor_msgs/msg/Range gz.msgs.LaserScan
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.

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

1.0.15 (2025-06-12)

  • Added easy way to configure bridge from XML launch files. (backport #735) (#754)
  • Contributors: mergify[bot]

1.0.14 (2025-05-26)

1.0.13 (2025-05-23)

1.0.12 (2025-05-06)

  • Added LaserScan-Range bridge (backport #736) (#739)
  • Added codespell pre-commit hook. (#721) (#722)
  • Add pre commit (#718) (#719)
  • Contributors: mergify[bot]

1.0.11 (2025-03-21)

  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#712) Co-authored-by: Afereti Pama <<79831813+retinfai@users.noreply.github.com>> Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>

1.0.10 (2025-02-24)

  • Add LogicalCameraImage support (#698) (#699) (cherry picked from commit 16fbab43f8b984c4d23a7d9b8c53910f486f6fd1) Co-authored-by: Dyst-0 <<69257845+Dyst-0@users.noreply.github.com>>
  • Contributors: mergify[bot]

1.0.9 (2025-02-12)

  • Minor optimization to avoid dynamic casting in Gazebo callbacks (#692) (#693) (cherry picked from commit f646d5cade730166f8cb408d483c24b6d382ca0e) Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>
  • Contributors: mergify[bot]

1.0.8 (2025-01-14)

  • Merge pull request #670 from gazebosim/ahcorde/jazzy/bp/663 [backport Jazzy] Improve argument parsing in Actions (#663)

  • Fix linter errors

  • Improve argument parsing in Actions The [RosGzBridge]{.title-ref} and [GzServer]{.title-ref} now support different spellings for boolean arguments ([True]{.title-ref}, [true]{.title-ref}). This also simplifies how conditionals are used to create composable nodes by evaluating the conditionals and using them as regular Python booleans instead of relying on [PythonExpression]{.title-ref}. It was actually the [PythonExpression]{.title-ref} that was preventing support of boolean arguments spelled [true]{.title-ref}/[false]{.title-ref}.

  • Fix use_respawn argument causing errors (#651) (#654) (cherry picked from commit cfd0f8c74ded9efdcb35410135d0a1da1727dcff) Co-authored-by: Aarav Gupta <<amronos275@gmail.com>> Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>

  • Add a way to pass extra parameters to ros_gz_bridge (#628) (#648)

    * Add bridge_params argument to ros_gz_bridge Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Wiktor Bajor <<69388767+Wiktor-99@users.noreply.github.com>> (cherry picked from commit 558a1cfd55f9921e78a87c563d8ed847e9eae6bd) Co-authored-by: Aarav Gupta <<amronos275@gmail.com>>

  • Contributors: Addisu Z. Taddese, Alejandro Hernández Cordero, mergify[bot]

1.0.7 (2024-11-08)

1.0.6 (2024-10-31)

  • Extra parameter to start a container (#616)

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

  • launch/clock_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • bridge_name
      • 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]
  • launch/ros_gz_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • 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]
      • bridge_params [default: ]
  • test/launch/test_launch_action.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • subst [default: msgs]

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 2.1.9
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 kilted
Last Updated 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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/LogicalCameraImage gz.msgs.LogicalCameraImage
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
sensor_msgs/msg/Range gz.msgs.LaserScan
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.

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

2.1.9 (2025-06-12)

  • Added easy way to configure bridge from XML launch files. (#735) (#753)
  • Contributors: mergify[bot]

2.1.8 (2025-05-26)

2.1.7 (2025-05-06)

  • Added LaserScan-Range bridge (backport #736) (#740)
  • use target_link_libraries instead of ament_target_dependencies (#730)
  • Added codespell pre-commit hook. (#721)
  • Add pre commit (#718)
  • Contributors: Alejandro Hernández Cordero, Leander Stephen D'Souza, mergify[bot]

2.1.6 (2025-03-21)

  • make linters happy (#709)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (#380)
  • Contributors: Afereti Pama, Alejandro Hernández Cordero

2.1.5 (2025-02-24)

  • Add LogicalCameraImage support (#698)
  • Contributors: Dyst-0

2.1.4 (2025-02-12)

  • Minor optimization to avoid dynamic casting in Gazebo callbacks (#692)
  • Contributors: Addisu Z. Taddese

2.1.3 (2025-01-14)

  • Use both ROS package and message name for unique mappings (#656) Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>

  • Merge pull request #664 from azeey/improve_parameter_handling Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>

  • Merge pull request #663 from azeey/improve_arg_parsing The [RosGzBridge]{.title-ref} and [GzServer]{.title-ref} now support different spellings for boolean arguments ([True]{.title-ref}, [true]{.title-ref}). This also simplifies how conditionals are used to create composable nodes by evaluating the conditionals and using them as regular Python booleans instead of relying on [PythonExpression]{.title-ref}. It was actually the [PythonExpression]{.title-ref} that was preventing support of boolean arguments spelled [true]{.title-ref}/[false]{.title-ref}.

  • Improve parameter handling for RosGzBridge

  • Fix linter errors

  • Improve argument parsing in Actions The [RosGzBridge]{.title-ref} and [GzServer]{.title-ref} now support different spellings for boolean arguments ([True]{.title-ref}, [true]{.title-ref}). This also simplifies how conditionals are used to create composable nodes by evaluating the conditionals and using them as regular Python booleans instead of relying on [PythonExpression]{.title-ref}. It was actually the [PythonExpression]{.title-ref} that was preventing support of boolean arguments spelled [true]{.title-ref}/[false]{.title-ref}.

  • Fix use_respawn argument causing errors (#651)

  • Add a way to pass extra parameters to ros_gz_bridge (#628)

    * Add bridge_params argument to ros_gz_bridge Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Wiktor Bajor <<69388767+Wiktor-99@users.noreply.github.com>>

  • Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Øystein Sture

2.1.2 (2024-10-31)

2.1.1 (2024-10-14)

  • Extra parameter to start a container

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

  • launch/clock_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • bridge_name
      • 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]
  • launch/ros_gz_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • 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]
      • bridge_params [default: ]
  • test/launch/test_launch_action.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

Package Summary

Tags No category tags.
Version 3.0.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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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/LogicalCameraImage gz.msgs.LogicalCameraImage
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
sensor_msgs/msg/Range gz.msgs.LaserScan
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.

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

3.0.2 (2025-06-12)

  • ros_gz_bridge: Allow setting QoS profile from YAML files and launch action. (#761)
  • Added easy way to configure bridge from XML launch files. (#735)
  • Contributors: Martin Pecka

3.0.1 (2025-05-26)

3.0.0 (2025-05-06)

  • Added LaserScan-Range bridge (backport #736) (#740)
  • use target_link_libraries instead of ament_target_dependencies (#730)
  • Added codespell pre-commit hook. (#721)
  • Add pre commit (#718)
  • Contributors: Alejandro Hernández Cordero, Leander Stephen D'Souza, mergify[bot]

2.1.6 (2025-03-21)

  • make linters happy (#709)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (#380)
  • Contributors: Afereti Pama, Alejandro Hernández Cordero

2.1.5 (2025-02-24)

  • Add LogicalCameraImage support (#698)
  • Contributors: Dyst-0

2.1.4 (2025-02-12)

  • Minor optimization to avoid dynamic casting in Gazebo callbacks (#692)
  • Contributors: Addisu Z. Taddese

2.1.3 (2025-01-14)

  • Use both ROS package and message name for unique mappings (#656) Co-authored-by: Addisu Z. Taddese <<addisu@openrobotics.org>>

  • Merge pull request #664 from azeey/improve_parameter_handling Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>>

  • Merge pull request #663 from azeey/improve_arg_parsing The [RosGzBridge]{.title-ref} and [GzServer]{.title-ref} now support different spellings for boolean arguments ([True]{.title-ref}, [true]{.title-ref}). This also simplifies how conditionals are used to create composable nodes by evaluating the conditionals and using them as regular Python booleans instead of relying on [PythonExpression]{.title-ref}. It was actually the [PythonExpression]{.title-ref} that was preventing support of boolean arguments spelled [true]{.title-ref}/[false]{.title-ref}.

  • Improve parameter handling for RosGzBridge

  • Fix linter errors

  • Improve argument parsing in Actions The [RosGzBridge]{.title-ref} and [GzServer]{.title-ref} now support different spellings for boolean arguments ([True]{.title-ref}, [true]{.title-ref}). This also simplifies how conditionals are used to create composable nodes by evaluating the conditionals and using them as regular Python booleans instead of relying on [PythonExpression]{.title-ref}. It was actually the [PythonExpression]{.title-ref} that was preventing support of boolean arguments spelled [true]{.title-ref}/[false]{.title-ref}.

  • Fix use_respawn argument causing errors (#651)

  • Add a way to pass extra parameters to ros_gz_bridge (#628)

    * Add bridge_params argument to ros_gz_bridge Co-authored-by: Alejandro Hernández Cordero <<ahcorde@gmail.com>> Co-authored-by: Wiktor Bajor <<69388767+Wiktor-99@users.noreply.github.com>>

  • Contributors: Aarav Gupta, Addisu Z. Taddese, Alejandro Hernández Cordero, Øystein Sture

2.1.2 (2024-10-31)

2.1.1 (2024-10-14)

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

  • launch/clock_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • bridge_name
      • 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]
  • launch/ros_gz_bridge.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.
      • 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]
      • bridge_params [default: ]
  • test/launch/test_launch_action.launch
    • Copyright 2025 Open Source Robotics Foundation, Inc. Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License. You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0 Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the License for the specific language governing permissions and limitations under the License.

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro ardent showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro bouncy showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro crystal showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro eloquent showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro dashing showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro galactic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro foxy showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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:

File truncated at 100 lines see the full file

CHANGELOG

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)

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro lunar showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro jade showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro indigo showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro hydro showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro kinetic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro melodic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange

No version for distro noetic showing humble. Known supported distros are highlighted in the buttons above.

Package Summary

Tags No category tags.
Version 0.244.20
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 2025-06-12
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

Bridge communication between ROS and Gazebo Transport

Additional Links

No 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
sensor_msgs/msg/Range ignition::msgs::LaserScan
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.

```

File truncated at 100 lines see the full file

CHANGELOG

Changelog for package ros_gz_bridge

0.244.20 (2025-06-12)

0.244.19 (2025-05-26)

0.244.18 (2025-05-23)

0.244.17 (2025-05-06)

  • Added LaserScan-Range bridge (#736)
  • Backported override_timestamps_with_wall_time to humble (#731)
  • Added codespell pre-commit hook. (backport #721) (#723)
  • Add pre commit (backport #718) (#720)
  • Fix missing child_frame_id in TF2 message conversion (#710)
  • Add SpawnEntity, DeleteEntity, & SetEntityPose Support (backport #380) (#713)
  • Contributors: Noa Thouard, chcaya, mergify[bot]

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)

  • backport pr 374 (#489)
  • populate imu covariances when converting (#488)
  • Contributors: El Jawad Alaa

File truncated at 100 lines see the full file

Wiki Tutorials

This package does not provide any links to tutorials in it's rosindex metadata. You can check on the ROS Wiki Tutorials page for the package.

Launch files

No launch files found

Messages

No message files found.

Services

No service files found

Plugins

No plugins found.

Recent questions tagged ros_gz_bridge at Robotics Stack Exchange