├── ros_gz_image
├── test
│ ├── AMENT_IGNORE
│ ├── ros_subscriber.test
│ ├── launch
│ │ └── test_ros_subscriber.launch
│ ├── publishers
│ │ └── gz_publisher.cpp
│ └── subscribers
│ │ └── ros_subscriber.cpp
├── package.xml
├── README.md
└── CMakeLists.txt
├── ros_gz_point_cloud
├── COLCON_IGNORE
├── package.xml
├── CMakeLists.txt
└── CHANGELOG.rst
├── ros_gz_sim
├── resource
│ └── ros_gz_sim
├── setup.cfg
├── launch
│ ├── gz_server.launch
│ ├── gz_spawn_model.launch
│ ├── ros_gz_sim.launch
│ ├── ros_gz_spawn_model.launch
│ └── gz_remove_model.launch.py
├── ros_gz_sim
│ ├── __init__.py
│ └── actions
│ │ └── __init__.py
├── include
│ └── ros_gz_sim
│ │ ├── gz_simulation_interfaces.hpp
│ │ ├── gzserver.hpp
│ │ └── delete_entity.hpp
├── src
│ └── gz_simulation_interfaces
│ │ ├── services
│ │ ├── delete_entity.hpp
│ │ ├── get_entity_info.hpp
│ │ ├── step_simulation.hpp
│ │ ├── reset_simulation.hpp
│ │ ├── get_entities_states.hpp
│ │ ├── get_simulation_state.hpp
│ │ ├── set_simulation_state.hpp
│ │ ├── spawn_entity.hpp
│ │ ├── get_simulator_features.hpp
│ │ ├── set_entity_state.hpp
│ │ └── get_entities.hpp
│ │ ├── actions
│ │ └── simulate_steps.hpp
│ │ └── handler_base.hpp
├── test
│ ├── test_create_node.launch.py
│ ├── test_remove_node.launch.py
│ ├── test_remove.cpp
│ └── test_create.cpp
└── package.xml
├── ros_gz_bridge
├── resource
│ ├── ros_gz_bridge
│ ├── pkg_factories.hpp.em
│ ├── pkg_factories.cpp.em
│ └── get_mappings.cpp.em
├── test
│ ├── config
│ │ ├── empty.yaml
│ │ ├── invalid_qos.yaml
│ │ ├── invalid.yaml
│ │ ├── qos.yaml
│ │ ├── test-config.yaml
│ │ ├── full.yaml
│ │ └── minimum.yaml
│ ├── launch
│ │ ├── test_launch_action_classic.launch
│ │ ├── test_launch_action.launch
│ │ └── test_gz_server.launch.py
│ ├── resource
│ │ ├── ros_pkg_subscriber.cpp.em
│ │ ├── ros_publisher.cpp.em
│ │ ├── gz_subscriber.cpp.em
│ │ └── gz_publisher.cpp.em
│ ├── subscribers
│ │ ├── ros_subscriber.cpp
│ │ └── ros_subscriber.hpp
│ └── serverclient
│ │ ├── ros_client.cpp
│ │ └── gz_server.cpp
├── setup.cfg
├── images
│ └── bridge_image_exchange.png
├── ros_gz_bridge
│ └── actions
│ │ └── __init__.py
├── src
│ ├── factory_interface.cpp
│ ├── service_factory_interface.cpp
│ ├── convert
│ │ ├── utils.hpp
│ │ ├── builtin_interfaces.cpp
│ │ ├── rosgraph_msgs.cpp
│ │ ├── utils.cpp
│ │ ├── tf2_msgs.cpp
│ │ ├── actuator_msgs.cpp
│ │ └── gps_msgs.cpp
│ ├── get_mappings.hpp
│ ├── service_factories
│ │ └── ros_gz_interfaces.hpp
│ ├── get_factory.hpp
│ ├── service_factory_interface.hpp
│ ├── static_bridge.cpp
│ ├── factory_interface.hpp
│ ├── bridge_handle_ros_to_gz.hpp
│ ├── bridge_handle_gz_to_ros.hpp
│ └── bridge_handle.cpp
├── include
│ └── ros_gz_bridge
│ │ ├── convert_decl.hpp
│ │ ├── convert.hpp
│ │ └── convert
│ │ ├── gps_msgs.hpp
│ │ ├── tf2_msgs.hpp
│ │ ├── builtin_interfaces.hpp
│ │ ├── rosgraph_msgs.hpp
│ │ ├── actuator_msgs.hpp
│ │ ├── rcl_interfaces.hpp
│ │ ├── nav_msgs.hpp
│ │ └── trajectory_msgs.hpp
├── launch
│ ├── ros_gz_bridge.launch
│ └── clock_bridge.launch
├── bin
│ ├── ros_gz_bridge_markdown_table
│ ├── ros_gz_bridge_generate_factories
│ └── ros_gz_bridge_generate_tests
└── package.xml
├── .gitignore
├── tools
├── .codespell_ignore_words
└── pyproject.toml
├── ros_gz_interfaces
├── msg
│ ├── Float32Array.msg
│ ├── LogicalCameraImageModel.msg
│ ├── Contacts.msg
│ ├── WorldReset.msg
│ ├── StringVec.msg
│ ├── EntityWrench.msg
│ ├── LogicalCameraImage.msg
│ ├── ParamVec.msg
│ ├── GuiCamera.msg
│ ├── Altimeter.msg
│ ├── VideoRecord.msg
│ ├── JointWrench.msg
│ ├── Entity.msg
│ ├── Contact.msg
│ ├── WorldControl.msg
│ ├── Dataframe.msg
│ ├── MaterialColor.msg
│ ├── EntityFactory.msg
│ ├── TrackVisual.msg
│ ├── SensorNoise.msg
│ └── Light.msg
├── srv
│ ├── DeleteEntity.srv
│ ├── SpawnEntity.srv
│ ├── ControlWorld.srv
│ └── SetEntityPose.srv
├── package.xml
├── CMakeLists.txt
└── README.md
├── img
└── video_img.png
├── ros_gz_sim_demos
├── hooks
│ └── ros_gz_sim_demos.dsv.in
├── images
│ ├── imu_demo.png
│ ├── tf_bridge.gif
│ ├── battery_demo.png
│ ├── camera_demo.png
│ ├── joint_states.png
│ ├── navsat_demo.png
│ ├── shapes_demo.png
│ ├── diff_drive_demo.png
│ ├── gpu_lidar_demo.png
│ ├── air_pressure_demo.png
│ ├── depth_camera_demo.png
│ ├── magnetometer_demo.png
│ ├── rgbd_camera_demo.png
│ └── robot_state_publisher_demo.png
├── resources
│ ├── spawn.gif
│ ├── set_entity.gif
│ └── delete_entity.gif
├── models
│ ├── cardboard_box
│ │ ├── thumbnails
│ │ │ ├── 1.png
│ │ │ ├── 2.png
│ │ │ ├── 3.png
│ │ │ ├── 4.png
│ │ │ └── 5.png
│ │ ├── materials
│ │ │ └── textures
│ │ │ │ └── cardboard_box.png
│ │ ├── model.config
│ │ └── model.sdf
│ └── vehicle
│ │ └── model.config
├── config
│ ├── imu.yaml
│ ├── navsat.yaml
│ ├── navsat_gpsfix.yaml
│ ├── magnetometer.yaml
│ ├── air_pressure.yaml
│ ├── camera.yaml
│ ├── gpu_lidar.yaml
│ ├── battery.yaml
│ ├── tf_bridge.yaml
│ ├── triggered_camera.yaml
│ ├── diff_drive.yaml
│ └── rgbd_camera_bridge.yaml
├── launch
│ ├── magnetometer.launch.xml
│ ├── navsat.launch.xml
│ ├── navsat_gpsfix.launch.xml
│ ├── imu.launch.xml
│ ├── tf_bridge.launch.xml
│ ├── camera.launch.xml
│ ├── rgbd_camera_bridge.launch.xml
│ ├── air_pressure.launch.xml
│ ├── gpu_lidar_bridge.launch.xml
│ ├── triggered_camera.launch.xml
│ ├── diff_drive.launch.xml
│ ├── rgbd_camera.launch.py
│ ├── gpu_lidar.launch.py
│ ├── image_bridge.launch.py
│ └── battery.launch.py
├── CMakeLists.txt
└── package.xml
├── ros_gz
├── README.md
├── CMakeLists.txt
└── package.xml
├── .github
├── CODEOWNERS
└── workflows
│ ├── triage.yml
│ ├── ros2-ci.yml
│ └── build-and-test.sh
├── .pre-commit-config.yaml
├── CONTRIBUTING.md
├── README_RENAME.md
└── test_ros_gz_bridge
├── CMakeLists.txt
├── package.xml
├── src
└── test_ros_gz_bridge.cpp
└── CHANGELOG.rst
/ros_gz_image/test/AMENT_IGNORE:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/ros_gz_point_cloud/COLCON_IGNORE:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/ros_gz_sim/resource/ros_gz_sim:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/ros_gz_bridge/resource/ros_gz_bridge:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/empty.yaml:
--------------------------------------------------------------------------------
1 |
--------------------------------------------------------------------------------
/.gitignore:
--------------------------------------------------------------------------------
1 | **/__pycache__
2 | .vscode
3 |
--------------------------------------------------------------------------------
/tools/.codespell_ignore_words:
--------------------------------------------------------------------------------
1 | Lew
2 | EmPy
3 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Float32Array.msg:
--------------------------------------------------------------------------------
1 | float32[] data
2 |
--------------------------------------------------------------------------------
/img/video_img.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/img/video_img.png
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/LogicalCameraImageModel.msg:
--------------------------------------------------------------------------------
1 | string name
2 | geometry_msgs/Pose pose
3 |
--------------------------------------------------------------------------------
/tools/pyproject.toml:
--------------------------------------------------------------------------------
1 | [tool.codespell]
2 | ignore-words = "tools/.codespell_ignore_words"
3 |
--------------------------------------------------------------------------------
/ros_gz_sim/setup.cfg:
--------------------------------------------------------------------------------
1 | [options.entry_points]
2 | launch.frontend.launch_extension =
3 | ros_gz_sim = ros_gz_sim
4 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/hooks/ros_gz_sim_demos.dsv.in:
--------------------------------------------------------------------------------
1 | prepend-non-duplicate;GZ_SIM_RESOURCE_PATH;@CMAKE_INSTALL_PREFIX@/share
2 |
--------------------------------------------------------------------------------
/ros_gz_bridge/setup.cfg:
--------------------------------------------------------------------------------
1 | [options.entry_points]
2 | launch.frontend.launch_extension =
3 | ros_gz_bridge = ros_gz_bridge
4 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/imu_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/imu_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/tf_bridge.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/tf_bridge.gif
--------------------------------------------------------------------------------
/ros_gz_sim_demos/resources/spawn.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/resources/spawn.gif
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/battery_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/battery_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/camera_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/camera_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/joint_states.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/joint_states.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/navsat_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/navsat_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/shapes_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/shapes_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/diff_drive_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/diff_drive_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/gpu_lidar_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/gpu_lidar_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/resources/set_entity.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/resources/set_entity.gif
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/air_pressure_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/air_pressure_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/depth_camera_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/depth_camera_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/magnetometer_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/magnetometer_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/rgbd_camera_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/rgbd_camera_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/resources/delete_entity.gif:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/resources/delete_entity.gif
--------------------------------------------------------------------------------
/ros_gz_bridge/images/bridge_image_exchange.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_bridge/images/bridge_image_exchange.png
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Contacts.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header # Time stamp
2 | ros_gz_interfaces/Contact[] contacts # List of contacts
3 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/images/robot_state_publisher_demo.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/images/robot_state_publisher_demo.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/thumbnails/1.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/thumbnails/1.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/thumbnails/2.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/thumbnails/2.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/thumbnails/3.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/thumbnails/3.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/thumbnails/4.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/thumbnails/4.png
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/thumbnails/5.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/thumbnails/5.png
--------------------------------------------------------------------------------
/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_interfaces/msg/WorldReset.msg:
--------------------------------------------------------------------------------
1 | bool all false # Reset time and model
2 | bool time_only false # Reset time only
3 | bool model_only false # Reset model only
4 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/StringVec.msg:
--------------------------------------------------------------------------------
1 | # A message for a vector of string data.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | # The vector of strings.
7 | string[] data
8 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/srv/DeleteEntity.srv:
--------------------------------------------------------------------------------
1 | ros_gz_interfaces/Entity entity # Gazebo Sim entity to be deleted.
2 | ---
3 | bool success # Return true if deletion is successful.
4 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/imu.yaml:
--------------------------------------------------------------------------------
1 | # IMU configuration.
2 | - topic_name: "/imu"
3 | ros_type_name: "sensor_msgs/msg/Imu"
4 | gz_type_name: "gz.msgs.IMU"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/materials/textures/cardboard_box.png:
--------------------------------------------------------------------------------
https://raw.githubusercontent.com/gazebosim/ros_gz/HEAD/ros_gz_sim_demos/models/cardboard_box/materials/textures/cardboard_box.png
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/EntityWrench.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header # Time stamp
2 | ros_gz_interfaces/Entity entity # Entity
3 | geometry_msgs/Wrench wrench # Wrench to be applied to entity
4 |
--------------------------------------------------------------------------------
/.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 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/LogicalCameraImage.msg:
--------------------------------------------------------------------------------
1 | # Optional header data.
2 | std_msgs/Header header
3 |
4 | # Logical camera pose
5 | geometry_msgs/Pose pose
6 |
7 | # Detected models
8 | LogicalCameraImageModel[] model
9 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/ParamVec.msg:
--------------------------------------------------------------------------------
1 | # A message for a vector of parameters data.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | # A set of name, value pairs
7 | rcl_interfaces/Parameter[] params
8 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/srv/SpawnEntity.srv:
--------------------------------------------------------------------------------
1 | ros_gz_interfaces/EntityFactory entity_factory # Message to create a new entity
2 | ---
3 | bool success # Return true if spawned successfully.
4 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/navsat.yaml:
--------------------------------------------------------------------------------
1 | # Navsat configuration.
2 | - topic_name: "/navsat"
3 | ros_type_name: "sensor_msgs/msg/NavSatFix"
4 | gz_type_name: "gz.msgs.NavSat"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/srv/ControlWorld.srv:
--------------------------------------------------------------------------------
1 | ros_gz_interfaces/WorldControl world_control # Message to Control world in Gazebo Sim
2 | ---
3 | bool success # Return true if control is successful.
4 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/navsat_gpsfix.yaml:
--------------------------------------------------------------------------------
1 | # Navsat_gpsfix configuration.
2 | - topic_name: "/navsat"
3 | ros_type_name: "gps_msgs/msg/GPSFix"
4 | gz_type_name: "gz.msgs.NavSat"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/srv/SetEntityPose.srv:
--------------------------------------------------------------------------------
1 | ros_gz_interfaces/Entity entity # Gazebo Sim entity.
2 | geometry_msgs/Pose pose # Pose of entity.
3 | ---
4 | bool success # Return true if set successfully.
5 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/magnetometer.yaml:
--------------------------------------------------------------------------------
1 | # Magnetometer configuration.
2 | - topic_name: "/magnetometer"
3 | ros_type_name: "sensor_msgs/msg/MagneticField"
4 | gz_type_name: "gz.msgs.Magnetometer"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/air_pressure.yaml:
--------------------------------------------------------------------------------
1 | # Air pressure bridge configuration.
2 | - topic_name: "air_pressure"
3 | ros_type_name: "sensor_msgs/msg/FluidPressure"
4 | gz_type_name: "gz.msgs.FluidPressure"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/invalid_qos.yaml:
--------------------------------------------------------------------------------
1 | - ros_topic_name: "ros_chatter"
2 | gz_topic_name: "gz_chatter"
3 | ros_type_name: "std_msgs/msg/String"
4 | gz_type_name: "ignition.msgs.StringMsg"
5 | lazy: true
6 | direction: ROS_TO_GZ
7 | qos_profile: UNKNOWN
8 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/invalid.yaml:
--------------------------------------------------------------------------------
1 | ros_topic_name: "ros_chatter"
2 | gz_topic_name: "gz_chatter"
3 | ros_type_name: "std_msgs/msg/String"
4 | gz_type_name: "ignition.msgs.StringMsg"
5 | subscriber_queue: 5
6 | publisher_queue: 6
7 | lazy: true
8 | direction: ROS_TO_GZ
9 |
--------------------------------------------------------------------------------
/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_image/test/ros_subscriber.test:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/GuiCamera.msg:
--------------------------------------------------------------------------------
1 | # Message for a GUI Camera.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | string name
7 | string view_controller
8 | geometry_msgs/Pose pose
9 | TrackVisual track
10 |
11 | # Type of projection: "perspective" or "orthographic".
12 | string projection_type
13 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Altimeter.msg:
--------------------------------------------------------------------------------
1 | # A message for Altimeter readings.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | # Vertical position data, in meters.
7 | float64 vertical_position
8 |
9 | # Vertical velocity data, in meters/second.
10 | float64 vertical_velocity
11 |
12 | # Vertical reference.
13 | float64 vertical_reference
14 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/camera.yaml:
--------------------------------------------------------------------------------
1 | # Camera bridge configuration.
2 | - topic_name: "/camera"
3 | ros_type_name: "sensor_msgs/msg/Image"
4 | gz_type_name: "gz.msgs.Image"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
8 | - topic_name: "/camera_info"
9 | ros_type_name: "sensor_msgs/msg/CameraInfo"
10 | gz_type_name: "gz.msgs.CameraInfo"
11 | lazy: true
12 | direction: GZ_TO_ROS
13 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/gpu_lidar.yaml:
--------------------------------------------------------------------------------
1 | # GPU lidar configuration.
2 | - topic_name: "/lidar"
3 | ros_type_name: "sensor_msgs/msg/LaserScan"
4 | gz_type_name: "gz.msgs.LaserScan"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
8 | - topic_name: "/lidar/points"
9 | ros_type_name: "sensor_msgs/msg/PointCloud2"
10 | gz_type_name: "gz.msgs.PointCloudPacked"
11 | lazy: true
12 | direction: GZ_TO_ROS
13 |
--------------------------------------------------------------------------------
/ros_gz_image/test/launch/test_ros_subscriber.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
8 |
9 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/VideoRecord.msg:
--------------------------------------------------------------------------------
1 | # A message that allows for control of video recording functions.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | # True to start video recording.
7 | bool start
8 |
9 | # True to stop video recording.
10 | bool stop
11 |
12 | # Video encoding format, e.g. "mp4", "ogv".
13 | string format
14 |
15 | # filename of the recorded video.
16 | string save_filename
17 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/JointWrench.msg:
--------------------------------------------------------------------------------
1 | std_msgs/Header header # Time stamp
2 | std_msgs/String body_1_name # Body 1 name string
3 | std_msgs/UInt32 body_1_id # Body 1 id
4 | std_msgs/String body_2_name # Body 2 name string
5 | std_msgs/UInt32 body_2_id # Body 2 id
6 |
7 | geometry_msgs/Wrench body_1_wrench # Body 1 wrench
8 | geometry_msgs/Wrench body_2_wrench # Body 2 wrench
9 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Entity.msg:
--------------------------------------------------------------------------------
1 | # Entity type: constant definition
2 | uint8 NONE = 0
3 | uint8 LIGHT = 1
4 | uint8 MODEL = 2
5 | uint8 LINK = 3
6 | uint8 VISUAL = 4
7 | uint8 COLLISION = 5
8 | uint8 SENSOR = 6
9 | uint8 JOINT = 7
10 |
11 | uint64 id # Entity unique identifier across all types. Defaults to 0
12 | string name # Entity name, which is not guaranteed to be unique.
13 | uint8 type # Entity type.
14 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/battery.yaml:
--------------------------------------------------------------------------------
1 | # Battery configuration.
2 | - topic_name: "/model/vehicle_blue/cmd_vel"
3 | ros_type_name: "geometry_msgs/msg/Twist"
4 | gz_type_name: "gz.msgs.Twist"
5 | lazy: true
6 | direction: ROS_TO_GZ
7 |
8 | - topic_name: "/model/vehicle_blue/battery/linear_battery/state"
9 | ros_type_name: "sensor_msgs/msg/BatteryState"
10 | gz_type_name: "gz.msgs.BatteryState"
11 | lazy: true
12 | direction: GZ_TO_ROS
13 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/magnetometer.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/navsat.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Contact.msg:
--------------------------------------------------------------------------------
1 | ros_gz_interfaces/Entity collision1 # Contact collision1
2 | ros_gz_interfaces/Entity collision2 # Contact collision2
3 | geometry_msgs/Vector3[] positions # List of contact position
4 | geometry_msgs/Vector3[] normals # List of contact normals
5 | float64[] depths # List of penetration depths
6 | ros_gz_interfaces/JointWrench[] wrenches # List of joint wrenches including forces/torques
7 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/WorldControl.msg:
--------------------------------------------------------------------------------
1 | bool pause # Paused state.
2 | bool step #
3 | uint32 multi_step 0 # Paused after stepping multi_step.
4 | ros_gz_interfaces/WorldReset reset #
5 | uint32 seed #
6 | builtin_interfaces/Time run_to_sim_time # A simulation time in the future to run to and
7 | # then pause.
8 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/Dataframe.msg:
--------------------------------------------------------------------------------
1 | # Message containing some payload as well as sender and destination
2 | # Intended for use with the comms system in Gazebo
3 | std_msgs/Header header # Time stamp
4 | string src_address # Address of the sender
5 | string dst_address # Address of the destination
6 | uint8[] data # Payload
7 | float64 rssi # Received Signal Strength Indicator
8 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/navsat_gpsfix.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/cardboard_box/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | Cardboard box
5 | 1.0
6 | model.sdf
7 |
8 |
9 | Nate Koenig
10 | nate@osrfoundation.org
11 |
12 |
13 |
14 | Cole Biesemeyer
15 |
16 |
17 |
18 | A closed cardboard box.
19 |
20 |
21 |
--------------------------------------------------------------------------------
/.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 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/models/vehicle/model.config:
--------------------------------------------------------------------------------
1 |
2 |
3 | vehicle
4 | 1.0
5 | model.sdf
6 |
7 |
8 | Dharini Dutia
9 | dharini@openrobotics.org
10 |
11 |
12 |
13 | Parser plugin `sdformat_urdf` compatible differential drive vehicle model. Used to read
14 | models described in SDFormat and outputs URDF C++ DOM structures.
15 |
16 |
17 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/tf_bridge.yaml:
--------------------------------------------------------------------------------
1 | # tf_bridge configuration.
2 | - ros_topic_name: "/joint_states"
3 | gz_topic_name: "/world/default/model/double_pendulum_with_base0/joint_state"
4 | ros_type_name: "sensor_msgs/msg/JointState"
5 | gz_type_name: "gz.msgs.Model"
6 | lazy: true
7 | direction: GZ_TO_ROS
8 |
9 | - ros_topic_name: "/tf"
10 | gz_topic_name: "/model/double_pendulum_with_base0/pose"
11 | ros_type_name: "tf2_msgs/msg/TFMessage"
12 | gz_type_name: "gz.msgs.Pose_V"
13 | lazy: true
14 | direction: GZ_TO_ROS
15 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/imu.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/tf_bridge.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/qos.yaml:
--------------------------------------------------------------------------------
1 | # Full set of configurations
2 | - ros_topic_name: "ros_chatter"
3 | gz_topic_name: "gz_chatter"
4 | ros_type_name: "std_msgs/msg/String"
5 | gz_type_name: "ignition.msgs.StringMsg"
6 | lazy: true
7 | qos_profile: SENSOR_DATA
8 | direction: ROS_TO_GZ
9 |
10 | - ros_topic_name: "ros_chatter"
11 | gz_topic_name: "gz_chatter"
12 | ros_type_name: "std_msgs/msg/String"
13 | gz_type_name: "ignition.msgs.StringMsg"
14 | publisher_queue: 20
15 | lazy: false
16 | qos_profile: CLOCK
17 | direction: GZ_TO_ROS
18 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/triggered_camera.yaml:
--------------------------------------------------------------------------------
1 | # triggered_cammera configuration.
2 | - topic_name: "/camera"
3 | ros_type_name: "sensor_msgs/msg/Image"
4 | gz_type_name: "gz.msgs.Image"
5 | lazy: true
6 | direction: GZ_TO_ROS
7 |
8 | - topic_name: "/camera_info"
9 | ros_type_name: "sensor_msgs/msg/CameraInfo"
10 | gz_type_name: "gz.msgs.CameraInfo"
11 | lazy: true
12 | direction: GZ_TO_ROS
13 |
14 | - topic_name: "/camera/trigger"
15 | ros_type_name: "std_msgs/msg/Bool"
16 | gz_type_name: "gz.msgs.Boolean"
17 | lazy: true
18 | direction: ROS_TO_GZ
19 |
--------------------------------------------------------------------------------
/ros_gz_sim/launch/gz_server.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
13 |
14 |
15 |
--------------------------------------------------------------------------------
/.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 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/MaterialColor.msg:
--------------------------------------------------------------------------------
1 | # Entities that match to apply material color: constant definition
2 | uint8 FIRST = 0
3 | uint8 ALL = 1
4 |
5 | std_msgs/Header header # Optional header data
6 | ros_gz_interfaces/Entity entity # Entity to change material color
7 | std_msgs/ColorRGBA ambient # Ambient color
8 | std_msgs/ColorRGBA diffuse # Diffuse color
9 | std_msgs/ColorRGBA specular # Specular color
10 | std_msgs/ColorRGBA emissive # Emissive color
11 | float64 shininess # Specular exponent
12 | uint8 entity_match # Entities that match to apply material color
13 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/camera.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/rgbd_camera_bridge.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/air_pressure.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/gpu_lidar_bridge.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
--------------------------------------------------------------------------------
/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 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/triggered_camera.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
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 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/test-config.yaml:
--------------------------------------------------------------------------------
1 | # Set just ROS topic name, applies to both
2 | - ros_topic_name: "imu_sensor_msgs_imu"
3 | gz_topic_name: "imu_sensor_msgs_imu"
4 | ros_type_name: "sensor_msgs/msg/Imu"
5 | gz_type_name: "gz.msgs.IMU"
6 |
7 | # Set just ROS topic name, applies to both
8 | - ros_topic_name: "boolean_std_msgs_bool"
9 | gz_topic_name: "boolean_std_msgs_bool"
10 | ros_type_name: "std_msgs/msg/Bool"
11 | gz_type_name: "gz.msgs.Boolean"
12 |
13 | # Set just ROS topic name, applies to both
14 | - service_name: "/gz_ros/test/serviceclient/world_control"
15 | ros_type_name: "ros_gz_interfaces/srv/ControlWorld"
16 | gz_req_type_name: "gz.msgs.WorldControl"
17 | gz_rep_type_name: "gz.msgs.Boolean"
18 |
--------------------------------------------------------------------------------
/ros_gz_point_cloud/package.xml:
--------------------------------------------------------------------------------
1 |
2 | ros_gz_point_cloud
3 | 0.7.0
4 | Point cloud utilities for Gazebo simulation with ROS.
5 | Apache 2.0
6 | Aditya Pande
7 | Alejandro Hernandez
8 |
9 | Louise Poubel
10 |
11 | catkin
12 |
13 | ignition-gazebo2
14 | ignition-rendering2
15 | ignition-sensors2
16 | roscpp
17 | sensor_msgs
18 |
19 | message_runtime
20 |
21 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/full.yaml:
--------------------------------------------------------------------------------
1 | # Full set of configurations
2 | - ros_topic_name: "ros_chatter"
3 | gz_topic_name: "gz_chatter"
4 | ros_type_name: "std_msgs/msg/String"
5 | gz_type_name: "ignition.msgs.StringMsg"
6 | subscriber_queue: 5
7 | publisher_queue: 6
8 | lazy: true
9 | direction: ROS_TO_GZ
10 |
11 | - ros_topic_name: "ros_chatter"
12 | gz_topic_name: "gz_chatter"
13 | ros_type_name: "std_msgs/msg/String"
14 | gz_type_name: "ignition.msgs.StringMsg"
15 | subscriber_queue: 10
16 | publisher_queue: 20
17 | lazy: false
18 | direction: GZ_TO_ROS
19 |
20 | - service_name: "/gz_ros/test/serviceclient/world_control"
21 | ros_type_name: "ros_gz_interfaces/srv/ControlWorld"
22 | gz_req_type_name: "gz.msgs.WorldControl"
23 | gz_rep_type_name: "gz.msgs.Boolean"
24 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/EntityFactory.msg:
--------------------------------------------------------------------------------
1 | string name # New name for the entity, overrides the name on the SDF
2 | bool allow_renaming false # Whether the server is allowed to rename the entity in case of
3 | # overlap with existing entities.
4 |
5 | # Only one method is supported at a time (sdf,sdf_filename,clone_name)
6 | string sdf # SDF description in string format
7 | string sdf_filename # Full path to SDF file.
8 | string clone_name # Name of entity to clone
9 |
10 | geometry_msgs/Pose pose # Pose where the entity will be spawned in the world.
11 | string relative_to "world" # Pose is defined relative to the frame of this entity.
12 |
--------------------------------------------------------------------------------
/ros_gz_sim/ros_gz_sim/__init__.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 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 | """Main entry point for the `ros_gz_sim` package."""
16 |
17 | from . import actions
18 |
19 |
20 | __all__ = [
21 | 'actions',
22 | ]
23 |
--------------------------------------------------------------------------------
/ros_gz_bridge/ros_gz_bridge/actions/__init__.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 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 | """Actions module."""
16 |
17 | from .ros_gz_bridge import RosGzBridge
18 |
19 |
20 | __all__ = [
21 | 'RosGzBridge',
22 | ]
23 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/launch/test_launch_action_classic.launch:
--------------------------------------------------------------------------------
1 |
2 |
17 |
18 |
19 |
20 |
21 |
--------------------------------------------------------------------------------
/ros_gz_bridge/src/factory_interface.cpp:
--------------------------------------------------------------------------------
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 | #include "factory_interface.hpp"
16 |
17 | namespace ros_gz_bridge
18 | {
19 |
20 | FactoryInterface::~FactoryInterface()
21 | {
22 | }
23 |
24 | } // namespace ros_gz_bridge
25 |
--------------------------------------------------------------------------------
/ros_gz_sim/ros_gz_sim/actions/__init__.py:
--------------------------------------------------------------------------------
1 | # Copyright 2024 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 | """Actions module."""
16 |
17 | from .gz_spawn_model import GzSpawnModel
18 | from .gzserver import GzServer
19 |
20 |
21 | __all__ = [
22 | 'GzSpawnModel',
23 | 'GzServer',
24 | ]
25 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/TrackVisual.msg:
--------------------------------------------------------------------------------
1 | # Message for a tracking a rendering::Visual with a rendering::Camera.
2 |
3 | # Optional header data.
4 | std_msgs/Header header
5 |
6 | # Name of the visual to track.
7 | string name
8 |
9 | # Id of the visual to track.
10 | uint32 id
11 |
12 | # True to have the tracking camera inherit the orientation of
13 | # the tracked visual.
14 | bool inherit_orientation
15 |
16 | # Minimum follow distance.
17 | float64 min_dist
18 |
19 | # Maximum follow distance.
20 | float64 max_dist
21 |
22 | # If set to true, the position of the camera is fixed.
23 | bool is_static
24 |
25 | # If set to true, the position of the camera is relative to the.
26 | # model reference frame.
27 | bool use_model_frame
28 |
29 | # Position of the camera.
30 | geometry_msgs/Vector3 xyz
31 |
32 | # If set to true, the camera inherits the yaw rotation of the model.
33 | bool inherit_yaw
34 |
--------------------------------------------------------------------------------
/test_ros_gz_bridge/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 |
3 | project(test_ros_gz_bridge)
4 |
5 | # Default to C++14
6 | if(NOT CMAKE_CXX_STANDARD)
7 | set(CMAKE_CXX_STANDARD 17)
8 | endif()
9 | if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10 | set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -Wall -Wextra -Wpedantic")
11 | endif()
12 |
13 | find_package(ament_cmake REQUIRED)
14 | find_package(ros_gz_bridge REQUIRED)
15 |
16 |
17 | if(BUILD_TESTING)
18 | find_package(ament_lint_auto REQUIRED)
19 | ament_lint_auto_find_test_dependencies()
20 |
21 | find_package(ament_cmake_gtest REQUIRED)
22 | find_package(launch_testing_ament_cmake REQUIRED)
23 | ament_find_gtest()
24 |
25 | ament_add_gtest(test_ros_gz_bridge src/test_ros_gz_bridge.cpp)
26 | target_link_libraries(test_ros_gz_bridge ros_gz_bridge::ros_gz_bridge)
27 | endif()
28 |
29 | ament_package()
30 |
--------------------------------------------------------------------------------
/ros_gz_bridge/src/service_factory_interface.cpp:
--------------------------------------------------------------------------------
1 | // Copyright 2024 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 | #include "service_factory_interface.hpp"
16 |
17 | namespace ros_gz_bridge
18 | {
19 |
20 | ServiceFactoryInterface::~ServiceFactoryInterface()
21 | {
22 | }
23 |
24 | } // namespace ros_gz_bridge
25 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/CMakeLists.txt:
--------------------------------------------------------------------------------
1 | cmake_minimum_required(VERSION 3.5)
2 |
3 | project(ros_gz_sim_demos)
4 |
5 | find_package(ament_cmake REQUIRED)
6 |
7 | if(BUILD_TESTING)
8 | find_package(ament_lint_auto REQUIRED)
9 | ament_lint_auto_find_test_dependencies()
10 | endif()
11 |
12 | install(
13 | DIRECTORY
14 | config/
15 | DESTINATION share/${PROJECT_NAME}/config
16 | )
17 |
18 | install(
19 | DIRECTORY
20 | launch/
21 | DESTINATION share/${PROJECT_NAME}/launch
22 | )
23 |
24 | install(
25 | DIRECTORY
26 | rviz/
27 | DESTINATION share/${PROJECT_NAME}/rviz
28 | )
29 |
30 | install(
31 | DIRECTORY
32 | models/
33 | DESTINATION share/${PROJECT_NAME}/models
34 | )
35 |
36 | install(
37 | DIRECTORY
38 | worlds/
39 | DESTINATION share/${PROJECT_NAME}/worlds
40 | )
41 |
42 | ament_environment_hooks("${CMAKE_CURRENT_SOURCE_DIR}/hooks/${PROJECT_NAME}.dsv.in")
43 |
44 | ament_package()
45 |
--------------------------------------------------------------------------------
/ros_gz_sim/launch/gz_spawn_model.launch:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 |
5 |
6 |
7 |
8 |
9 |
10 |
11 |
12 |
13 |
14 |
27 |
28 |
29 |
--------------------------------------------------------------------------------
/ros_gz_bridge/test/config/minimum.yaml:
--------------------------------------------------------------------------------
1 | # Set just topic name, applies to both
2 | - topic_name: "chatter"
3 | ros_type_name: "std_msgs/msg/String"
4 | gz_type_name: "ignition.msgs.StringMsg"
5 |
6 | # Set just ROS topic name, applies to both
7 | - ros_topic_name: "chatter_ros"
8 | ros_type_name: "std_msgs/msg/String"
9 | gz_type_name: "ignition.msgs.StringMsg"
10 |
11 | # Set just GZ topic name, applies to both
12 | - gz_topic_name: "chatter_gz"
13 | ros_type_name: "std_msgs/msg/String"
14 | gz_type_name: "ignition.msgs.StringMsg"
15 |
16 | # Set each topic name explicitly
17 | - ros_topic_name: "chatter_both_ros"
18 | gz_topic_name: "chatter_both_gz"
19 | ros_type_name: "std_msgs/msg/String"
20 | gz_type_name: "ignition.msgs.StringMsg"
21 |
22 | - service_name: "/gz_ros/test/serviceclient/world_control"
23 | ros_type_name: "ros_gz_interfaces/srv/ControlWorld"
24 | gz_req_type_name: "gz.msgs.WorldControl"
25 | gz_rep_type_name: "gz.msgs.Boolean"
26 |
--------------------------------------------------------------------------------
/ros_gz_image/package.xml:
--------------------------------------------------------------------------------
1 |
2 | ros_gz_image
3 | 3.0.5
4 | Image utilities for Gazebo simulation with ROS.
5 | Apache 2.0
6 | Aditya Pande
7 | Alejandro Hernandez
8 |
9 | Louise Poubel
10 |
11 | ament_cmake
12 | pkg-config
13 |
14 | image_transport
15 | ros_gz_bridge
16 | rclcpp
17 | sensor_msgs
18 |
19 | gz_msgs_vendor
20 | gz_transport_vendor
21 |
22 | ament_lint_auto
23 | ament_lint_common
24 |
25 | ament_cmake
26 |
27 |
28 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/launch/diff_drive.launch.xml:
--------------------------------------------------------------------------------
1 |
2 |
6 |
10 |
11 |
12 |
13 |
14 |
15 |
16 |
17 |
18 |
--------------------------------------------------------------------------------
/.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 | ros-distro: "rolling"
28 | container:
29 | image: ${{ matrix.docker-image }}
30 | steps:
31 | - name: Checkout
32 | uses: actions/checkout@v4
33 | - name: Build and Test
34 | run: .github/workflows/build-and-test.sh
35 | env:
36 | DOCKER_IMAGE: ${{ matrix.docker-image }}
37 | ROS_DISTRO: ${{ matrix.ros-distro }}
38 |
--------------------------------------------------------------------------------
/ros_gz_image/README.md:
--------------------------------------------------------------------------------
1 | # Image utilities for using ROS and Gazebo Transport
2 |
3 | This package provides a unidirectional bridge for images from Gazebo to ROS.
4 | The bridge subscribes to Gazebo image messages (`gz::msgs::Image`)
5 | and republishes them to ROS using [image_transport](http://wiki.ros.org/image_transport).
6 |
7 | For compressed images, install
8 | [compressed_image_transport](http://wiki.ros.org/compressed_image_transport)
9 | and the bridge will publish `/compressed` images. The same goes for other
10 | `image_transport` plugins.
11 |
12 | To run the bridge from the command line:
13 |
14 | ```shell
15 | ros2 run ros_gz_image image_bridge /topic1 /topic2
16 | ```
17 |
18 | You can also modify the [Quality of Service (QoS) policy](https://docs.ros.org/en/rolling/Concepts/About-Quality-of-Service-Settings.html#qos-policies) used to publish images using an additional `qos` ROS parameter. For example:
19 |
20 | ```shell
21 | ros2 run ros_gz_image image_bridge /topic1 /topic2 --ros-args qos:=sensor_data
22 | ```
23 |
--------------------------------------------------------------------------------
/ros_gz_bridge/resource/pkg_factories.hpp.em:
--------------------------------------------------------------------------------
1 | // generated from ros_gz_bridge/resource/pkg_factories.hpp.em
2 |
3 | @###############################################
4 | @#
5 | @# Factory template specializations based on
6 | @# message types of a single ROS 2 package
7 | @#
8 | @# EmPy template for generating factories/.hpp
9 | @#
10 | @###############################################
11 | @# Start of Template
12 | @#
13 | @# Context:
14 | @# - ros2_package_name (str)
15 | @# The ROS 2 package name of this file
16 | @###############################################
17 | @
18 |
19 | #ifndef FACTORIES_@(ros2_package_name.upper())
20 | #define FACTORIES_@(ros2_package_name.upper())
21 |
22 | #include
23 | #include
24 |
25 | #include "factory_interface.hpp"
26 |
27 | namespace ros_gz_bridge
28 | {
29 |
30 | std::shared_ptr
31 | get_factory__@(ros2_package_name)(
32 | const std::string & ros_type_name,
33 | const std::string & gz_type_name);
34 |
35 | } // namespace ros_gz_bridge
36 |
37 | #endif // FACTORIES_@(ros2_package_name.upper())
38 |
--------------------------------------------------------------------------------
/test_ros_gz_bridge/package.xml:
--------------------------------------------------------------------------------
1 |
2 |
3 |
4 | test_ros_gz_bridge
5 | 3.0.5
6 | Bridge communication between ROS and Gazebo Transport
7 | Aditya Pande
8 | Alejandro Hernandez
9 |
10 | Apache 2.0
11 |
12 | Michael Carroll
13 |
14 | ament_cmake
15 |
16 | ros_gz_bridge
17 |
18 | ament_cmake_gtest
19 | ament_lint_auto
20 | ament_lint_common
21 | launch_testing_ament_cmake
22 | launch_ros
23 | launch_testing
24 |
25 |
26 | ament_cmake
27 |
28 |
29 |
--------------------------------------------------------------------------------
/test_ros_gz_bridge/src/test_ros_gz_bridge.cpp:
--------------------------------------------------------------------------------
1 | // Copyright 2024 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 | #include
16 |
17 | #include
18 |
19 | class test_ros_gz_bridge : public ::testing::Test
20 | {
21 | public:
22 | static void SetUpTestCase()
23 | {
24 | rclcpp::init(0, nullptr);
25 | }
26 |
27 | static void TearDownTestCase()
28 | {
29 | rclcpp::shutdown();
30 | }
31 | };
32 |
33 | TEST_F(test_ros_gz_bridge, SpawnNode)
34 | {
35 | ros_gz_bridge::RosGzBridge node;
36 | }
37 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/diff_drive.yaml:
--------------------------------------------------------------------------------
1 | # Diff drive configuration.
2 | - topic_name: "/model/vehicle_blue/cmd_vel"
3 | ros_type_name: "geometry_msgs/msg/Twist"
4 | gz_type_name: "gz.msgs.Twist"
5 | lazy: true
6 | direction: ROS_TO_GZ
7 |
8 | - topic_name: "/model/vehicle_blue/odometry"
9 | ros_type_name: "nav_msgs/msg/Odometry"
10 | gz_type_name: "gz.msgs.Odometry"
11 | lazy: true
12 | direction: GZ_TO_ROS
13 |
14 | - topic_name: "/model/vehicle_green/cmd_vel"
15 | ros_type_name: "geometry_msgs/msg/Twist"
16 | gz_type_name: "gz.msgs.Twist"
17 | lazy: true
18 | direction: ROS_TO_GZ
19 |
20 | - topic_name: "/model/vehicle_green/odometry"
21 | ros_type_name: "nav_msgs/msg/Odometry"
22 | gz_type_name: "gz.msgs.Odometry"
23 | lazy: true
24 | direction: GZ_TO_ROS
25 |
26 | - ros_topic_name: "/tf"
27 | gz_topic_name: "/model/vehicle_green/tf"
28 | ros_type_name: "tf2_msgs/msg/TFMessage"
29 | gz_type_name: "gz.msgs.Pose_V"
30 | direction: GZ_TO_ROS
31 |
32 | - ros_topic_name: "/tf"
33 | gz_topic_name: "/model/vehicle_blue/tf"
34 | ros_type_name: "tf2_msgs/msg/TFMessage"
35 | gz_type_name: "gz.msgs.Pose_V"
36 | direction: GZ_TO_ROS
37 |
--------------------------------------------------------------------------------
/ros_gz_interfaces/msg/SensorNoise.msg:
--------------------------------------------------------------------------------
1 | # A message for specifying sensor noise.
2 |
3 | # Noise type
4 | uint8 NONE = 0
5 | uint8 GAUSSIAN = 2
6 | uint8 GAUSSIAN_QUANTIZED = 3
7 |
8 | # Optional header data.
9 | std_msgs/Header header
10 |
11 | # The type of noise
12 | uint8 type
13 |
14 | # Noise mean
15 | # Used by GAUSSIAN and GAUSSIAN_QUANTIZED
16 | float64 mean
17 |
18 | # Noise standard deviation
19 | # Used by GAUSSIAN and GAUSSIAN_QUANTIZED
20 | float64 stddev
21 |
22 | # Noise mean bias
23 | # Used by GAUSSIAN and GAUSSIAN_QUANTIZED
24 | float64 bias_mean
25 |
26 | # Noise standard deviation bias
27 | float64 bias_stddev
28 |
29 | # Noise precision
30 | # Used by GAUSSIAN_QUANTIZED
31 | float64 precision
32 |
33 | # For type "gaussian*", the standard deviation of the noise used to
34 | # drive a process to model slow variations in a sensor bias.
35 | float64 dynamic_bias_stddev
36 |
37 | # For type "gaussian*", the correlation time in seconds of the
38 | # noise used to drive a process to model slow variations in a sensor bias.
39 | # A typical value, when used, would be on the order of
40 | # 3600 seconds (1 hour).
41 | float64 dynamic_bias_correlation_time
42 |
--------------------------------------------------------------------------------
/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/src/convert/utils.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 CONVERT__UTILS_HPP_
16 | #define CONVERT__UTILS_HPP_
17 |
18 | #include
19 |
20 | namespace ros_gz_bridge
21 | {
22 |
23 | // This can be used to replace `::` with `/` to make frame_id compatible with TF
24 | std::string replace_delimiter(
25 | const std::string & input,
26 | const std::string & old_delim,
27 | const std::string new_delim);
28 |
29 | std::string frame_id_gz_to_ros(const std::string & frame_id);
30 |
31 | } // namespace ros_gz_bridge
32 |
33 | #endif // CONVERT__UTILS_HPP_
34 |
--------------------------------------------------------------------------------
/ros_gz_sim_demos/config/rgbd_camera_bridge.yaml:
--------------------------------------------------------------------------------
1 | # rgbd_camera_bridge configuration.
2 | - ros_topic_name: "/camera/image"
3 | gz_topic_name: "/camera"
4 | ros_type_name: "sensor_msgs/msg/Image"
5 | gz_type_name: "gz.msgs.Image"
6 | lazy: true
7 | direction: GZ_TO_ROS
8 |
9 | - ros_topic_name: "/camera/camera_info"
10 | gz_topic_name: "/camera_info"
11 | ros_type_name: "sensor_msgs/msg/CameraInfo"
12 | gz_type_name: "gz.msgs.CameraInfo"
13 | lazy: true
14 | direction: GZ_TO_ROS
15 |
16 | - topic_name: "/rgbd_camera/image"
17 | ros_type_name: "sensor_msgs/msg/Image"
18 | gz_type_name: "gz.msgs.Image"
19 | lazy: true
20 | direction: GZ_TO_ROS
21 |
22 | - topic_name: "/rgbd_camera/camera_info"
23 | ros_type_name: "sensor_msgs/msg/CameraInfo"
24 | gz_type_name: "gz.msgs.CameraInfo"
25 | lazy: true
26 | direction: GZ_TO_ROS
27 |
28 | - topic_name: "/rgbd_camera/depth_image"
29 | ros_type_name: "sensor_msgs/msg/Image"
30 | gz_type_name: "gz.msgs.Image"
31 | lazy: true
32 | direction: GZ_TO_ROS
33 |
34 | - topic_name: "/rgbd_camera/points"
35 | ros_type_name: "sensor_msgs/msg/PointCloud2"
36 | gz_type_name: "gz.msgs.PointCloudPacked"
37 | lazy: true
38 | direction: GZ_TO_ROS
39 |
--------------------------------------------------------------------------------
/ros_gz_bridge/src/get_mappings.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 GET_MAPPINGS_HPP_
16 | #define GET_MAPPINGS_HPP_
17 |
18 | #include