< >
Home » ROS2与webots入门教程 » ros2与webots入门教程-如何添加设备

ros2与webots入门教程-如何添加设备

ros2与webots入门教程-如何添加设备

说明: 

  • 介绍webots如何添加设备
  • 默认情况下,webots_ros2_driver 包会自动为几乎所有的 Webots 设备创建一个 ROS 2 接口(IMU 设备不是这种情况,因为它是多个 Webots 设备的组合)。
  • 对设备接口进行参数化的常用方法是在 URDF 文件的 标记中进行。
  • 您可以在下面找到一个通用示例,其中引用应与机器人中设备的名称匹配,类型应与设备的类型匹配(您可以在下一节中为每个设备找到它。)
  • 通用示例如下
<?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>

执行器设备

LED设备

  • 设备类型名称: LED。
  • 控制此设备
  • LED 设备可以接收有关主题的 std_msgs/Int32 消息,以便打开或关闭 LED 或更改其颜色。
  • 可在此处找到 LED 设备的 Webots 文档以获取更多信息

传感器设备

Camera

  • 设备类型名称

  • 摄像头设备的类型名称为 Camera。

  • 设备输出

  • 摄像头设备可以发布多个话题:

    • 包含相机原始图像的 sensor_msgs/Image 消息的主要话题。
    • 带有 sensor_msgs/CameraInfo 消息的次要话题,其中包含相机的元信息。该话题的名称是 /camera_info,前面是主要话题的名称。
  • 如果相机具有识别功能,相机可以选择发布两个附加话题:

    • 带有 vision_msgs/Detection2DArray 消息的第三个话题,其中包含检测到的对象列表。该话题的名称是 /recognitions,前面是主要话题的名称。
    • 带有自定义 WbCameraRecognitionObjects 消息的第三个话题。该话题的名称是 /recognitions/webots,前面是主要话题的名称。
  • 自定义 WbCameraRecognitionObjects 包含 std_msgs/Header 和 WbCameraRecognitionObject 检测到的对象的列表。

  • WbCameraRecognitionObject 对象包含以下信息:

    • id std_msgs/Int32:检测到的对象的 Webots id。
    • pose geometry_msgs/PoseStamped:包含检测到的物体的位姿。
    • bbox vision_msgs/BoundingBox2D:定义图像中检测到的物体周围的边界框。
    • colors std_msgs/ColorRGBA[]:包含检测到的对象的所有颜色的列表。
    • model std_msgs/String:检测到对象的 Webots 模型字段。
    • 可在此处找到相机设备的 Webots 文档以获取更多信息

距离传感器装置

  • 设备类型名称

  • 距离传感器设备的类型名称是 DistanceSensor。

  • 设备输出

  • 距离传感器设备发布 sensor_msgs/Range 消息,其中范围不是 -Inf 或 +Inf(无论是否进行了检测),而是到潜在对象的距离。

  • 可在此处找到距离传感器设备的 Webots 文档以获取更多信息

GPS设备

  • 设备类型名称

  • GPS 设备的类型名称为 GPS。

  • 设备输出

  • GPS 设备可以发布多个话题:

    • 包含 GPS 测量值的 geometry_msgs/PointStamped 消息(或 sensor_msgs/NavSatFix 消息,如果 Webots WorldInfo 节点的 gpsCoordinateSystem 字段为 WGS84)的话题。
    • 带有 std_msgs/Float32 消息的次要话题,其中包含 GPS 速度(以米/秒为单位)。 该话题的名称是 /speed,前面是主要话题的名称。
    • 包含以米/秒为单位的 GPS 速度矢量的 geometry_msgs/Vector3 消息的第三个话题。 该话题的名称是 /speed_vector,前面是主要话题的名称。
  • 可以在此处找到 GPS 设备的 Webots 文档以获取更多信息

激光雷达设备

  • 设备类型名称

  • 激光雷达设备的类型名称为 Lidar。

  • 设备输出

  • 激光雷达设备可以发布多个话题:

 - 包含激光雷达设备第一层的 sensor_msgs/LaserScan 消息的主要话题。 仅当激光雷达设备具有单层时才会发布此话题。
 - 带有 sensor_msgs/PointCloud2 消息的次要话题,其中包含 1D 无序方式的激光雷达测量值。 该话题的名称是 - /point_cloud,前面是主要主题的名称。

  • 可以在此处找到激光雷达设备的 Webots 文档以获取更多信息

光传感器装置

  • 设备类型名称

    • 光传感器设备的类型名称是 LightSensor。
  • 设备输出

    • 光传感器设备发布 sensor_msgs/Illuminance 消息。
  • 可在此处找到光传感器设备的 Webots 文档以获取更多信息

测距仪设备

  • 设备类型名称

    • RangeFinder 设备的类型名称为 RangeFinder。
  • 设备输出

  • rangeFinder 设备可以发布多个主题:

    • sensor_msgs/Image 消息的主要主题,其中包含 rangeFinder 的原始灰度图像,这是一个深度相机。
    • 带有 sensor_msgs/CameraInfo 消息的次要主题,其中包含 rangeFinder 相机的元信息。 该主题的名称是 /camera_info,前面是主要主题的名称。
    • 带有 sensor_msgs/PointCloud2 消息的第三个主题包含以 2D 有序方式的 rangeFinder 测量值。 该主题的名称是 /point_cloud,前面是主要主题的名称。
  • 可在此处找到 rangeFinder 设备的 Webots 文档以获取更多信息

IMU 设备

  • 如前所述,IMU 设备由三个 Webots 设备组成:

  • 一个 Webots 惯性单元设备(在 Webots 中,惯性单元只返回一个方向)。

  • 用于获取角速度的 Webots 陀螺仪设备。

  • 用于获取加速度的 Webots 加速度计设备。

  • 此设备的接口不会自动创建,必须在 URDF 文件中添加已创建的插件。

  • 可选标签与 标签相同,但必须指定机器人内部的惯性单元设备、陀螺仪设备和加速度计设备的名称,以便插件找到它们。

<?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>

纠错,疑问,交流: 请进入讨论区点击加入Q群

获取最新文章: 扫一扫右上角的二维码加入“创客智造”公众号


标签: ros2与webots入门教程