惯性测量单元IMU

惯性测量单元是测量物体三轴姿态角(或角速率)以及加速度的装置。一般的,一个IMU包含了三个单轴的加速度计和三个单轴的陀螺,加速度计检测物体在载体坐标系统独立三轴的加速度信号,而陀螺检测载体相对于导航坐标系的角速度信号,测量物体在三维空间中的角速度和加速度,并以此解算出物体的姿态。在导航中有着很重要的应用价值。

上面这段话是小鱼从百科中摘抄出来的,你需要知道的一个关键点是IMU可以测量以下三组数据:

  • 三维角度

  • 三维加速度

  • 三维角速度

常见IMU

Gazebo-IMU插件介绍

仿真的IMU也是对应一个后缀为.so的动态链接库,使用下面的指令可以查看所有的动态链接库:

ls /opt/ros/humble/lib/libgazebo_ros*

IMU对应的消息类型为sensor_msgs/msg/Imu

ros2 interface show sensor_msgs/msg/Imu

给FIshbot配置IMU传感器

有了上节课的经验,我们可以很轻松的添加IMU传感器,但是还有一个需要注意的地方,为了更真实的模拟IMU传感器,我们需要给我们的仿真IMU传感器加点料。

加什么?加点高斯噪声,高斯噪声只需要指定平均值和标准差两个参数即可,不过因为IMU传感器的特殊性,我们还需要给模型添加两个偏差参数,分别是 平均值偏差标准差偏差

有关Gazebo仿真和噪声模型更深入的介绍可以参考小鱼发的两篇推文:

下面是IMU传感器的URDF配置代码,大家结合文章对应可以理解一下,IMU对应的插件库libgazebo_ros_imu_sensor.so

    <gazebo reference="imu_link">
      <sensor name="imu_sensor" type="imu">
      <plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">
          <ros>
            <namespace>/</namespace>
            <remapping>~/out:=imu</remapping>
          </ros>
          <initial_orientation_as_reference>false</initial_orientation_as_reference>
        </plugin>
        <always_on>true</always_on>
        <update_rate>100</update_rate>
        <visualize>true</visualize>
        <imu>
          <angular_velocity>
            <x>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>2e-4</stddev>
                <bias_mean>0.0000075</bias_mean>
                <bias_stddev>0.0000008</bias_stddev>
              </noise>
            </x>
            <y>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>2e-4</stddev>
                <bias_mean>0.0000075</bias_mean>
                <bias_stddev>0.0000008</bias_stddev>
              </noise>
            </y>
            <z>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>2e-4</stddev>
                <bias_mean>0.0000075</bias_mean>
                <bias_stddev>0.0000008</bias_stddev>
              </noise>
            </z>
          </angular_velocity>
          <linear_acceleration>
            <x>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>1.7e-2</stddev>
                <bias_mean>0.1</bias_mean>
                <bias_stddev>0.001</bias_stddev>
              </noise>
            </x>
            <y>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>1.7e-2</stddev>
                <bias_mean>0.1</bias_mean>
                <bias_stddev>0.001</bias_stddev>
              </noise>
            </y>
            <z>
              <noise type="gaussian">
                <mean>0.0</mean>
                <stddev>1.7e-2</stddev>
                <bias_mean>0.1</bias_mean>
                <bias_stddev>0.001</bias_stddev>
              </noise>
            </z>
          </linear_acceleration>
        </imu>
      </sensor>
    </gazebo>

<gazebo reference="imu_link">

  • reference="imu_link":指定这个配置是针对机器人模型中的 imu_link 链接。imu_link 是机器人模型中用于表示 IMU 传感器位置和方向的虚拟链接。

<sensor name="imu_sensor" type="imu">

  • name="imu_sensor":传感器的名称,这里是 imu_sensor

  • type="imu":传感器的类型,这里是 IMU(惯性测量单元)。

<plugin filename="libgazebo_ros_imu_sensor.so" name="imu_plugin">

  • filename="libgazebo_ros_imu_sensor.so":指定插件的共享库文件名。这个文件是 Gazebo 和 ROS 之间的桥梁,用于将 IMU 数据发布到 ROS 话题。

  • name="imu_plugin":插件的名称,这里是 imu_plugin

<ros>

  • <namespace>/</namespace>:ROS 命名空间,默认为根命名空间 /

  • <remapping>~/out:=imu</remapping>:将插件内部的 ~/out 话题重映射为 ROS 的 imu 话题。这意味着插件会将 IMU 数据发布到 /imu 话题。

<initial_orientation_as_reference>false</initial_orientation_as_reference>

  • false:表示不将初始方向作为参考方向。这意味着 IMU 数据将直接反映传感器的绝对方向,而不是相对于初始方向的变化。

<always_on>true</always_on>

  • true:表示传感器始终处于开启状态。

<update_rate>100</update_rate>

  • 100:传感器的更新频率,单位为 Hz。这里设置为每秒更新 100 次。

<visualize>true</visualize>

  • true:表示在 Gazebo 的可视化窗口中显示传感器的模型。

<imu>

  • <angular_velocity>:定义角速度的噪声特性。

    • <x><y><z>:分别定义绕 x、y、z 轴的角速度噪声。

    • <noise type="gaussian">:噪声类型为高斯噪声。

      • <mean>:噪声的均值,这里是 0.0。

      • <stddev>:噪声的标准差,这里是 2e-4。

      • <bias_mean>:偏置的均值,这里是 0.0000075。

      • <bias_stddev>:偏置的标准差,这里是 0.0000008。

  • <linear_acceleration>:定义线性加速度的噪声特性。

    • <x><y><z>:分别定义沿 x、y、z 轴的线性加速度噪声。

    • <noise type="gaussian">:噪声类型为高斯噪声。

      • <mean>:噪声的均值,这里是 0.0。

      • <stddev>:噪声的标准差,这里是 1.7e-2。

      • <bias_mean>:偏置的均值,这里是 0.1。

      • <bias_stddev>:偏置的标准差,这里是 0.001。

将上面的代码加到fishbot_gazebo.urdf中,接着我们就可以进行测试了。

编译测试

colcon build --packages-select fishbot_description
source install/setup.bash

运行

ros2 launch fishbot_description gazebo.launch.py

查看话题

ros2 topic list
ros2 topic info /imu

输出话题

ros2 topic echo /imu

用rqt可视化

总结

本节我们对IMU传感器进行介绍,并通过gazbeo的imu插件完成了fishbot的IMU数据的输出。

最后还有小练习等着你:

  1. 再次启动遥控节点,控制fishbot,观察IMU传感器的数据变化