References Devices - cyberbotics/webots_ros2 GitHub Wiki

By default, the webots_ros2_driver package will automatically create a ROS 2 interface for almost all the Webots devices (it is not the case for the IMU device, as it is a combination of multiple Webots devices).

The common way to parametrize the interface for a device is to do it within a <device> tag in a URDF file.

You can find below a generic example, where the reference should match the name of the device in the robot and the type should match the type of the device (you can find it for each device in the next sections.)

<?xml version="1.0" ?>
<robot name="RobotName">
    <webots>
        <device reference="referenceName" type="typeName">
            <ros>
                <!-- If `False`, disable the device. By default the device will be enabled. -->
                <enabled>False</enabled>

                <!-- Set the main topic name of the device. By default it will be `/robotName/referenceName`. -->
                <!-- If a device publishes several topics, the secondary topics names are relative to the main topic name. -->
                <!-- Example: if the main topic name is `my_robot/camera`, the secondary topic for the `camera_info` messages -->
                <!-- will be `my_robot/camera/camera_info`. -->
                <topicName>/new_topic_name</topicName>
                <!-- Set the update rate in Hz of the topic. By default the topic will be published at each simulation step. -->
                <updateRate>10</updateRate>
                <!-- If `True`, the device topics will constantly publish, which can slow down the simulation. -->
                <!-- By default the topics are publishing only if there is at least one subscriber for the corresponding topic. -->
                <alwaysOn>True</alwaysOn>
                <!-- Set the frame ID for message headers. By default the frame ID is `referenceName`. -->
                <frameName>new_frame_name</frameName>
            </ros>
        </device>
    </webots>
</robot>

Actuator Devices

This section regroups the actuators currently available:

LED Device

Device Type Name

The type name of the LED device is LED.

Controlling this Device

The LED device can receive std_msgs/Int32 messages on a topic in order to switch on or off a LED or change its color.

The Webots documentation for the LED device can be found here for further information.

Emitter Device

Device Type Name

The type name of the Emitter device is Emitter.

Controlling this Device

The Emitter device can receive webots_ros2_msgs/srv/EmitterSendString messages on a service in order to send messages.

By using the integer parameter in the URDF file, you can select the specific channel where you want to send your messages.

The Webots documentation for the Emitter device can be found here for further information.

Sensor Devices

This section regroups the sensors currently available:

Camera Device

Device Type Name

The type name of the camera device is Camera.

Device Output(s)

The camera device can publish on several topics:

  • A main topic with sensor_msgs/Image messages containing the raw images of the camera. By default, images are published on the main topic, but it is possible to add a suffix with the parameter in the URDF. For example, to publish to the /main_topic/image_raw topic, you can add <imageSuffix>/image_raw</imageSuffix> to the URDF file.
  • A secondary topic with sensor_msgs/CameraInfo messages containing meta information for the camera. By default, the name of this topic is /camera_info preceded by the name of the main topic, but the suffix can be changed with the parameter.

Optionally the camera can publish two additional topics if the camera has a recognition capability:

  • An third topic with vision_msgs/Detection2DArray messages containing a list of detected objects. The name of this topic is /recognitions preceded by the name of the main topic.
  • An third topic with custom WbCameraRecognitionObjects messages. The name of this topic is /recognitions/webots preceded by the name of the main topic.

The custom WbCameraRecognitionObjects contains a std_msgs/Header and a list of WbCameraRecognitionObject detected objects.

A WbCameraRecognitionObject object contains the following information:

The Webots documentation for the camera device can be found here for further information.

Compass Device

Device Type Name

The type name of the compass device is Compass.

Device Output(s)

The compass device publishes geometry_msgs/Vector3Stamped messages to the /main_topic/north_vector topic indicating the North direction.

Additionally, it publishes webots_ros2_msgs/FloatStamped messages to the /main_topic/bearing topic giving the angle between the sensor and the north direction in degrees.

The Webots documentation for the compass device can be found here for further information.

Distance Sensor Device

Device Type Name

The type name of the distance sensor device is DistanceSensor.

Device Output(s)

The distance sensor device publishes sensor_msgs/Range messages where the range is not -Inf or +Inf whether a detection has been made or not, but rather a distance to a potential object.

The Webots documentation for the distance sensor device can be found here for further information.

GPS Device

Device Type Name

The type name of the GPS device is GPS.

Device Output(s)

The GPS device can publish on several topics:

  • A main topic with geometry_msgs/PointStamped messages (or sensor_msgs/NavSatFix messages in case the gpsCoordinateSystem field of the Webots WorldInfo node is WGS84) containing the GPS measurements.
  • A secondary topic with std_msgs/Float32 messages containing the GPS speed in meters per second. The name of this topic is /speed preceded by the name of the main topic.
  • A third topic with geometry_msgs/Vector3 messages containing the GPS speed vector in meters per second. The name of this topic is /speed_vector preceded by the name of the main topic.

The Webots documentation for the GPS device can be found here for further information.

Lidar Device

Device Type Name

The type name of the lidar device is Lidar.

Device Output(s)

The lidar device can publish on several topics:

  • A main topic with sensor_msgs/LaserScan messages containing the first layer of the lidar device. This topic is published only if the lidar device has a single layer.
  • A secondary topic with sensor_msgs/PointCloud2 messages containing the lidar measurements in an 1D unordered way. The name of this topic is /point_cloud preceded by the name of the main topic.

The Webots documentation for the lidar device can be found here for further information.

Light Sensor Device

Device Type Name

The type name of the light sensor device is LightSensor.

Device Output(s)

The light sensor device publishes sensor_msgs/Illuminance messages.

The Webots documentation for the light sensor device can be found here for further information.

RangeFinder Device

Device Type Name

The type name of the rangeFinder device is RangeFinder.

Device Output(s)

The rangeFinder device can publish on several topics:

  • A main topic with sensor_msgs/Image messages containing the raw grayscale images of the rangeFinder, which is a depth camera. By default, images are published on the main topic, but it is possible to add a suffix with the parameter in the URDF. For example, to publish to the /main_topic/image_raw topic, you can add <imageSuffix>/image_raw</imageSuffix> to the URDF file.
  • A secondary topic with sensor_msgs/CameraInfo messages containing meta information for the camera of the rangeFinder. By default, the name of this topic is /camera_info preceded by the name of the main topic, but the suffix can be changed with the parameter.
  • A third topic with sensor_msgs/PointCloud2 messages containing the rangeFinder measurements in an 2D ordered way. By default, the name of this topic is /point_cloud preceded by the name of the main topic, but the suffix can be changed with the parameter.

The Webots documentation for the rangeFinder device can be found here for further information.

Receiver Device

Device Type Name

The type name of the receiver device is Receiver.

Device Output(s)

The receiver device publishes webots_ros2_msgs/StringStamped messages to the /main_topic/data topic containing the content of the message sent by the Emitter.

Additionally, it publishes webots_ros2_msgs/FloatStamped messages to the /main_topic/signal_strength topic giving the signal strength of the received message.

Finally, it publishes geometry_msgs/Vector3Stamped messages to the /main_topic/emitter_direction topic indicating the direction to the Emitter that sent the message.

The Webots documentation for the receiver device can be found here for further information.

IMU Device

As explained earlier, the IMU device is composed of three Webots devices:

  • An Webots inertial unit device (in Webots the intertial unit returns only an orientation).
  • A Webots gyro device to get angular velocities.
  • A Webots accelerometer device to get accelerations.

The interface for this device is not automatically created and an already created plugin has to be added in the URDF file.

The optional tags are the same than for the <device> tag but in addition the names of the inertial unit device, gyro device and accelerometer device inside the robot have to be specified in order for the plugin to find them.

<?xml version="1.0" ?>
<robot name="RobotName">
    <webots>
        <plugin type="webots_ros2_driver::Ros2IMU">
            <!-- If `False`, disable the device. By default the device will be enabled. -->
            <enabled>False</enabled>

            <!-- Set the topic name of the device. By default it will be `/robotName/referenceName`. -->
            <topicName>/new_topic_name</topicName>
            <!-- Set the update rate in Hz of the topic. By default the topic will be published at each simulation step. -->
            <updateRate>10</updateRate>
            <!-- If `True`, the device topics will constantly publish, which can slow down the simulation. -->
            <!-- By default the topics are publishing only if there is at least one subscriber for the corresponding topic. -->
            <alwaysOn>True</alwaysOn>
            <!-- Set the frame ID for message headers. By default the frame ID is `referenceName`. -->
            <frameName>new_frame_name</frameName>

            <!-- Indicates the name of the inertial unit device. -->
            <inertialUnitName>inertial_unit</inertialUnitName>
            <!-- Indicates the name of the gyro device. -->
            <gyroName>gyro</gyroName>
            <!-- Indicates the name of the accelerometer device. -->
            <accelerometerName>accelerometer</accelerometerName>
        </plugin>
    </webots>
</robot>

Device Output(s)

The IMU device publishes sensor_msgs/Imu messages on a topic.

The Webots documentation for the inertial unit device can be found here, for the gyro device it can be found here and for the accelerometer device it can be found here to get further information on these three devices.

⚠️ **GitHub.com Fallback** ⚠️