一、引言

在机器人仿真领域,Gazebo 是一款强大且广泛应用的开源 3D 仿真环境。传感器是机器人感知周围环境的重要部件,在 Gazebo 中正确添加和使用传感器对于实现逼真的机器人仿真至关重要。本教程将详细介绍如何在 Gazebo 中添加和使用不同类型的传感器,包括 IMU 传感器、接触传感器和激光雷达传感器等,并结合实例展示其使用方法。

在为不含插件的 SDF(Simulation Description Format)文件添加 plugin 时,默认插件不会自动加载。为了确保能继续使用 GZ GUI,需要在世界文件的 <world> 标签内添加一些逻辑默认插件。示例代码如下:

<plugin
    filename="gz-sim-physics-system"
    name="gz::sim::systems::Physics">
</plugin>
<plugin
    filename="gz-sim-scene-broadcaster-system"
    name="gz::sim::systems::SceneBroadcaster">
</plugin>

参数解释

  • gz-sim-physics-system:这个插件负责模拟物理效果,如重力、碰撞等,是仿真中不可或缺的部分。
  • gz-sim-scene-broadcaster-system:该插件用于广播场景信息,使得仿真中的物体状态等信息能够被其他模块获取和处理。

本文将基于《Gazebo 仿真环境系列教程(三):让机器人动起来》中的building_robot.sdf为基础,进行添加操作,并将新文件命名为gz sim sensor_tutorial.sdf

二、添加和使用传感器

2.1 IMU 传感器

  1. 添加IMU传感器

    惯性测量单元(IMU)能够输出机器人的四元数姿态、三轴角速度和三轴线加速度。我们基于 moving_robot.sdf 创建新文件 sensor_tutorial.sdf,并在 <world> 标签下添加 IMU 传感器插件定义:

    <plugin filename="gz-sim-imu-system"
        name="gz::sim::systems::Imu">
    </plugin>
    

    接着,在机器人的 chassis 链接下添加 IMU 传感器:

    <sensor name="imu_sensor" type="imu">
        <always_on>1</always_on>
        <update_rate>1</update_rate>
        <visualize>true</visualize>
        <topic>imu</topic>
    </sensor>
    

    参数解释:

    • <always_on>:设置为 1 表示传感器始终处于开启状态,会按照设定的更新速率持续更新数据。
    • <update_rate>:指定传感器数据的更新频率,这里设置为 1 Hz,即每秒更新一次数据。
    • <visualize>:设置为 true 可以在 GUI 中可视化传感器的相关信息,方便观察。
    • <topic>:指定传感器数据发布的主题为 imu,其他模块可以通过订阅该主题来获取传感器数据。
  2. 读取 IMU 数据

    1. 在一个终端中运行世界:
    gz sim sensor_tutorial.sdf
    
    1. 在另一个终端中监听 /imu 主题:
    gz topic -e -t /imu
    

    操作解释:

    • gz sim sensor_tutorial.sdf:启动 Gazebo 仿真,并加载 sensor_tutorial.sdf 世界文件。
    • gz topic -e -t /imu:使用 gz topic 命令监听 /imu 主题,-e 选项表示以详细模式输出,-t 选项指定要监听的主题。

    运行后,使用键盘上的向上箭头键控制机器人前进(需先启用 Key Publisher 插件),此时可以看到传感器数据发生变化,这些数据反映了机器人的姿态、角速度和线加速度信息。

2.2 接触传感器

接触传感器用于检测模型之间的接触情况。在机器人仿真中,接触传感器可以用来检测机器人与障碍物的碰撞,从而实现避障等功能。

  1. 创建障碍物并添加接触传感器

    首先创建一个障碍物(墙):

    <model name='wall'>
        <static>true</static>
        <pose>5 0 0 0 0 0</pose>
        <link name='box'>
            <visual name='visual'>
                <geometry>
                    <box>
                        <size>0.5 10.0 2.0</size>
                    </box>
                </geometry>
                <material>
                    <ambient>0.0 0.0 1.0 1</ambient>
                    <diffuse>0.0 0.0 1.0 1</diffuse>
                    <specular>0.0 0.0 1.0 1</specular>
                </material>
            </visual>
            <collision name='collision'>
                <geometry>
                    <box>
                        <size>0.5 10.0 2.0</size>
                    </box>
                </geometry>
            </collision>
        </link>
    </model>
    

    接着添加接触传感器插件:

    <plugin filename="gz-sim-contact-system"
        name="gz::sim::systems::Contact">
    </plugin>
    

    并在 wall 模型的 box 链接下添加接触传感器:

    <sensor name='sensor_contact' type='contact'>
        <contact>
            <collision>collision</collision>
        </contact>
    </sensor>
    

    参数解释:

    • <static>:设置为 true 表示该模型是静态的,不会受到物理力的影响而移动。
    • <pose>:指定模型在世界中的位置和姿态。
    • <visual>:定义模型的可视化外观,包括几何形状和材质。
    • <collision>:定义模型的碰撞体,用于检测碰撞。
    • gz-sim-contact-system:该插件用于处理接触传感器的相关功能。
    • <sensor>:定义一个接触传感器,name 为传感器的名称,type 为传感器类型。
    • <contact>:指定要检测的碰撞体,这里关联了 collision 碰撞体。
  2. 添加触摸插件与实现机器人停止

    为了使墙被触碰时能发送消息,需要添加 TouchPlugin

    <plugin filename="gz-sim-touchplugin-system"
        name="gz::sim::systems::TouchPlugin">
        <target>vehicle_blue</target>
        <namespace>wall</namespace>
        <time>0.001</time>
        <enabled>true</enabled>
    </plugin>
    

    运行世界并监听 /wall/touched 主题:

    gz sim sensor_tutorial.sdf
    gz topic -e -t /wall/touched
    

    控制机器人撞向墙,会看到终端输出 data: true。为了实现机器人撞墙后停止,添加 TriggeredPublisher 插件:

    <plugin filename="gz-sim-triggered-publisher-system"
        name="gz::sim::systems::TriggeredPublisher">
        <input type="gz.msgs.Boolean" topic="/wall/touched">
            <match>data: true</match>
        </input>
        <output type="gz.msgs.Twist" topic="/cmd_vel">
            linear: {x: 0.0}, angular: {z: 0.0}
        </output>
    </plugin>
    

    参数解释

    • <target>:指定与墙接触的目标为 vehicle_blue,即当 vehicle_blue 与墙接触时触发相应操作。
    • <namespace>:设置消息发布的命名空间,机器人触碰墙时会向 /wall/touched 主题发送消息。
    • <time>:指定接触检测的时间间隔。
    • <enabled>:设置为 true 表示启用该插件。
    • <input>:指定输入的消息类型和主题,当 /wall/touched 主题接收到 data: true 消息时触发操作。
    • <output>:指定输出的消息类型和主题,向 /cmd_vel 主题发布速度指令,将线速度和角速度都设置为 0,从而使机器人停止。

此时世界模型效果如下图所示:
在这里插入图片描述

2.3 激光雷达传感器

激光雷达(Lidar)是一种通过发射激光束并接收反射光来测量距离的传感器。在机器人领域,激光雷达常用于环境感知和导航。

首先在 vehicle_blue 模型内创建一个固定激光雷达的框架:

<frame name="lidar_frame" attached_to='chassis'>
    <pose>0.8 0 0.5 0 0 0</pose>
</frame>

然后在 <world> 标签下添加传感器插件:

<plugin
    filename="gz-sim-sensors-system"
    name="gz::sim::systems::Sensors">
    <render_engine>ogre2</render_engine>
</plugin>

chassis 链接下添加激光雷达传感器:

<sensor name='gpu_lidar' type='gpu_lidar'>
    <pose relative_to='lidar_frame'>0 0 0 0 0 0</pose>
    <topic>lidar</topic>
    <update_rate>10</update_rate>
    <ray>
        <scan>
            <horizontal>
                <samples>640</samples>
                <resolution>1</resolution>
                <min_angle>-1.396263</min_angle>
                <max_angle>1.396263</max_angle>
            </horizontal>
            <vertical>
                <samples>1</samples>
                <resolution>0.01</resolution>
                <min_angle>0</min_angle>
                <max_angle>0</max_angle>
            </vertical>
        </scan>
        <range>
            <min>0.08</min>
            <max>10.0</max>
            <resolution>0.01</resolution>
        </range>
    </ray>
    <always_on>1</always_on>
    <visualize>true</visualize>
</sensor>

参数解释:

  • <frame>:定义一个坐标系框架,name 为框架名称,attached_to 指定该框架附着的链接。
  • <pose>:指定框架在附着链接上的位置和姿态。
  • gz-sim-sensors-system:该插件用于管理和处理各种传感器。
  • <render_engine>:指定渲染引擎为 ogre2,用于生成激光雷达的扫描数据。
  • <sensor>:定义一个激光雷达传感器,name 为传感器名称,type 为传感器类型。
  • <pose>:指定传感器在 lidar_frame 框架下的位置和姿态。
  • <topic>:指定传感器数据发布的主题为 lidar
  • <update_rate>:指定传感器数据的更新频率为 10 Hz。
  • <ray>:定义激光雷达的扫描和测距参数。
    • <scan>:包括水平和垂直扫描参数。
      • <horizontal>:定义水平扫描的样本数、分辨率和角度范围。
      • <vertical>:定义垂直扫描的样本数、分辨率和角度范围。
    • <range>:定义激光雷达的测距范围和分辨率。
  • <always_on>:设置为 1 表示传感器始终开启。
  • <visualize>:设置为 true 可以在 GUI 中可视化传感器的扫描数据。

四、实现机器人避障

4.1 构建节点程序

有了激光雷达后,我们可以使用ranges数据,让机器人避免撞墙。为此,我们将编写一个简短的 C++ 程序,用于侦听传感器数据并向机器人发送速度命令。我们将构建一个订阅 /lidar 主题并读取其数据的节点。

  1. 创建节点文件
  • 在你的工作空间中创建一个新的节点文件,例如 lidar_node.cpp。这个文件将包含用于处理激光雷达数据并控制机器人运动的代码。

  • lidar_node.cpp 文件中,编写以下代码:

    #include <gz/msgs/twist.pb.h>
    #include <gz/msgs/laserscan.pb.h>
    #include <gz/transport/Node.hh>
    
    
    std::string topic_pub = "/cmd_vel";   //publish to this topic
    gz::transport::Node node;
    auto pub = node.Advertise<gz::msgs::Twist>(topic_pub);
    
    //brief Function called each time a topic update is received.
    void cb(const gz::msgs::LaserScan &_msg)
    {
      gz::msgs::Twist data;
    
      bool allMore = true;
      for (int i = 0; i < _msg.ranges_size(); i++)
      {
        if (_msg.ranges(i) < 1.0) 
        {
          allMore = false;
          break;
        }
      }
      if (allMore) //if all bigger than one
      {
        data.mutable_linear()->set_x(0.5);
        data.mutable_angular()->set_z(0.0);
      }
      else
      {
        data.mutable_linear()->set_x(0.0);
        data.mutable_angular()->set_z(0.5);
      }
      pub.Publish(data);
    }
    
    int main(int argc, char **argv)
    {
      std::string topic_sub = "/lidar";   // subscribe to this topic
      // Subscribe to a topic by registering a callback.
      if (!node.Subscribe(topic_sub, cb))
      {
        std::cerr << "Error subscribing to topic [" << topic_sub << "]" << std::endl;
        return -1;
      }
    
      // Zzzzzz.
      gz::transport::waitForShutdown();
    
      return 0;
    }
    

    参数解释:

    • 包含头文件:包含了 gz/msgs/laserscan.pb.hgz/msgs/twist.pb.h 用于处理激光雷达数据和速度指令消息,gz/transport/Node.h 用于创建节点进行消息的发布和订阅。
    • 全局变量:定义了发布速度指令的主题 topic_pub,创建了一个 gz::transport::Node 节点和一个发布器 pub
    • 回调函数 cb:该函数接收激光雷达数据 _msg,遍历所有测距数据,如果所有数据都大于 1.0,则让机器人以 0.5 的线速度前进,角速度为 0;否则,让机器人停止前进,以 0.5 的角速度旋转。
    • 主函数 main:定义了订阅激光雷达数据的主题 topic_sub,调用 node.Subscribe 方法订阅该主题,并指定回调函数 cb。如果订阅失败,输出错误信息并返回 -1。最后调用 gz::transport::waitForShutdown() 等待程序结束。
  1. 创建 CMakeLists.txt 文件

    在工作空间中创建一个 CMakeLists.txt 文件,内容如下:

    cmake_minimum_required(VERSION 3.10.2 FATAL_ERROR)
    
    project(avoid_wall)
    
    # Find the Gazebo_Transport library
    find_package(gz-transport12 QUIET REQUIRED OPTIONAL_COMPONENTS log)
    set(GZ_TRANSPORT_VER ${gz-transport12_VERSION_MAJOR})
    
    include_directories(${CMAKE_BINARY_DIR})
    
    if (EXISTS "${CMAKE_SOURCE_DIR}/lidar_node.cpp")
      add_executable(lidar_node lidar_node.cpp)
      target_link_libraries(lidar_node gz-transport${GZ_TRANSPORT_VER}::core)
    endif()
    

4.2. 运行节点

lidar_node 所在文件夹创建 build 目录,执行如下命令构建代码:

mkdir build
cd build
cmake ..
make lidar_node

分别在两个终端运行节点和世界:

./build/lidar_node
gz sim sensor_tutorial.sdf

此时可以看到机器人能自动避障。

在这里插入图片描述

五、Gazebo 启动文件

为了简化操作,可以创建启动文件同时运行世界和节点。创建 sensor_launch.gzlaunch 文件,内容如下:

<?xml version='1.0'?>
<gz version='1.0'>
    <executable name='sensor-world'>
        <command>gz sim sensor_tutorial.sdf</command>
    </executable>
    <executable name='lidar_node'>
        <command>./build/lidar_node</command>
    </executable>
</gz>

运行启动文件:

gz launch sensor_launch.gzlaunch

按下仿真界面的播放按钮,机器人即可自动避障运行。

六、总结

本教程详细介绍了在 Gazebo 仿真环境中添加和使用 IMU 传感器、接触传感器和激光雷达传感器的方法,并结合实例展示了如何利用这些传感器实现机器人避障功能。同时,还介绍了使用 Gazebo 启动文件简化操作的方法。通过学习本教程,读者可以在 Gazebo 中灵活运用各种传感器进行机器人仿真开发。

参考文献

Gazebo Tutorials

Logo

DAMO开发者矩阵,由阿里巴巴达摩院和中国互联网协会联合发起,致力于探讨最前沿的技术趋势与应用成果,搭建高质量的交流与分享平台,推动技术创新与产业应用链接,围绕“人工智能与新型计算”构建开放共享的开发者生态。

更多推荐