├── .github
├── CODEOWNERS
└── workflows
│ ├── build-and-test.sh
│ ├── ros2-ci.yml
│ └── triage.yml
├── .gitignore
├── .pre-commit-config.yaml
├── CONTRIBUTING.md
├── LICENSE
├── README.md
├── README_RENAME.md
├── RELEASING.md
├── img
└── video_img.png
├── ros_gz
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
└── package.xml
├── ros_gz_bridge
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── bin
│ ├── ros_gz_bridge_generate_factories
│ ├── ros_gz_bridge_generate_tests
│ └── ros_gz_bridge_markdown_table
├── images
│ └── bridge_image_exchange.png
├── include
│ └── ros_gz_bridge
│ │ ├── bridge_config.hpp
│ │ ├── convert.hpp
│ │ ├── convert
│ │ ├── actuator_msgs.hpp
│ │ ├── builtin_interfaces.hpp
│ │ ├── geometry_msgs.hpp
│ │ ├── gps_msgs.hpp
│ │ ├── nav_msgs.hpp
│ │ ├── rcl_interfaces.hpp
│ │ ├── ros_gz_interfaces.hpp
│ │ ├── rosgraph_msgs.hpp
│ │ ├── sensor_msgs.hpp
│ │ ├── std_msgs.hpp
│ │ ├── tf2_msgs.hpp
│ │ ├── trajectory_msgs.hpp
│ │ └── vision_msgs.hpp
│ │ ├── convert_decl.hpp
│ │ └── ros_gz_bridge.hpp
├── launch
│ ├── clock_bridge.launch
│ ├── ros_gz_bridge.launch
│ └── ros_gz_bridge.launch.py
├── package.xml
├── resource
│ ├── get_factory.cpp.em
│ ├── get_mappings.cpp.em
│ ├── pkg_factories.cpp.em
│ ├── pkg_factories.hpp.em
│ └── ros_gz_bridge
├── ros_gz_bridge
│ ├── __init__.py
│ ├── actions
│ │ ├── __init__.py
│ │ └── ros_gz_bridge.py
│ └── mappings.py
├── setup.cfg
├── src
│ ├── bridge_config.cpp
│ ├── bridge_handle.cpp
│ ├── bridge_handle.hpp
│ ├── bridge_handle_gz_to_ros.cpp
│ ├── bridge_handle_gz_to_ros.hpp
│ ├── bridge_handle_ros_to_gz.cpp
│ ├── bridge_handle_ros_to_gz.hpp
│ ├── bridge_types.cpp
│ ├── convert
│ │ ├── actuator_msgs.cpp
│ │ ├── builtin_interfaces.cpp
│ │ ├── geometry_msgs.cpp
│ │ ├── gps_msgs.cpp
│ │ ├── nav_msgs.cpp
│ │ ├── rcl_interfaces.cpp
│ │ ├── rcl_interfaces_TEST.cpp
│ │ ├── ros_gz_interfaces.cpp
│ │ ├── ros_gz_interfaces_TEST.cpp
│ │ ├── rosgraph_msgs.cpp
│ │ ├── sensor_msgs.cpp
│ │ ├── std_msgs.cpp
│ │ ├── tf2_msgs.cpp
│ │ ├── trajectory_msgs.cpp
│ │ ├── utils.cpp
│ │ ├── utils.hpp
│ │ └── vision_msgs.cpp
│ ├── factory.hpp
│ ├── factory_interface.cpp
│ ├── factory_interface.hpp
│ ├── get_factory.hpp
│ ├── get_mappings.hpp
│ ├── parameter_bridge.cpp
│ ├── ros_gz_bridge.cpp
│ ├── service_factories
│ │ ├── ros_gz_interfaces.cpp
│ │ └── ros_gz_interfaces.hpp
│ ├── service_factory.hpp
│ ├── service_factory_interface.cpp
│ ├── service_factory_interface.hpp
│ └── static_bridge.cpp
└── test
│ ├── bridge_config.cpp
│ ├── config
│ ├── empty.yaml
│ ├── full.yaml
│ ├── invalid.yaml
│ └── minimum.yaml
│ ├── launch
│ ├── test_gz_server.launch.py
│ ├── test_gz_subscriber.launch.py
│ ├── test_launch_action.launch
│ ├── test_launch_action.launch.py
│ └── test_ros_subscriber.launch.py
│ ├── resource
│ ├── gz_publisher.cpp.em
│ ├── gz_subscriber.cpp.em
│ ├── ros_pkg_subscriber.cpp.em
│ └── ros_publisher.cpp.em
│ ├── serverclient
│ ├── gz_server.cpp
│ └── ros_client.cpp
│ ├── subscribers
│ ├── launch_action_subscriber.cpp
│ ├── ros_subscriber.cpp
│ ├── ros_subscriber.hpp
│ └── ros_subscriber
│ │ └── ros_gz_interfaces_subscriber.cpp
│ └── utils
│ ├── gz_test_msg.cpp
│ ├── gz_test_msg.hpp
│ ├── ros_test_msg.cpp
│ ├── ros_test_msg.hpp
│ └── test_utils.hpp
├── ros_gz_image
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── package.xml
├── src
│ └── image_bridge.cpp
└── test
│ ├── AMENT_IGNORE
│ ├── launch
│ └── test_ros_subscriber.launch
│ ├── publishers
│ └── gz_publisher.cpp
│ ├── ros_subscriber.test
│ ├── subscribers
│ └── ros_subscriber.cpp
│ └── test_utils.h
├── ros_gz_interfaces
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── msg
│ ├── Altimeter.msg
│ ├── Contact.msg
│ ├── Contacts.msg
│ ├── Dataframe.msg
│ ├── Entity.msg
│ ├── EntityFactory.msg
│ ├── EntityWrench.msg
│ ├── Float32Array.msg
│ ├── GuiCamera.msg
│ ├── JointWrench.msg
│ ├── Light.msg
│ ├── LogicalCameraImage.msg
│ ├── LogicalCameraImageModel.msg
│ ├── MaterialColor.msg
│ ├── ParamVec.msg
│ ├── SensorNoise.msg
│ ├── StringVec.msg
│ ├── TrackVisual.msg
│ ├── VideoRecord.msg
│ ├── WorldControl.msg
│ └── WorldReset.msg
├── package.xml
└── srv
│ ├── ControlWorld.srv
│ ├── DeleteEntity.srv
│ ├── SetEntityPose.srv
│ └── SpawnEntity.srv
├── ros_gz_point_cloud
├── CHANGELOG.rst
├── CMakeLists.txt
├── COLCON_IGNORE
├── examples
│ ├── depth_camera.sdf
│ ├── gpu_lidar.sdf
│ └── rgbd_camera.sdf
├── package.xml
└── src
│ ├── point_cloud.cc
│ └── point_cloud.hh
├── ros_gz_sim
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── include
│ └── ros_gz_sim
│ │ ├── Stopwatch.hpp
│ │ ├── delete_entity.hpp
│ │ ├── gzserver.hpp
│ │ ├── set_entity_pose.hpp
│ │ └── spawn_entity.hpp
├── launch
│ ├── gz_remove_model.launch.py
│ ├── gz_server.launch
│ ├── gz_server.launch.py
│ ├── gz_sim.launch.py.in
│ ├── gz_spawn_model.launch
│ ├── gz_spawn_model.launch.py
│ ├── ros_gz_sim.launch
│ ├── ros_gz_sim.launch.py
│ ├── ros_gz_spawn_model.launch
│ └── ros_gz_spawn_model.launch.py
├── package.xml
├── resource
│ └── ros_gz_sim
├── ros_gz_sim
│ ├── __init__.py
│ └── actions
│ │ ├── __init__.py
│ │ ├── gz_spawn_model.py
│ │ └── gzserver.py
├── setup.cfg
├── src
│ ├── Stopwatch.cpp
│ ├── create.cpp
│ ├── delete_entity.cpp
│ ├── gzserver.cpp
│ ├── remove.cpp
│ ├── set_entity_pose.cpp
│ └── spawn_entity.cpp
└── test
│ ├── test_create.cpp
│ ├── test_create_node.launch.py
│ ├── test_delete_entity.cpp
│ ├── test_remove.cpp
│ ├── test_remove_node.launch.py
│ ├── test_set_entity_pose.cpp
│ ├── test_spawn_entity.cpp
│ └── test_stopwatch.cpp
├── ros_gz_sim_demos
├── CHANGELOG.rst
├── CMakeLists.txt
├── README.md
├── config
│ ├── air_pressure.yaml
│ ├── battery.yaml
│ ├── camera.yaml
│ ├── diff_drive.yaml
│ ├── gpu_lidar.yaml
│ ├── imu.yaml
│ ├── magnetometer.yaml
│ ├── navsat.yaml
│ ├── navsat_gpsfix.yaml
│ ├── rgbd_camera_bridge.yaml
│ ├── tf_bridge.yaml
│ └── triggered_camera.yaml
├── hooks
│ └── ros_gz_sim_demos.dsv.in
├── images
│ ├── air_pressure_demo.png
│ ├── battery_demo.png
│ ├── camera_demo.png
│ ├── depth_camera_demo.png
│ ├── diff_drive_demo.png
│ ├── gpu_lidar_demo.png
│ ├── imu_demo.png
│ ├── joint_states.png
│ ├── magnetometer_demo.png
│ ├── navsat_demo.png
│ ├── rgbd_camera_demo.png
│ ├── robot_state_publisher_demo.png
│ ├── shapes_demo.png
│ └── tf_bridge.gif
├── launch
│ ├── air_pressure.launch.xml
│ ├── battery.launch.py
│ ├── camera.launch.xml
│ ├── depth_camera.launch.py
│ ├── diff_drive.launch.xml
│ ├── gpu_lidar.launch.py
│ ├── gpu_lidar_bridge.launch.xml
│ ├── image_bridge.launch.py
│ ├── imu.launch.xml
│ ├── joint_states.launch.py
│ ├── magnetometer.launch.xml
│ ├── navsat.launch.xml
│ ├── navsat_gpsfix.launch.xml
│ ├── rgbd_camera.launch.py
│ ├── rgbd_camera_bridge.launch.xml
│ ├── robot_description_publisher.launch.py
│ ├── sdf_parser.launch.py
│ ├── tf_bridge.launch.xml
│ └── triggered_camera.launch.xml
├── models
│ ├── cardboard_box
│ │ ├── materials
│ │ │ └── textures
│ │ │ │ └── cardboard_box.png
│ │ ├── meshes
│ │ │ └── cardboard_box.dae
│ │ ├── model.config
│ │ ├── model.sdf
│ │ └── thumbnails
│ │ │ ├── 1.png
│ │ │ ├── 2.png
│ │ │ ├── 3.png
│ │ │ ├── 4.png
│ │ │ └── 5.png
│ ├── double_pendulum_model.sdf
│ ├── rrbot.xacro
│ └── vehicle
│ │ ├── model.config
│ │ └── model.sdf
├── package.xml
├── resources
│ ├── delete_entity.gif
│ ├── set_entity.gif
│ └── spawn.gif
├── rviz
│ ├── camera.rviz
│ ├── depth_camera.rviz
│ ├── diff_drive.rviz
│ ├── gpu_lidar.rviz
│ ├── gpu_lidar_bridge.rviz
│ ├── imu.rviz
│ ├── joint_states.rviz
│ ├── rgbd_camera.rviz
│ ├── rgbd_camera_bridge.rviz
│ ├── robot_description_publisher.rviz
│ ├── tf_bridge.rviz
│ └── vehicle.rviz
└── worlds
│ ├── default.sdf
│ └── vehicle.sdf
├── test_ros_gz_bridge
├── CHANGELOG.rst
├── CMakeLists.txt
├── package.xml
└── src
│ └── test_ros_gz_bridge.cpp
└── tools
├── .codespell_ignore_words
└── pyproject.toml
/.github/CODEOWNERS:
--------------------------------------------------------------------------------
1 | # More info:
2 | # https://help.github.com/en/github/creating-cloning-and-archiving-repositories/about-code-owners
3 |
4 | * @adityapande-1995
5 | * @ahcorde
6 |
--------------------------------------------------------------------------------
/.github/workflows/build-and-test.sh:
--------------------------------------------------------------------------------
1 | #!/bin/bash
2 | set -ev
3 |
4 | # Configuration.
5 | export COLCON_WS=~/ws
6 | export COLCON_WS_SRC=${COLCON_WS}/src
7 | export DEBIAN_FRONTEND=noninteractive
8 | export ROS_PYTHON_VERSION=3
9 |
10 | apt update -qq
11 | apt install -qq -y lsb-release wget curl build-essential
12 |
13 | echo "deb http://packages.osrfoundation.org/gazebo/ubuntu-stable `lsb_release -cs` main" > /etc/apt/sources.list.d/gazebo-stable.list
14 | wget https://packages.osrfoundation.org/gazebo.key -O - | apt-key add -
15 |
16 | # Dependencies.
17 | echo "deb http://packages.ros.org/ros2-testing/ubuntu `lsb_release -cs` main" > /etc/apt/sources.list.d/ros2-testing.list
18 | curl -s https://raw.githubusercontent.com/ros/rosdistro/master/ros.asc | apt-key add -
19 | apt-get update -qq
20 | apt-get install -y python3-colcon-common-extensions \
21 | python3-rosdep \
22 | libcli11-dev
23 |
24 | rosdep init
25 | rosdep update
26 | rosdep install --from-paths ./ -i -y -r --rosdistro $ROS_DISTRO $ROSDEP_ARGS
27 |
28 | # Build.
29 | source /opt/ros/$ROS_DISTRO/setup.bash
30 | mkdir -p $COLCON_WS_SRC
31 | cp -r $GITHUB_WORKSPACE $COLCON_WS_SRC
32 | cd $COLCON_WS
33 | colcon build --event-handlers console_direct+
34 |
35 | # Tests.
36 | colcon test --event-handlers console_direct+
37 | colcon test-result
38 |
--------------------------------------------------------------------------------
/.github/workflows/ros2-ci.yml:
--------------------------------------------------------------------------------
1 | name: ROS2 CI
2 |
3 | on: [push, pull_request]
4 |
5 | jobs:
6 | pre-commit:
7 | name: Pre-commit
8 | runs-on: ubuntu-latest
9 | steps:
10 | - name: Checkout
11 | uses: actions/checkout@v4
12 |
13 | - name: Set up Python
14 | uses: actions/setup-python@v4
15 |
16 | - name: Run pre-commit
17 | uses: pre-commit/action@v3.0.1
18 |
19 | ros_gz_ci:
20 | name: ros_gz CI
21 | runs-on: ubuntu-latest
22 | strategy:
23 | fail-fast: false
24 | matrix:
25 | include:
26 | - docker-image: "ubuntu:24.04"
27 | gz-version: "harmonic"
28 | ros-distro: "rolling"
29 | container:
30 | image: ${{ matrix.docker-image }}
31 | steps:
32 | - name: Checkout
33 | uses: actions/checkout@v4
34 | - name: Build and Test
35 | run: .github/workflows/build-and-test.sh
36 | env:
37 | DOCKER_IMAGE: ${{ matrix.docker-image }}
38 | GZ_VERSION: ${{ matrix.gz-version }}
39 | ROS_DISTRO: ${{ matrix.ros-distro }}
40 |
--------------------------------------------------------------------------------
/.github/workflows/triage.yml:
--------------------------------------------------------------------------------
1 | on:
2 | issues:
3 | types: [opened]
4 | pull_request_target:
5 | types: [opened]
6 | name: Ticket opened
7 | jobs:
8 | assign:
9 | name: Add ticket to inbox
10 | runs-on: ubuntu-latest
11 | steps:
12 | - name: Add ticket to inbox
13 | uses: actions/add-to-project@v0.5.0
14 | with:
15 | project-url: https://github.com/orgs/gazebosim/projects/7
16 | github-token: ${{ secrets.TRIAGE_TOKEN }}
17 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | **/__pycache__
2 | .vscode
3 |
--------------------------------------------------------------------------------
/.pre-commit-config.yaml:
--------------------------------------------------------------------------------
1 | repos:
2 | - repo: https://github.com/pre-commit/pre-commit-hooks
3 | rev: v5.0.0
4 | hooks:
5 | - id: check-added-large-files
6 | args: ['--maxkb=500']
7 | - id: check-merge-conflict
8 | - id: check-xml
9 | - id: check-yaml
10 | - id: end-of-file-fixer
11 | - id: mixed-line-ending
12 | - id: trailing-whitespace
13 |
14 | - repo: https://github.com/codespell-project/codespell
15 | rev: v2.4.1
16 | hooks:
17 | - id: codespell
18 | additional_dependencies:
19 | - tomli
20 | args:
21 | [--toml=./tools/pyproject.toml]
22 |
--------------------------------------------------------------------------------
/CONTRIBUTING.md:
--------------------------------------------------------------------------------
1 | Any contribution that you make to this repository will
2 | be under the Apache 2 License, as dictated by that
3 | [license](http://www.apache.org/licenses/LICENSE-2.0.html):
4 |
5 | ~~~
6 | 5. Submission of Contributions. Unless You explicitly state otherwise,
7 | any Contribution intentionally submitted for inclusion in the Work
8 | by You to the Licensor shall be under the terms and conditions of
9 | this License, without any additional terms or conditions.
10 | Notwithstanding the above, nothing herein shall supersede or modify
11 | the terms of any separate license agreement you may have executed
12 | with Licensor regarding such Contributions.
13 | ~~~
14 |
--------------------------------------------------------------------------------
/README_RENAME.md:
--------------------------------------------------------------------------------
1 | # Description
2 |
3 | These are shim packages for `ros_gz` that redirect executable calls to the related `ros_gz` executable.
4 | These require `ros_gz` to be installed though, but are set up to depend on `ros_gz`.
5 |
6 | This allows users to do either of these and get equivalent behavior:
7 |
8 | ```bash
9 | ros2 run ros_gz parameter_bridge [...]
10 | ros2 run ros_gz parameter_bridge [...] # Will emit deprecation warning
11 | ```
12 |
13 | Additionally, installed files like launch files, message interfaces etc. are **duplicated** versions of the ones in `ros_gz` (but renamed as appropriate), and point to `ros_gz` dependencies as well (e.g. launch files pointing to `ros_gz` nodes.)
14 |
--------------------------------------------------------------------------------
/img/video_img.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/6ab206d991072014230c1355e7566fe4899f80d0/img/video_img.png
--------------------------------------------------------------------------------
/ros_gz/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 | project(ros_gz)
3 | find_package(ament_cmake REQUIRED)
4 |
5 | if(BUILD_TESTING)
6 | find_package(ament_lint_auto REQUIRED)
7 | ament_lint_auto_find_test_dependencies()
8 | endif()
9 |
10 | ament_package()
11 |
--------------------------------------------------------------------------------
/ros_gz/README.md:
--------------------------------------------------------------------------------
1 | # ROS-Gazebo packages
2 |
3 | `ros_gz` is a metapackage that installs all packages integrating
4 | [ROS](http://www.ros.org/) and [Gazebo](https://gazebosim.org):
5 |
--------------------------------------------------------------------------------
/ros_gz/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
6 | ros_gz
7 | 3.0.1
8 | Meta-package containing interfaces for using ROS 2 with Gazebo simulation.
9 | Aditya Pande
10 | Alejandro Hernandez
11 | Apache 2.0
12 |
13 | Louise Poubel
14 |
15 | ament_cmake
16 |
17 | ros_gz_bridge
18 | ros_gz_sim
19 | ros_gz_sim_demos
20 | ros_gz_image
21 |
22 |
23 |
24 | ament_lint_auto
25 | ament_lint_common
26 |
27 |
28 | ament_cmake
29 |
30 |
31 |
--------------------------------------------------------------------------------
/ros_gz_bridge/bin/ros_gz_bridge_generate_factories:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | # Copyright 2022 Open Source Robotics Foundation, Inc.
3 | #
4 | # Licensed under the Apache License, Version 2.0 (the "License");
5 | # you may not use this file except in compliance with the License.
6 | # You may obtain a copy of the License at
7 | #
8 | # http://www.apache.org/licenses/LICENSE-2.0
9 | #
10 | # Unless required by applicable law or agreed to in writing, software
11 | # distributed under the License is distributed on an "AS IS" BASIS,
12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | # See the License for the specific language governing permissions and
14 | # limitations under the License.
15 |
16 |
17 | import argparse
18 | import os
19 | import sys
20 |
21 | # add ros_gz_bridge to the Python path
22 | ros_gz_bridge_root = os.path.join(os.path.dirname(__file__), '..')
23 | sys.path.insert(0, os.path.abspath(ros_gz_bridge_root))
24 |
25 | from ros_gz_bridge import generate_cpp
26 |
27 |
28 | def main(argv=sys.argv[1:]):
29 | parser = argparse.ArgumentParser(
30 | description='Generate C++ template specializations.',
31 | formatter_class=argparse.ArgumentDefaultsHelpFormatter)
32 | parser.add_argument(
33 | '--output-path',
34 | required=True,
35 | help='The basepath of the generated C++ files')
36 | parser.add_argument(
37 | '--template-dir',
38 | required=True,
39 | help='The location of the template files')
40 | parser.add_argument(
41 | '--gz-msgs-ver',
42 | required=False,
43 | default="0.0.0",
44 | help='Gazebo messages version')
45 |
46 | args = parser.parse_args(argv)
47 | msgs_ver = tuple(map(int, args.gz_msgs_ver.split('.')))
48 |
49 | try:
50 | return generate_cpp(
51 | args.output_path,
52 | args.template_dir,
53 | msgs_ver,
54 | )
55 | except RuntimeError as e:
56 | print(str(e), file=sys.stderr)
57 | return 1
58 |
59 |
60 | if __name__ == '__main__':
61 | sys.exit(main())
62 |
--------------------------------------------------------------------------------
/ros_gz_bridge/bin/ros_gz_bridge_generate_tests:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | # Copyright 2022 Open Source Robotics Foundation, Inc.
3 | #
4 | # Licensed under the Apache License, Version 2.0 (the "License");
5 | # you may not use this file except in compliance with the License.
6 | # You may obtain a copy of the License at
7 | #
8 | # http://www.apache.org/licenses/LICENSE-2.0
9 | #
10 | # Unless required by applicable law or agreed to in writing, software
11 | # distributed under the License is distributed on an "AS IS" BASIS,
12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | # See the License for the specific language governing permissions and
14 | # limitations under the License.
15 |
16 |
17 | import argparse
18 | import os
19 | import sys
20 |
21 | # add ros_gz_bridge to the Python path
22 | ros_gz_bridge_root = os.path.join(os.path.dirname(__file__), '..')
23 | sys.path.insert(0, os.path.abspath(ros_gz_bridge_root))
24 |
25 | from ros_gz_bridge import generate_test_cpp
26 |
27 |
28 | def main(argv=sys.argv[1:]):
29 | parser = argparse.ArgumentParser(
30 | description='Generate C++ template specializations.',
31 | formatter_class=argparse.ArgumentDefaultsHelpFormatter)
32 | parser.add_argument(
33 | '--output-path',
34 | required=True,
35 | help='The basepath of the generated C++ files')
36 | parser.add_argument(
37 | '--template-dir',
38 | required=True,
39 | help='The location of the template files')
40 | parser.add_argument(
41 | '--gz-msgs-ver',
42 | required=False,
43 | default="0.0.0",
44 | help='Gazebo messages version')
45 |
46 | args = parser.parse_args(argv)
47 | msgs_ver = tuple(map(int, args.gz_msgs_ver.split('.')))
48 |
49 | try:
50 | return generate_test_cpp(
51 | args.output_path,
52 | args.template_dir,
53 | msgs_ver
54 | )
55 | except RuntimeError as e:
56 | print(str(e), file=sys.stderr)
57 | return 1
58 |
59 |
60 | if __name__ == '__main__':
61 | sys.exit(main())
62 |
--------------------------------------------------------------------------------
/ros_gz_bridge/bin/ros_gz_bridge_markdown_table:
--------------------------------------------------------------------------------
1 | #!/usr/bin/env python3
2 | # Copyright 2022 Open Source Robotics Foundation, Inc.
3 | #
4 | # Licensed under the Apache License, Version 2.0 (the "License");
5 | # you may not use this file except in compliance with the License.
6 | # You may obtain a copy of the License at
7 | #
8 | # http://www.apache.org/licenses/LICENSE-2.0
9 | #
10 | # Unless required by applicable law or agreed to in writing, software
11 | # distributed under the License is distributed on an "AS IS" BASIS,
12 | # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13 | # See the License for the specific language governing permissions and
14 | # limitations under the License.
15 |
16 | import argparse
17 | import os
18 | import sys
19 |
20 | # add ros_gz_bridge to the Python path
21 | ros_gz_bridge_root = os.path.join(os.path.dirname(__file__), '..')
22 | sys.path.insert(0, os.path.abspath(ros_gz_bridge_root))
23 |
24 | from ros_gz_bridge import mappings
25 |
26 | def main(argv=sys.argv[1:]):
27 | parser = argparse.ArgumentParser(
28 | description='Generate Markdown table of supported messages.',
29 | formatter_class=argparse.ArgumentDefaultsHelpFormatter)
30 | parser.add_argument(
31 | '--gz-msgs-ver',
32 | required=False,
33 | default="0.0.0",
34 | help='Gazebo messages version')
35 |
36 | args = parser.parse_args(argv)
37 | msgs_ver = tuple(map(int, args.gz_msgs_ver.split('.')))
38 |
39 | rows = []
40 | rows.append(f'| {"ROS type":35}| {"Gazebo Transport Type":35}|')
41 | rows.append(f'|{"-":-<36}|:{"-":-<34}:|')
42 |
43 | for mapping in mappings(msgs_ver):
44 | rows.append('| {:35}| {:35}|'.format(
45 | mapping.ros2_package_name + '/msg/' + mapping.ros2_message_name,
46 | mapping.gz_string()))
47 | print('\n'.join(rows))
48 |
49 |
50 | if __name__ == '__main__':
51 | sys.exit(main())
52 |
--------------------------------------------------------------------------------
/ros_gz_bridge/images/bridge_image_exchange.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/6ab206d991072014230c1355e7566fe4899f80d0/ros_gz_bridge/images/bridge_image_exchange.png
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT_HPP_
17 |
18 | #include
19 | #include
20 | #include
21 | #include
22 | #include
23 | #include
24 | #include
25 | #include
26 | #include
27 | #include
28 |
29 | #endif // ROS_GZ_BRIDGE__CONVERT_HPP_
30 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/actuator_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2023 Rudis Laboratories LLC
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__ACTUATOR_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__ACTUATOR_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 |
24 | #include
25 |
26 | namespace ros_gz_bridge
27 | {
28 | // actuator_msgs
29 | template<>
30 | void
31 | convert_ros_to_gz(
32 | const actuator_msgs::msg::Actuators & ros_msg,
33 | gz::msgs::Actuators & gz_msg);
34 |
35 | template<>
36 | void
37 | convert_gz_to_ros(
38 | const gz::msgs::Actuators & gz_msg,
39 | actuator_msgs::msg::Actuators & ros_msg);
40 |
41 | } // namespace ros_gz_bridge
42 |
43 | #endif // ROS_GZ_BRIDGE__CONVERT__ACTUATOR_MSGS_HPP_
44 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/builtin_interfaces.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_
17 |
18 | #include
19 |
20 | #include
21 |
22 | #include "ros_gz_bridge/convert_decl.hpp"
23 |
24 | namespace ros_gz_bridge
25 | {
26 |
27 | template<>
28 | void
29 | convert_ros_to_gz(
30 | const builtin_interfaces::msg::Time & ros_msg,
31 | gz::msgs::Time & gz_msg);
32 |
33 | template<>
34 | void
35 | convert_gz_to_ros(
36 | const gz::msgs::Time & gz_msg,
37 | builtin_interfaces::msg::Time & ros_msg);
38 |
39 | } // namespace ros_gz_bridge
40 |
41 | #endif // ROS_GZ_BRIDGE__CONVERT__BUILTIN_INTERFACES_HPP_
42 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/gps_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__GPS_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__GPS_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 |
24 | #include
25 |
26 | namespace ros_gz_bridge
27 | {
28 | template<>
29 | void
30 | convert_ros_to_gz(
31 | const gps_msgs::msg::GPSFix & ros_msg,
32 | gz::msgs::NavSat & gz_msg);
33 |
34 | template<>
35 | void
36 | convert_gz_to_ros(
37 | const gz::msgs::NavSat & gz_msg,
38 | gps_msgs::msg::GPSFix & ros_msg);
39 | } // namespace ros_gz_bridge
40 |
41 | #endif // ROS_GZ_BRIDGE__CONVERT__GPS_MSGS_HPP_
42 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/nav_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 | #include
21 |
22 | // ROS 2 messages
23 | #include
24 |
25 | #include
26 |
27 | namespace ros_gz_bridge
28 | {
29 | // nav_msgs
30 | template<>
31 | void
32 | convert_ros_to_gz(
33 | const nav_msgs::msg::Odometry & ros_msg,
34 | gz::msgs::Odometry & gz_msg);
35 |
36 | template<>
37 | void
38 | convert_gz_to_ros(
39 | const gz::msgs::Odometry & gz_msg,
40 | nav_msgs::msg::Odometry & ros_msg);
41 |
42 | template<>
43 | void
44 | convert_ros_to_gz(
45 | const nav_msgs::msg::Odometry & ros_msg,
46 | gz::msgs::OdometryWithCovariance & gz_msg);
47 |
48 | template<>
49 | void
50 | convert_gz_to_ros(
51 | const gz::msgs::OdometryWithCovariance & gz_msg,
52 | nav_msgs::msg::Odometry & ros_msg);
53 |
54 | } // namespace ros_gz_bridge
55 |
56 | #endif // ROS_GZ_BRIDGE__CONVERT__NAV_MSGS_HPP_
57 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/rcl_interfaces.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_
17 |
18 | // GZ messages
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 | #include
24 | #include
25 |
26 | #include
27 |
28 | namespace ros_gz_bridge
29 | {
30 |
31 | template<>
32 | void
33 | convert_ros_to_gz(
34 | const rcl_interfaces::msg::ParameterValue & ros_msg,
35 | gz::msgs::Any & ign_msg);
36 |
37 | template<>
38 | void
39 | convert_gz_to_ros(
40 | const gz::msgs::Any & ign_msg,
41 | rcl_interfaces::msg::ParameterValue & ros_msg);
42 |
43 | } // namespace ros_gz_bridge
44 | #endif // ROS_GZ_BRIDGE__CONVERT__RCL_INTERFACES_HPP_
45 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/rosgraph_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 |
24 | #include
25 |
26 | namespace ros_gz_bridge
27 | {
28 |
29 | template<>
30 | void
31 | convert_gz_to_ros(
32 | const gz::msgs::Clock & gz_msg,
33 | rosgraph_msgs::msg::Clock & ros_msg);
34 |
35 | template<>
36 | void
37 | convert_ros_to_gz(
38 | const rosgraph_msgs::msg::Clock & ros_msg,
39 | gz::msgs::Clock & gz_msg);
40 |
41 | } // namespace ros_gz_bridge
42 |
43 | #endif // ROS_GZ_BRIDGE__CONVERT__ROSGRAPH_MSGS_HPP_
44 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/tf2_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 |
24 | #include
25 |
26 | namespace ros_gz_bridge
27 | {
28 |
29 | template<>
30 | void
31 | convert_ros_to_gz(
32 | const tf2_msgs::msg::TFMessage & ros_msg,
33 | gz::msgs::Pose_V & gz_msg);
34 |
35 | template<>
36 | void
37 | convert_gz_to_ros(
38 | const gz::msgs::Pose_V & gz_msg,
39 | tf2_msgs::msg::TFMessage & ros_msg);
40 |
41 | } // namespace ros_gz_bridge
42 |
43 | #endif // ROS_GZ_BRIDGE__CONVERT__TF2_MSGS_HPP_
44 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/trajectory_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 |
21 | // ROS 2 messages
22 | #include
23 |
24 | #include
25 |
26 | namespace ros_gz_bridge
27 | {
28 |
29 | template<>
30 | void
31 | convert_ros_to_gz(
32 | const trajectory_msgs::msg::JointTrajectoryPoint & ros_msg,
33 | gz::msgs::JointTrajectoryPoint & gz_msg);
34 |
35 | template<>
36 | void
37 | convert_gz_to_ros(
38 | const gz::msgs::JointTrajectoryPoint & gz_msg,
39 | trajectory_msgs::msg::JointTrajectoryPoint & ros_msg);
40 |
41 | template<>
42 | void
43 | convert_ros_to_gz(
44 | const trajectory_msgs::msg::JointTrajectory & ros_msg,
45 | gz::msgs::JointTrajectory & gz_msg);
46 |
47 | template<>
48 | void
49 | convert_gz_to_ros(
50 | const gz::msgs::JointTrajectory & gz_msg,
51 | trajectory_msgs::msg::JointTrajectory & ros_msg);
52 |
53 |
54 | } // namespace ros_gz_bridge
55 |
56 | #endif // ROS_GZ_BRIDGE__CONVERT__TRAJECTORY_MSGS_HPP_
57 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert/vision_msgs.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2023 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT__VISION_MSGS_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT__VISION_MSGS_HPP_
17 |
18 | // Gazebo Msgs
19 | #include
20 | #include
21 |
22 | // ROS 2 messages
23 | #include "vision_msgs/msg/detection2_d_array.hpp"
24 | #include "vision_msgs/msg/detection3_d_array.hpp"
25 | #include
26 |
27 | namespace ros_gz_bridge
28 | {
29 | template<>
30 | void
31 | convert_ros_to_gz(
32 | const vision_msgs::msg::Detection2D & ros_msg,
33 | gz::msgs::AnnotatedAxisAligned2DBox & gz_msg);
34 |
35 | template<>
36 | void
37 | convert_gz_to_ros(
38 | const gz::msgs::AnnotatedAxisAligned2DBox & gz_msg,
39 | vision_msgs::msg::Detection2D & ros_msg);
40 |
41 | template<>
42 | void
43 | convert_ros_to_gz(
44 | const vision_msgs::msg::Detection2DArray & ros_msg,
45 | gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg);
46 |
47 | template<>
48 | void
49 | convert_gz_to_ros(
50 | const gz::msgs::AnnotatedAxisAligned2DBox_V & gz_msg,
51 | vision_msgs::msg::Detection2DArray & ros_msg);
52 |
53 | template<>
54 | void
55 | convert_ros_to_gz(
56 | const vision_msgs::msg::Detection3D & ros_msg,
57 | gz::msgs::AnnotatedOriented3DBox & gz_msg);
58 |
59 | template<>
60 | void
61 | convert_gz_to_ros(
62 | const gz::msgs::AnnotatedOriented3DBox & gz_msg,
63 | vision_msgs::msg::Detection3D & ros_msg);
64 |
65 | template<>
66 | void
67 | convert_ros_to_gz(
68 | const vision_msgs::msg::Detection3DArray & ros_msg,
69 | gz::msgs::AnnotatedOriented3DBox_V & gz_msg);
70 |
71 | template<>
72 | void
73 | convert_gz_to_ros(
74 | const gz::msgs::AnnotatedOriented3DBox_V & gz_msg,
75 | vision_msgs::msg::Detection3DArray & ros_msg);
76 | } // namespace ros_gz_bridge
77 |
78 | #endif // ROS_GZ_BRIDGE__CONVERT__VISION_MSGS_HPP_
79 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/convert_decl.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2018 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__CONVERT_DECL_HPP_
16 | #define ROS_GZ_BRIDGE__CONVERT_DECL_HPP_
17 |
18 | namespace ros_gz_bridge
19 | {
20 |
21 | template
22 | void
23 | convert_ros_to_gz(
24 | const ROS_T & ros_msg,
25 | GZ_T & gz_msg);
26 |
27 | template
28 | void
29 | convert_gz_to_ros(
30 | const GZ_T & gz_msg,
31 | ROS_T & ros_msg);
32 |
33 | } // namespace ros_gz_bridge
34 |
35 | #endif // ROS_GZ_BRIDGE__CONVERT_DECL_HPP_
36 |
--------------------------------------------------------------------------------
/ros_gz_bridge/include/ros_gz_bridge/ros_gz_bridge.hpp:
--------------------------------------------------------------------------------
1 | // Copyright 2022 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | #ifndef ROS_GZ_BRIDGE__ROS_GZ_BRIDGE_HPP_
16 | #define ROS_GZ_BRIDGE__ROS_GZ_BRIDGE_HPP_
17 |
18 | #include
19 | #include
20 | #include
21 |
22 | #include
23 | #include
24 | #include
25 | #include "ros_gz_bridge/bridge_config.hpp"
26 |
27 | namespace ros_gz_bridge
28 | {
29 | /// Forward declarations
30 | class BridgeHandle;
31 |
32 | /// \brief Component container for the ROS-GZ Bridge
33 | class RosGzBridge : public rclcpp::Node
34 | {
35 | public:
36 | /// \brief Constructor
37 | /// \param[in] options options control creation of the ROS 2 node
38 | explicit RosGzBridge(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
39 |
40 | /// \brief Add a new ROS-GZ bridge to the node
41 | /// \param[in] config Parameters to control creation of a new bridge
42 | void add_bridge(const BridgeConfig & config);
43 |
44 | /// \brief Create a new ROS-GZ bridge for a service
45 | /// \param[in] ros_type_name Name of the ROS service (eg ros_bz_interfaces/srv/ControlWorld)
46 | /// \param[in] gz_req_type_name Gazebo service request type
47 | /// \param[in] gz_req_type_name Gazebo service response type
48 | /// \param[in] service_name Address of the service to be bridged
49 | void add_service_bridge(
50 | const std::string & ros_type_name,
51 | const std::string & gz_req_type_name,
52 | const std::string & gz_rep_type_name,
53 | const std::string & service_name);
54 |
55 | protected:
56 | /// \brief Periodic callback to check connectivity and liveliness
57 | void spin();
58 |
59 | protected:
60 | /// \brief Pointer to Gazebo node used to create publishers/subscribers
61 | std::shared_ptr gz_node_;
62 |
63 | /// \brief List of bridge handles
64 | std::vector> handles_;
65 |
66 | /// \brief List of bridged ROS services
67 | std::vector services_;
68 |
69 | /// \brief Timer to control periodic callback
70 | rclcpp::TimerBase::SharedPtr heartbeat_timer_;
71 | };
72 | } // namespace ros_gz_bridge
73 |
74 | #endif // ROS_GZ_BRIDGE__ROS_GZ_BRIDGE_HPP_
75 |
--------------------------------------------------------------------------------
/ros_gz_bridge/launch/clock_bridge.launch:
--------------------------------------------------------------------------------
1 |
2 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
35 |
36 |
39 |
40 |
41 |
42 |
--------------------------------------------------------------------------------
/ros_gz_bridge/launch/ros_gz_bridge.launch:
--------------------------------------------------------------------------------
1 |
2 |
17 |
18 |
19 |
20 |
21 |
22 |
23 |
24 |
25 |
26 |
27 |
28 |
38 |
39 |
40 |
--------------------------------------------------------------------------------
/ros_gz_bridge/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | ros_gz_bridge
5 | 3.0.1
6 | Bridge communication between ROS and Gazebo Transport
7 | Aditya Pande
8 | Alejandro Hernandez
9 |
10 | Apache 2.0
11 |
12 | Shivesh Khaitan
13 | Louise Poubel
14 | Carlos Agüero
15 |
16 | ament_cmake
17 | ament_cmake_python
18 | pkg-config
19 | rosidl_pycommon
20 |
21 | actuator_msgs
22 | geometry_msgs
23 | gps_msgs
24 | launch
25 | launch_ros
26 | nav_msgs
27 | rclcpp
28 | rclcpp_components
29 | ros_gz_interfaces
30 | rosgraph_msgs
31 | sensor_msgs
32 | std_msgs
33 | tf2_msgs
34 | trajectory_msgs
35 | yaml_cpp_vendor
36 | vision_msgs
37 |
38 | gz_msgs_vendor
39 | gz_transport_vendor
40 |
41 | ament_cmake_gtest
42 | ament_lint_auto
43 | ament_lint_common
44 | launch_testing_ament_cmake
45 | launch_ros
46 | launch_testing
47 |
48 |
49 | ament_cmake
50 |
51 |
52 |
--------------------------------------------------------------------------------
/ros_gz_bridge/resource/get_factory.cpp.em:
--------------------------------------------------------------------------------
1 | // Copyright 2021 Open Source Robotics Foundation, Inc.
2 | //
3 | // Licensed under the Apache License, Version 2.0 (the "License");
4 | // you may not use this file except in compliance with the License.
5 | // You may obtain a copy of the License at
6 | //
7 | // http://www.apache.org/licenses/LICENSE-2.0
8 | //
9 | // Unless required by applicable law or agreed to in writing, software
10 | // distributed under the License is distributed on an "AS IS" BASIS,
11 | // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 | // See the License for the specific language governing permissions and
13 | // limitations under the License.
14 |
15 | // generated from ros_gz_bridge/resource/get_factory.cpp.em
16 |
17 | #include
18 | #include
19 |
20 | #include "get_factory.hpp"
21 |
22 | @[for ros2_package_name in sorted(ros2_package_names)]@
23 | #include "factories/@(ros2_package_name).hpp"
24 | @[end for]@
25 |
26 | #include "service_factories/ros_gz_interfaces.hpp"
27 |
28 | namespace ros_gz_bridge
29 | {
30 |
31 | std::shared_ptr
32 | get_factory_impl(
33 | const std::string & ros_type_name,
34 | const std::string & gz_type_name)
35 | {
36 | std::shared_ptr impl = nullptr;
37 | @[for ros2_package_name in sorted(ros2_package_names)]@
38 | impl = get_factory__@(ros2_package_name)(ros_type_name, gz_type_name);
39 | if (impl) {return impl;}
40 | @[end for]
41 | return nullptr;
42 | }
43 |
44 | std::shared_ptr
45 | get_factory(
46 | const std::string & ros_type_name,
47 | const std::string & gz_type_name)
48 | {
49 | std::shared_ptr factory;
50 | factory = get_factory_impl(ros_type_name, gz_type_name);
51 | if (factory) {
52 | return factory;
53 | }
54 |
55 | throw std::runtime_error("No template specialization for the pair");
56 | }
57 |
58 | std::shared_ptr
59 | get_service_factory(
60 | const std::string & ros_type_name,
61 | const std::string & gz_req_type_name,
62 | const std::string & gz_rep_type_name)
63 | {
64 | std::shared_ptr impl;
65 |
66 | impl = get_service_factory__ros_gz_interfaces(
67 | ros_type_name, gz_req_type_name, gz_rep_type_name);
68 | if (impl) {return impl;}
69 |
70 | std::ostringstream oss{"No template specialization for the specified service type {"};
71 | oss << ros_type_name << "}, gz request type {" << gz_req_type_name
72 | << "}, gz request type {" << gz_req_type_name << "}, gz reply type name {"
73 | << gz_rep_type_name << "}";
74 | throw std::runtime_error(oss.str());
75 | }
76 |
77 | } // namespace ros_gz_bridge
78 |
--------------------------------------------------------------------------------
/ros_gz_bridge/resource/get_mappings.cpp.em:
--------------------------------------------------------------------------------
1 | // generated from ros_gz_bridge/resource/get_mappings.cpp.em
2 |
3 | @###############################################
4 | @#
5 | @# Methods for determining mappings between
6 | @# Gazebo and ROS interfaces
7 | @#
8 | @# EmPy template for generating get_mappings.cpp
9 | @#
10 | @###############################################
11 | @# Start of Template
12 | @#
13 | @# Context:
14 | @# - mappings (list of ros_gz_bridge.Mapping)
15 | @# Mapping between messages as well as their fields
16 | @###############################################
17 | @
18 | #include