From 7d8f788c4f6409ba717b8e021512dca6f998a744 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 19 May 2022 10:01:16 -0700 Subject: [PATCH 1/3] [ros2] README updates (service bridge, Gazebo rename) Signed-off-by: Louise Poubel --- README.md | 70 +++++++++++++++++----------------- ros_ign/README.md | 4 +- ros_ign_bridge/README.md | 43 ++++++++++++--------- ros_ign_gazebo/README.md | 10 ++--- ros_ign_gazebo_demos/README.md | 18 ++++----- ros_ign_image/README.md | 6 +-- ros_ign_interfaces/README.md | 20 +++++----- 7 files changed, 88 insertions(+), 83 deletions(-) diff --git a/README.md b/README.md index 6cb3a7df..f1c2f081 100644 --- a/README.md +++ b/README.md @@ -1,48 +1,48 @@ -[![Build Status](https://github.com/ignitionrobotics/ros_ign/actions/workflows/ros2-ci.yml/badge.svg?branch=ros2)](https://github.com/ignitionrobotics/ros_ign/actions/workflows/ros2-ci.yml) +[![Build Status](https://github.com/gazebosim/ros_gz/actions/workflows/ros2-ci.yml/badge.svg?branch=ros2)](https://github.com/gazebosim/ros_gz/actions/workflows/ros2-ci.yml) -ROS version | Ignition version | Branch | Binaries hosted at +ROS version | Gazebo version | Branch | Binaries hosted at -- | -- | -- | -- -Melodic | Citadel | [melodic](https://github.com/osrf/ros_ign/tree/melodic) | only from source -Melodic | Fortress | [melodic](https://github.com/osrf/ros_ign/tree/melodic) | only from source -Noetic | Citadel | [noetic](https://github.com/osrf/ros_ign/tree/noetic) | https://packages.ros.org -Noetic | Edifice | [noetic](https://github.com/osrf/ros_ign/tree/noetic) | only from source -Noetic | Fortress | [noetic](https://github.com/osrf/ros_ign/tree/noetic) | only from source -Foxy | Citadel | [foxy](https://github.com/osrf/ros_ign/tree/foxy) | https://packages.ros.org -Foxy | Edifice | [foxy](https://github.com/osrf/ros_ign/tree/foxy) | only from source -Galactic | Edifice | [galactic](https://github.com/osrf/ros_ign/tree/galactic) | https://packages.ros.org -Galactic | Fortress | [galactic](https://github.com/osrf/ros_ign/tree/galactic) | only from source -Rolling | Edifice | [ros2](https://github.com/osrf/ros_ign/tree/ros2) | only from source -Rolling | Fortress | [ros2](https://github.com/osrf/ros_ign/tree/ros2) | https://packages.ros.org - -> Please [ticket an issue](https://github.com/ignitionrobotics/ros_ign/issues/) if you'd like support to be added for some combination. - -# Integration between ROS and Ignition +Melodic | Citadel | [melodic](https://github.com/gazebosim/ros_gz/tree/melodic) | only from source +Melodic | Fortress | [melodic](https://github.com/gazebosim/ros_gz/tree/melodic) | only from source +Noetic | Citadel | [noetic](https://github.com/gazebosim/ros_gz/tree/noetic) | https://packages.ros.org +Noetic | Edifice | [noetic](https://github.com/gazebosim/ros_gz/tree/noetic) | only from source +Noetic | Fortress | [noetic](https://github.com/gazebosim/ros_gz/tree/noetic) | only from source +Foxy | Citadel | [foxy](https://github.com/gazebosim/ros_gz/tree/foxy) | https://packages.ros.org +Foxy | Edifice | [foxy](https://github.com/gazebosim/ros_gz/tree/foxy) | only from source +Galactic | Edifice | [galactic](https://github.com/gazebosim/ros_gz/tree/galactic) | https://packages.ros.org +Galactic | Fortress | [galactic](https://github.com/gazebosim/ros_gz/tree/galactic) | only from source +Rolling | Edifice | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | only from source +Rolling | Fortress | [ros2](https://github.com/gazebosim/ros_gz/tree/ros2) | https://packages.ros.org + +> Please [ticket an issue](https://github.com/gazebosim/ros_gz/issues/) if you'd like support to be added for some combination. + +# Integration between ROS and Gazebo ## Packages This repository holds packages that provide integration between -[ROS](http://www.ros.org/) and [Ignition](https://ignitionrobotics.org): +[ROS](http://www.ros.org/) and [Gazebo](https://gazebosim.org): -* [ros_ign](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign): +* [ros_ign](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign): Metapackage which provides all the other packages. -* [ros_ign_image](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign_image): +* [ros_ign_image](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_image): Unidirectional transport bridge for images from - [Ignition Transport](https://ignitionrobotics.org/libs/transport) + [Gazebo Transport](https://gazebosim.org/libs/transport) to ROS using [image_transport](http://wiki.ros.org/image_transport). -* [ros_ign_bridge](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign_bridge): +* [ros_ign_bridge](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_bridge): Bidirectional transport bridge between - [Ignition Transport](https://ignitionrobotics.org/libs/transport) + [Gazebo Transport](https://gazebosim.org/libs/transport) and ROS. -* [ros_ign_gazebo](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign_gazebo): +* [ros_ign_gazebo](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo): Convenient launch files and executables for using - [Ignition Gazebo](https://ignitionrobotics.org/libs/gazebo) + [Gazebo Sim](https://gazebosim.org/libs/gazebo) with ROS. -* [ros_ign_gazebo_demos](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign_gazebo_demos): - Demos using the ROS-Ignition integration. -* [ros_ign_point_cloud](https://github.com/ignitionrobotics/ros_ign/tree/ros2/ros_ign_point_cloud): +* [ros_ign_gazebo_demos](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_gazebo_demos): + Demos using the ROS-Gazebo integration. +* [ros_ign_point_cloud](https://github.com/gazebosim/ros_gz/tree/ros2/ros_ign_point_cloud): Plugins for publishing point clouds to ROS from - [Ignition Gazebo](https://ignitionrobotics.org/libs/gazebo) simulations. + [Gazebo Sim](https://gazebosim.org/libs/gazebo) simulations. ## Install @@ -71,11 +71,11 @@ Be sure you've installed [ROS Rolling](https://index.ros.org/doc/ros2/Installation/) (at least ROS-Base). More ROS dependencies will be installed below. -#### Ignition +#### Gazebo -Install either [Edifice or Fortress](https://ignitionrobotics.org/docs). +Install either [Edifice or Fortress](https://gazebosim.org/docs). -Set the `IGNITION_VERSION` environment variable to the Ignition version you'd +Set the `IGNITION_VERSION` environment variable to the Gazebo version you'd like to compile against. For example: export IGNITION_VERSION=edifice @@ -94,17 +94,17 @@ The following steps are for Linux and OSX. cd ~/ws/src # Download needed software - git clone https://github.com/osrf/ros_ign.git -b ros2 + git clone https://github.com/gazebosim/ros_gz.git -b ros2 ``` -1. Install dependencies (this may also install Ignition): +1. Install dependencies (this may also install Gazebo): ``` cd ~/ws rosdep install -r --from-paths src -i -y --rosdistro rolling ``` - > If `rosdep` fails to install Ignition libraries and you have not installed them before, please follow [Ignition installation instructions](https://ignitionrobotics.org/docs/latest/install). + > If `rosdep` fails to install Gazebo libraries and you have not installed them before, please follow [Gazebo installation instructions](https://gazebosim.org/docs/latest/install). 1. Build the workspace: diff --git a/ros_ign/README.md b/ros_ign/README.md index 57837442..b57cdcf8 100644 --- a/ros_ign/README.md +++ b/ros_ign/README.md @@ -1,4 +1,4 @@ -# ROS-Ignition packages +# ROS-Gazebo packages `ros_ign` is a metapackage that installs all packages integrating -[ROS](http://www.ros.org/) and [Ignition](https://ignitionrobotics.org): +[ROS](http://www.ros.org/) and [Gazebo](https://gazebosim.org): diff --git a/ros_ign_bridge/README.md b/ros_ign_bridge/README.md index 49b268c6..f5d20c8c 100644 --- a/ros_ign_bridge/README.md +++ b/ros_ign_bridge/README.md @@ -1,12 +1,11 @@ -# Bridge communication between ROS and Ignition Transport +# Bridge communication between ROS and Gazebo This package provides a network bridge which enables the exchange of messages -between ROS and Ignition Transport. +between ROS and Gazebo Transport. -The bridge is currently implemented in C++. At this point there's no support for -service calls. Its support is limited to only the following message types: +The following message types can be bridged for topics: -| ROS type | Ignition Transport type | +| ROS type | Gazebo type | |--------------------------------------|:--------------------------------------:| | builtin_interfaces/msg/Time | ignition::msgs::Time | | std_msgs/msg/Bool | ignition::msgs::Boolean | @@ -55,9 +54,15 @@ service calls. Its support is limited to only the following message types: | tf2_msgs/msg/TFMessage | ignition::msgs::Pose_V | | trajectory_msgs/msg/JointTrajectory | ignition::msgs::JointTrajectory | +And the following for services: + +| ROS type | Gazebo request | Gazebo response | +|--------------------------------------|:--------------------------:| --------------------- | +| ros_ign_interfaces/srv/ControlWorld | ignition.msgs.WorldControl | ignition.msgs.Boolean | + Run `ros2 run ros_ign_bridge parameter_bridge -h` for instructions. -## Example 1a: Ignition Transport talker and ROS 2 listener +## Example 1a: Gazebo Transport talker and ROS 2 listener Start the parameter bridge which will watch the specified topics. @@ -75,14 +80,14 @@ Now we start the ROS listener. ros2 topic echo /chatter ``` -Now we start the Ignition Transport talker. +Now we start the Gazebo Transport talker. ``` # Shell C: ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"' ``` -## Example 1b: ROS 2 talker and Ignition Transport listener +## Example 1b: ROS 2 talker and Gazebo Transport listener Start the parameter bridge which will watch the specified topics. @@ -92,7 +97,7 @@ Start the parameter bridge which will watch the specified topics. ros2 run ros_ign_bridge parameter_bridge /chatter@std_msgs/msg/String@ignition.msgs.StringMsg ``` -Now we start the Ignition Transport listener. +Now we start the Gazebo Transport listener. ``` # Shell B: @@ -109,11 +114,11 @@ ros2 topic pub /chatter std_msgs/msg/String "data: 'Hi'" --once ## Example 2: Run the bridge and exchange images -In this example, we're going to generate Ignition Transport images using -Ignition Gazebo, that will be converted into ROS images, and visualized with +In this example, we're going to generate Gazebo Transport images using +Gazebo Sim, that will be converted into ROS images, and visualized with `rqt_image_viewer`. -First we start Ignition Gazebo (don't forget to hit play, or Ignition Gazebo won't generate any images). +First we start Gazebo Sim (don't forget to hit play, or Gazebo Sim won't generate any images). ``` # Shell A: @@ -146,12 +151,12 @@ ros2 run rqt_image_view rqt_image_view /rgbd_camera/image ``` You should see the current images in `rqt_image_view` which are coming from -Gazebo (published as Ignition Msgs over Ignition Transport). +Gazebo (published as Gazebo Msgs over Gazebo Transport). The screenshot shows all the shell windows and their expected content -(it was taken using ROS 2 Galactic and Ignition Fortress): +(it was taken using ROS 2 Galactic and Gazebo Fortress): -![Ignition Transport images and ROS rqt](images/bridge_image_exchange.png) +![Gazebo Transport images and ROS rqt](images/bridge_image_exchange.png) ## Example 3: Static bridge @@ -163,7 +168,7 @@ The example's code can be found under `ros_ign_bridge/src/static_bridge.cpp`. In the code, it's possible to see how the bridge is hardcoded to bridge string messages published on the `/chatter` topic. -Let's give it a try, starting with Ignition -> ROS 2. +Let's give it a try, starting with Gazebo -> ROS 2. On terminal A, start the bridge: @@ -173,13 +178,13 @@ On terminal B, we start a ROS 2 listener: `ros2 topic echo /chatter std_msgs/msg/String` -And terminal C, publish an Ignition message: +And terminal C, publish an Gazebo message: `ign topic -t /chatter -m ignition.msgs.StringMsg -p 'data:"Hello"'` At this point, you should see the ROS 2 listener echoing the message. -Now let's try the other way around, ROS 2 -> Ignition. +Now let's try the other way around, ROS 2 -> Gazebo. On terminal D, start an Igntion listener: @@ -189,4 +194,4 @@ And on terminal E, publish a ROS 2 message: `ros2 topic pub /chatter std_msgs/msg/String 'data: "Hello"' -1` -You should see the Ignition listener echoing the message. +You should see the Gazebo listener echoing the message. diff --git a/ros_ign_gazebo/README.md b/ros_ign_gazebo/README.md index 4a01567a..377c4080 100644 --- a/ros_ign_gazebo/README.md +++ b/ros_ign_gazebo/README.md @@ -1,11 +1,11 @@ -# ROS + Ignition Gazebo +# ROS + Gazebo Sim -This package contains things that make it convenient to integrate ROS with Ignition, such as: +This package contains things that make it convenient to integrate ROS with Gazebo, such as: - Launch files - ROS-enabled executables -### Run Ignition Gazebo +### Run Gazebo Sim There's a convenient launch file, try for example: @@ -17,10 +17,10 @@ ros2 launch ros_ign_gazebo ign_gazebo.launch.py ign_args:="shapes.sdf" The `create` executable can be used to spawn SDF or URDF entities from: - - A file on disk or from Ignition Fuel + - A file on disk or from Gazebo Fuel - A ROS parameter -For example, start Ignition Gazebo: +For example, start Gazebo Sim: ``` ros2 launch ros_ign_gazebo ign_gazebo.launch.py diff --git a/ros_ign_gazebo_demos/README.md b/ros_ign_gazebo_demos/README.md index a7ada44d..4ba9b4fb 100644 --- a/ros_ign_gazebo_demos/README.md +++ b/ros_ign_gazebo_demos/README.md @@ -1,8 +1,8 @@ -# ROS + Ignition Gazebo demos +# ROS + Gazebo Sim demos -This package contains demos showing how to use Ignition Gazebo with ROS. +This package contains demos showing how to use Gazebo Sim with ROS. -## Run Ignition Gazebo +## Run Gazebo Sim There's a convenient launch file, try for example: @@ -41,11 +41,11 @@ Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.o Using the regular bridge: ros2 launch ros_ign_gazebo_demos camera.launch.py - + To use a camera that only publishes information when triggered: ros2 launch ros_ign_gazebo_demos triggered_camera.launch.py - + Trigger the camera: ros2 topic pub /camera/trigger std_msgs/msg/Bool "{data: true}" --once @@ -87,7 +87,7 @@ Using the image bridge (unidirectional, uses [image_transport](http://wiki.ros.o *TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). -Using Ignition Gazebo plugin: +Using Gazebo Sim plugin: ros2 launch ros_ign_gazebo_demos depth_camera.launch.py @@ -106,7 +106,7 @@ Using the bridge: *TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). -Using Ignition Gazebo plugin: +Using Gazebo Sim plugin: ros2 launch ros_ign_gazebo_demos gpu_lidar.launch.py @@ -150,7 +150,7 @@ Using the regular bridge: *TODO*: Blocked by `ros_ign_point_cloud` [issue](https://github.com/osrf/ros_ign/issues/40). -Using Ignition Gazebo plugin: +Using Gazebo Sim plugin: ros2 launch ros_ign_gazebo_demos rgbd_camera.launch.py @@ -190,7 +190,7 @@ To try the demo launch: ## Bridging joint state and pose publishers -The launch file demonstrates bridging ignition poses to TFMessage to visualize the pose +The launch file demonstrates bridging Gazebo poses to TFMessage to visualize the pose and transforms of a robot in rviz. To try the demo launch: diff --git a/ros_ign_image/README.md b/ros_ign_image/README.md index b07984b2..b7b27e1f 100644 --- a/ros_ign_image/README.md +++ b/ros_ign_image/README.md @@ -1,7 +1,7 @@ -# Image utilities for using ROS and Ignition Transport +# Image utilities for using ROS and Gazebo Transport -This package provides a unidirectional bridge for images from Ignition to ROS. -The bridge subscribes to Ignition image messages (`ignition::msgs::Image`) +This package provides a unidirectional bridge for images from Gazebo to ROS. +The bridge subscribes to Gazebo image messages (`ignition::msgs::Image`) and republishes them to ROS using [image_transport](http://wiki.ros.org/image_transport). For compressed images, install diff --git a/ros_ign_interfaces/README.md b/ros_ign_interfaces/README.md index e6a637bc..bc81a456 100644 --- a/ros_ign_interfaces/README.md +++ b/ros_ign_interfaces/README.md @@ -1,20 +1,20 @@ -# Message and service data structures for interacting with Ignition from ROS2 +# Message and service data structures for interacting with Gazebo from ROS2 -This package currently contains some Ignition-specific ROS message and service data structures (.msg and .srv) +This package currently contains some Gazebo-specific ROS message and service data structures (.msg and .srv) ## Messages (.msg) -* [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Ignition Gazebo. +* [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Gazebo Sim. * [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto). A list of contacts. -* [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Ignition Gazebo. +* [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Gazebo Sim. * [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity. -* [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Ignition Gazebo. -* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Ignition Gazebo. +* [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Gazebo Sim. +* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Gazebo Sim. * [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation. ## Services (.srv) -* [ControlWorld](srv/ControlWorld.srv): Control world of Ignition Gazebo,for example,pasue,pasue with multiple steps,resume,etc. -* [DeleteEntity](srv/DeleteEntity.srv): Delete Entity in Ignition Gazebo -* [SetEntityPose](srv/SetEntityPose.srv): Set pose of Entity in Ignition Gazebo -* [SpawnEntity](srv/SpawnEntity.srv): Spawn a Entity in Ignition Gazebo +* [ControlWorld](srv/ControlWorld.srv): Control world of Gazebo Sim,for example,pasue,pasue with multiple steps,resume,etc. +* [DeleteEntity](srv/DeleteEntity.srv): Delete Entity in Gazebo Sim +* [SetEntityPose](srv/SetEntityPose.srv): Set pose of Entity in Gazebo Sim +* [SpawnEntity](srv/SpawnEntity.srv): Spawn a Entity in Gazebo Sim From 8dde4dcbc46a85772398244af34ee28b1f35f097 Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 19 May 2022 10:33:36 -0700 Subject: [PATCH 2/3] service bridge example Signed-off-by: Louise Poubel --- ros_ign_bridge/README.md | 18 ++++++++++++++++++ 1 file changed, 18 insertions(+) diff --git a/ros_ign_bridge/README.md b/ros_ign_bridge/README.md index f5d20c8c..ef9bb3ac 100644 --- a/ros_ign_bridge/README.md +++ b/ros_ign_bridge/README.md @@ -195,3 +195,21 @@ And on terminal E, publish a ROS 2 message: `ros2 topic pub /chatter std_msgs/msg/String 'data: "Hello"' -1` You should see the Gazebo listener echoing the message. + +## Example 4: Service bridge + +It's possible to make ROS service requests into Gazebo. Let's try unpausing the simulation. + +On terminal A, start the service bridge: + +`ros2 run ros_ign_bridge parameter_bridge /world/shapes/control@ros_ign_interfaces/srv/ControlWorld` + +On terminal B, start Gazebo, it will be paused by default: + +`ign gazebo shapes.sdf` + +On terminal C, make a ROS request to unpause simulation: + +``` +ros2 service call /world//control ros_ign_interfaces/srv/ControlWorld "world_control: pause: false" +``` From 066a68c14a60579c72edaf32990e6d4beb914f1f Mon Sep 17 00:00:00 2001 From: Louise Poubel Date: Thu, 19 May 2022 16:29:52 -0700 Subject: [PATCH 3/3] More URLs Signed-off-by: Louise Poubel --- ros_ign_interfaces/README.md | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/ros_ign_interfaces/README.md b/ros_ign_interfaces/README.md index bc81a456..88ed27d7 100644 --- a/ros_ign_interfaces/README.md +++ b/ros_ign_interfaces/README.md @@ -4,13 +4,13 @@ This package currently contains some Gazebo-specific ROS message and service dat ## Messages (.msg) -* [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Gazebo Sim. -* [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto). A list of contacts. -* [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Gazebo Sim. -* [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity. -* [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Gazebo Sim. -* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Gazebo Sim. -* [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/ignitionrobotics/ign-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation. +* [Contact](msg/Contact.msg): related to [ignition::msgs::Contact](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/contact.proto). Contant info bewteen collisions in Gazebo Sim. +* [Contacts](msg/Contacts.msg): related to [ignition::msgs::Contacts](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/contacts.proto). A list of contacts. +* [Entity](msg/Entity.msg): related to [ignition::msgs::Entity](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/entity.proto). Entity of Gazebo Sim. +* [EntityFactory](msg/EntityFactory.msg): related to [ignition::msgs::EntityFactory](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/entity_factory.proto). Message to create a new entity. +* [Light](msg/Light.msg): related to [ignition::msgs::Light](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/light.proto). Light info in Gazebo Sim. +* [WorldControl](msg/WorldControl.msg): related to [ignition::msgs::WorldControl](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/world_control.proto). Message to control world of Gazebo Sim. +* [WorldReset](msg/WorldReset.msg): related to [ignition::msgs::WorldReset](https://github.com/gazebosim/gz-msgs/blob/ign-msgs7/proto/ignition/msgs/world_reset.proto). Reset time and model of simulation. ## Services (.srv)