注意:

  • 再学习本系列教程时,应该已经安装过ROS了并且需要有一些ROS的基本知识

ubuntu版本:20.04
ros版本:noetic

课程回顾

ROS1结合自动驾驶数据集Kitti开发教程(一)Kitti资料介绍和可视化
ROS1结合自动驾驶数据集Kitti开发教程(二)发布图片
ROS1结合自动驾驶数据集Kitti开发教程(三)发布点云数据
ROS1结合自动驾驶数据集Kitti开发教程(四)画出自己车子模型以及照相机视野

前言

自动驾驶车辆必备数据IMU将会在这章教程中发布出来。

1.数据分析

在之前的教程中分别使用到了相机图片数据和激光雷达点云数据,他们都是使用不同的文件进行数据封装的。这次的IMU数据是在oxts文件夹下,每一帧的数据都存放在.txt文件中,每一个文件中装有30种类型的数据,详见kitti_doc

  - lat:     latitude of the oxts-unit (deg)
  - lon:     longitude of the oxts-unit (deg)
  - alt:     altitude of the oxts-unit (m)
  - roll:    roll angle (rad),  0 = level, positive = left side up (-pi..pi)
  - pitch:   pitch angle (rad), 0 = level, positive = front down (-pi/2..pi/2)
  - yaw:     heading (rad),     0 = east,  positive = counter clockwise (-pi..pi)
  - vn:      velocity towards north (m/s)
  - ve:      velocity towards east (m/s)
  - vf:      forward velocity, i.e. parallel to earth-surface (m/s)
  - vl:      leftward velocity, i.e. parallel to earth-surface (m/s)
  - vu:      upward velocity, i.e. perpendicular to earth-surface (m/s)
  - ax:      acceleration in x, i.e. in direction of vehicle front (m/s^2)
  - ay:      acceleration in y, i.e. in direction of vehicle left (m/s^2)
  - az:      acceleration in z, i.e. in direction of vehicle top (m/s^2)
  - af:      forward acceleration (m/s^2)
  - al:      leftward acceleration (m/s^2)
  - au:      upward acceleration (m/s^2)
  - wx:      angular rate around x (rad/s)
  - wy:      angular rate around y (rad/s)
  - wz:      angular rate around z (rad/s)
  - wf:      angular rate around forward axis (rad/s)
  - wl:      angular rate around leftward axis (rad/s)
  - wu:      angular rate around upward axis (rad/s)
  - posacc:  velocity accuracy (north/east in m)
  - velacc:  velocity accuracy (north/east in m/s)
  - navstat: navigation status
  - numsats: number of satellites tracked by primary GPS receiver
  - posmode: position mode of primary GPS receiver
  - velmode: velocity mode of primary GPS receiver
  - orimode: orientation mode of primary GPS receiver

2.发布IMU数据

2.1IMU插件

rviz_imu_plugin
首先确保已经安装了Rvizimu插件,使用如下命令查看并安装:

$ sudo apt install ros-noetic-rviz-imu-plugin

安装完成后可以再rviz->add窗口内看到imu插件。

2.2源码

# 给每一帧的数据集的每列加上列名
IMU_NAME = ["lat", "lon", "alt", "roll", "pitch", "yaw", "vn", "ve", "vf", "vl", "vu", "ax", "ay", "az", "af", "al", "au", "wx", "wy", "wz", "wf", "wl", "wu", "posacc", "velacc", "navstat", "numsats", "posmode", "velmode", "orimode"]

def publish_imu(num,imu_pub):
    # 使用pandas数据处理模块载入txt文件
    imu_data = pd.read_csv(os.path.join(BASE_PATH, "oxts/data/%010d.txt"%num), header=None, sep=" ")
    imu_data.columns = IMU_NAME
    imu = Imu()

    imu.header.frame_id = "map"
    imu.header.stamp = rospy.Time.now()

    # 从imu获取四元数
    q = transformations.quaternion_from_euler(float(imu_data.roll), float(imu_data.pitch), float(imu_data.yaw))
    imu.orientation.x = q[0]
    imu.orientation.y = q[1]
    imu.orientation.z = q[2]
    imu.orientation.w = q[3]
    # 线速度
    imu.linear_acceleration.x = imu_data.af
    imu.linear_acceleration.y = imu_data.al
    imu.linear_acceleration.z = imu_data.au
    # 角速度
    imu.angular_velocity.x = imu_data.wx
    imu.angular_velocity.y = imu_data.wy
    imu.angular_velocity.z = imu_data.wz

    imu_pub.publish(imu)

3.效果

在Rviz中加上IMU数据节点,如下所示配置:

最后的效果如下所示:

结语

本文也是基于笔者的学习和使用经验总结的,主观性较强,如果有哪些不对的地方或者不明白的地方,欢迎评论区留言交流~

为了能和读者进一步讨论问题,建立了一个微信群,方便给大家解答问题,也可以一起讨论问题。
加群链接
✌Bye