AirSim笔记8:面向SLAM任务的AirSim双目相机、IMU、LiDAR多传感器数据采集方案

Nov 13,2023   41835 words   150 min

Tags: Simulation

本篇博客我们重点记录利用AirSim仿真环境进行多传感器数据(Camera、LiDAR、IMU)采集的完整流程和注意事项,方便以后查阅。 在之前的这篇笔记中我们初步介绍了利用AirSim进行双目相机、IMU、LiDAR等多模态数据的采集。但如果从SLAM的角度,其中其实有一些小问题。一个比较关键的就是帧率问题。对于双目相机,采用之前方法采集的帧率偏低,而且非常不稳定。尤其对于IMU,采集的帧率过低(和双目帧率差不多),无法直接用于SLAM。而且,在之前的笔记中并没有给出明确的多传感器之间的外参。在这篇笔记中,我们将重点从帧率和传感器参数这两个方面进行介绍。

1.不同多传感器采集方案比较与分析

1.1 方案分析

前面也提到了,AirSim数据采集的一个潜在问题就是帧率过低(对SLAM而言),相机可能只有7、8帧左右,IMU只有大约30帧。而且相机数据还存在帧率不稳定的情况。这个问题在之前这篇笔记中有进行过简单讨论,但当时并没有真正解决。导致以上这些现象的原因有多种,包括硬件算力不足、同时采集的数据量过大、数据保存速度过慢等。这样的数据虽然是采集下来了,但是对SLAM运行没有实际价值。因此我们以双目相机、IMU、LiDAR同时采集为目标,重点讨论真正对SLAM可用的AirSim数据采集方案。

如果说帧率不稳定以及慢是由于性能不足或者数据量过大导致的,一个显而易见的解决方案就是从硬件下手,换更强的设备。但事实上,经过测试,更强的设备确实可以在一定程度上提升帧率。但是对于相机帧率不稳定的问题没有任何效果。即使将双目变成单目,缩小影像分辨率,对于帧率不均匀的情况依旧没有改善。不能指望直接用AirSim录制的相机数据帧率是稳定的。因此,更换硬件这个方案就被排除了。

剩下的就是软件层面解决。根据这个网页的描述,似乎可以通过修改settings.json配置文件中的ClockSpeed来调整帧率,但是经过我实际测试似乎没有效果,所以该方法被pass。我们提出新的方案,核心解决思路就是:保证轨迹相同,各模态数据分次采集。每次采集一两个数据,减少计算量。比如一次采集IMU、一次采集LiDAR,一次采集双目相机。 那么如何控制每次轨迹相同就成了新的问题。目前我们在场景中采集数据都是手动控制的。如果多次采集,显然我们没法保证每次采集的轨迹都是完全一样的。首先,根据我们之前的知识,有以下几种理论上行得通的方案:

  • 方案一:利用键盘鼠标录制软件录制键盘操作,然后下次采集的时候回放,保证每次轨迹相同。比如使用这款按键精灵
  • 方案二:利用Python脚本通过pynput库自己监听键盘操作,然后下次采集的时候回放,保证每次轨迹相同。我把提写好的录制播放键盘事件的脚本放到了Github,感兴趣可以参考。
  • 方案三:利用AirSim提供的airsim.CarControls()API控制小车运动,保证每次轨迹相同。如果想了解,可以参考官方给的一个示例脚本

然而这三种方案经过实际测试,各有各的问题:

  • 方案一问题:经过实际测试,录制以后播放的键盘操作和实际真实操作有较大差异,导致小车轨迹完全不对,而且有明显延时。猜测原因是因为操作小车对于键盘事件的监听灵敏度是很高的,普通操作也许还可以,但这种情况就满足不了了。
  • 方案二问题:本质上和方案一是一样的,只是录制的方式不同。结果还是不能用,和真实轨迹差异很大。原因也是和方案一相同。
  • 方案三问题:方案三在一定程度上确实可以实现对小车运动的控制,进而保证每次运动的轨迹都是相同的。但它的问题在于,AirSim支持的对小车的控制都很简单,这就导致这样的运动很难用于SLAM中IMU的激活和初始化。并且,在AirSim中,只提供了对于小车的控制接口,不直接支持对无人机的控制(当然不嫌麻烦你可以自己写,比如我们之前写的控制无人机的脚本)。

此外,即使不考虑IMU需要的运动充分性,就按照方案三进行数据采集,另一个很头疼的问题是时间对齐。由于不同数据是在不同时刻采集的,要实现精准的时间对齐几乎不可能。一个可能的解决办法是(只是理论上可行,我没试过,也没必要尝试,后面会介绍更优雅的方法):当采集完成后利用client.reset()函数重置设备状态。这样在保存的数据中,我们找到数据突变的那一个时刻,作为参考,从后往前进行对齐。 因此,总体而言,这三种方案都无法满足我们高帧率、多模态数据采集需求。

1.2 可行方案

正当一筹莫展的时候,Github上一个Issue的回答给了我新的思路,他说:单独采集IMU其实帧率是挺高的,但当和其它数据一起的时候,帧率就会降低。我在电脑上试了一下,确实如此。因此他的做法是先单独采集IMU和轨迹真值,然后基于轨迹真值再逐个采集影像数据。这个思路其实和我们之前的方法是一样的,都是将采集任务分解。但不同之处在于,他通过保存轨迹真值,后期逐个遍历位姿,在该位姿上采集;我们则是想保存控制运动的这个操作。显然,相比于我们的方法,前者更有效一些。

因此,进一步明确我们要采集的数据,包括:位姿真值、左影像、右影像、IMU观测、LiDAR点云。经过测试,一个真正有效、高帧率、多模态的数据采集方案如下:

  • 第一步,手动控制小车或者无人机运动,利用AirSim API保存位姿真值和IMU观测。
  • 第二步,利用AirSim API将小车或者无人机依次设置到每个位姿真值,在该状态下同时采集左影像、右影像和LiDAR点云,完成多模态数据采集任务。

这里有几个值得注意的小点:(1) 我们其实是将要采集的数据分为了内感受型和外感受型两种。位姿真值和IMU观测是和外界无关的,所以他们放在一起进行采集。而双目影像、LiDAR点云是和外界紧密相关的,应该放在一起采集。(2) 当然你可能会说,既然都分开了,每次的轨迹也相同,为什么不一次采集左影像、一次采集右影像,最后采集LiDAR点云呢?理论上确实可以,但是有漏洞。前面说了,他们三个都属于外感受型数据,反映外部环境。尽管我们可以保证每次运行轨迹相同,但无法保证每次运行的场景不会变化。比如在AirSim自带的城市场景中,有非常多的运动车辆,而且每次运行车辆是随机的。如果说将他们分开采集,结果可能就是,左影像中有一辆车但右影像上找不到,而LiDAR数据中又有一个新的车。这显然是有问题的。所以他们三者需要在同一环境下同时采集。

明确了总的思路以后,下面就是技术细节了(当然也会遇到各种奇怪的问题)。

2.LVI多传感器数据采集技术实现

2.1 第一步

首先是第一步,手动控制小车或无人机运动,并保存位姿真值和IMU观测。当然,正如前面笔记说的,AirSim中最重要的其实是settings.json文件的配置。在第一步中,我们用到的文件内容如下(以无人机为例)。

{
    "SeeDocsAt": "https://microsoft.github.io/AirSim/settings/",
    "SettingsVersion": 1.2,
  
    "SimMode": "Multirotor",
  
     "Vehicles": {
        "Ours": {
            "VehicleType": "SimpleFlight",
            "AutoCreate": true,
            "Sensors": {
              "Imu": {
                "SensorType": 2,
                "Enabled" : true,
                "AngularRandomWalk": 0.3,
                "GyroBiasStabilityTau": 500,
                "GyroBiasStability": 4.6,
                "VelocityRandomWalk": 0.24,
                "AccelBiasStabilityTau": 800,
                "AccelBiasStability": 36,
                "X": 0, "Y": 0, "Z": -1,
                "Roll": 0, "Pitch": 0, "Yaw" : 0
                }
            },
               
               "//": "这下面的表示我们搭建的这个平台的位置与姿态",
               "X": 0, "Y": 0, "Z": 0,
              "Pitch": 0, "Roll": 0, "Yaw": 0
            }
      }
  }

如果是小车的话,SimMode应为Car,VehicleType为PhysXCar。为了方便,第一步骤用到的无人机文件小车文件都上传到了Github。

2.1.1 控制机器人运动

在前面的笔记中说过,对于小车,直接键盘方向键就可以控制。而无人机麻烦一些,不过之前也写好了代码,拿来用就好。这里为了方便,将代码再贴过来。同时也上传到了Github,点击查看

# coding=utf-8
import keyboard
import airsim


def callBackFunc(x):
    w = keyboard.KeyboardEvent('down', 28, 'w')             # 前进
    s = keyboard.KeyboardEvent('down', 28, 's')             # 后退
    a = keyboard.KeyboardEvent('down', 28, 'a')             # 左移
    d = keyboard.KeyboardEvent('down', 28, 'd')             # 右移
    up = keyboard.KeyboardEvent('down', 28, 'up')           # 上升
    down = keyboard.KeyboardEvent('down', 28, 'down')       # 下降
    left = keyboard.KeyboardEvent('down', 28, 'left')       # 左转
    right = keyboard.KeyboardEvent('down', 28, 'right')     # 右转
    k = keyboard.KeyboardEvent('down', 28, 'k')             # 获取控制
    l = keyboard.KeyboardEvent('down', 28, 'l')             # 释放控制

    if x.event_type == 'down' and x.name == w.name:
        # 前进
        client.moveByVelocityBodyFrameAsync(3, 0, 0, 0.5)
        print("前进")
    elif x.event_type == 'down' and x.name == s.name:
        # 后退
        client.moveByVelocityBodyFrameAsync(-3, 0, 0, 0.5)
        print("后退")
    elif x.event_type == 'down' and x.name == a.name:
        # 左移
        client.moveByVelocityBodyFrameAsync(0, -2, 0, 0.5)
        print("左移")
    elif x.event_type == 'down' and x.name == d.name:
        # 右移
        client.moveByVelocityBodyFrameAsync(0, 2, 0, 0.5)
        print("右移")
    elif x.event_type == 'down' and x.name == up.name:
        # 上升
        client.moveByVelocityBodyFrameAsync(0, 0, -0.5, 0.5)
        print("上升")
    elif x.event_type == 'down' and x.name == down.name:
        # 下降
        client.moveByVelocityBodyFrameAsync(0, 0, 0.5, 0.5)
        print("下降")
    elif x.event_type == 'down' and x.name == left.name:
        # 左转
        client.rotateByYawRateAsync(-20, 0.5)
        print("左转")
    elif x.event_type == 'down' and x.name == right.name:
        # 右转
        client.rotateByYawRateAsync(20, 0.5)
        print("右转")
    elif x.event_type == 'down' and x.name == k.name:
        # 无人机起飞
        # get control
        client.enableApiControl(True)
        print("get control")
        # unlock
        client.armDisarm(True)
        print("unlock")
        # Async methods returns Future. Call join() to wait for task to complete.
        client.takeoffAsync().join()
        print("takeoff")
    elif x.event_type == 'down' and x.name == l.name:
        # 无人机降落
        client.landAsync().join()
        print("land")
        # lock
        client.armDisarm(False)
        print("lock")
        # release control
        client.enableApiControl(False)
        print("release control")
    else:
        # 没有按下按键
        client.moveByVelocityBodyFrameAsync(0, 0, 0, 0.5).join()
        client.hoverAsync().join()  # 第四阶段:悬停6秒钟
        print("悬停")


if __name__ == '__main__':
    # 建立脚本与AirSim环境的连接
    client = airsim.MultirotorClient()
    client.confirmConnection()

    # 监听键盘事件,执行回调函数
    keyboard.hook(callBackFunc)
    keyboard.wait()
2.1.2 获取IMU观测

在之前这篇笔记中,其实我们已经介绍过如何获取IMU数据,核心就是client.getImuData()函数。这里为了方便,再贴过来(以无人机为例):

# coding=utf-8
import airsim
import os


def parseIMU(imu_data):
    angular_velocity = imu_data.angular_velocity
    linear_acceleration = imu_data.linear_acceleration
    orientation = imu_data.orientation
    time_stamp = imu_data.time_stamp

    # 参考EuRoC IMU数据格式
    data_item = [str(time_stamp),
                 str(angular_velocity.x_val),
                 str(angular_velocity.y_val),
                 str(angular_velocity.z_val),
                 str(linear_acceleration.x_val),
                 str(linear_acceleration.y_val),
                 str(linear_acceleration.z_val)]
    return data_item

def saveData(out_path, measurements):
    print("Saving recorded data ...")
    fout = open(out_path, "w")

    fout.write("# timestamp(ns),"
               " gyro_x(rad/s), gyro_y(rad/s), gyro_z(rad/s),"
               " accel_x(m/s^2), accel_y(m/s^2), accel_z(m/s^2)\n")

    for i in range(len(measurements)):
        data_item = parseIMU(measurements[i])
        fout.write(data_item[0] + "," +
                       data_item[1] + "," +
                       data_item[2] + "," +
                       data_item[3] + "," +
                       data_item[4] + "," +
                       data_item[5] + "," +
                       data_item[6] + "\n")
    
    fout.close()
    print("Saved record file:", out_path)

def isDirExist(path='output'):
    if not os.path.exists(path):
        os.makedirs(path)
        return False
    else:
        return True


if __name__ == '__main__':
    raw_measurements = []
    out_dir = "./data-imu/"
    isDirExist(out_dir)

    try:
        # 连接到AirSim模拟器
        client = airsim.MultirotorClient()
        client.confirmConnection()
        
        print("Recording IMU data ...\nPress Ctrl + C to stop.")

        last_timestamp = 0

        # 循环读取数据
        while True:
            # 通过getImuData()函数即可获得IMU观测
            # 返回结果由角速度、线加速度、朝向(四元数表示)、时间戳(纳秒)构成
            imu_data = client.getImuData()
            cur_time_stamp = imu_data.time_stamp

            if cur_time_stamp != last_timestamp:
                raw_measurements.append(imu_data)
                last_timestamp = cur_time_stamp
    except KeyboardInterrupt:
        saveData(out_dir+"IMU.csv", raw_measurements)

对应Github上这个文件,小车则是这个文件

2.1.3 获取机器人位姿真值

在之前这篇笔记中提到airsim_rec.txt文件,里面存放了位姿真值。但这种方式还是有很大局限性,因为这个文件只会在你点击仿真界面中的Recording按钮才会生成。其实我们完全可以通过AirSim提供的API高效获取机器人位姿真值,核心是client.simGetVehiclePose()函数,代码如下(以无人机为例)。

# coding=utf-8
import airsim
import time
import os

def saveData(out_path, pose_gt, timestamps):
    fout = open(out_path, "w")
    print("Saving ground truth poses.")

    fout.write("#timestamp(ns), pos_x, pos_y, pos_z, quat_x, quat_y, quat_z, quat_w\n")
    for i in range(len(pose_gt)):
        cur_pose = pose_gt[i]
        cur_quat_w = cur_pose.orientation.w_val
        cur_quat_x = cur_pose.orientation.x_val
        cur_quat_y = cur_pose.orientation.y_val
        cur_quat_z = cur_pose.orientation.z_val

        cur_pos_x = cur_pose.position.x_val
        cur_pos_y = cur_pose.position.y_val
        cur_pos_z = cur_pose.position.z_val

        fout.write(str(timestamps[i])+","+
                   str(cur_pos_x)+","+str(cur_pos_y)+","+str(cur_pos_z)+","+
                   str(cur_quat_x)+","+str(cur_quat_y)+","+str(cur_quat_z)+","+str(cur_quat_w)+"\n")
    fout.close()

    print("Saved all gt poses:", out_path)

def isDirExist(path='output'):
    if not os.path.exists(path):
        os.makedirs(path)
        return False
    else:
        return True

if __name__ == '__main__':
    gt_poses = []
    timestamps = []

    try:
        out_dir = "./data-gt/"
        isDirExist(out_dir)

        # 连接到AirSim模拟器
        client = airsim.MultirotorClient()
        client.confirmConnection()

        print("Recording Pose GT data ...\nPress Ctrl + C to stop.")
        
        cur_timestamp = 0
        last_timestamp = 0
        
        # 循环读取数据
        while True:
            cur_pose = client.simGetVehiclePose()
            cur_timestamp = client.getMultirotorState().timestamp

            if cur_timestamp != last_timestamp:
                gt_poses.append(cur_pose)
                timestamps.append(cur_timestamp)
                last_timestamp = cur_timestamp
    
    except KeyboardInterrupt:
        saveData(out_dir+"/pose_gt.txt", gt_poses, timestamps)

代码上传到Github,点击查看,小车对应的代码是这个。在我电脑上,如果只是client.simGetVehiclePose()最高可以达到1000Hz,但加了client.getMultirotorState()以后,就到300Hz左右了。因为client.getMultirotorState()这个函数是获得机器人的动力学相关参数,因此稍微需要一些时间。而如果你注意观察会发现,其实这里我并没有用那些运动学参数,只是拿了他的时间戳。你可能会好奇,为什么不直接利用Python的time.time()获取时间戳,因为AirSim其实本身的仿真时间也是基于当前系统时间的。答案是他们之间有一定的时差,这会导致保存的位姿真值和IMU观测不对齐。更多解释可以参考这个官方文档。下面的图片简单展示了这一点。我们同时输出Python获得的时间、从getMultirotorState()获得的时间和IMU的时间。 可以看到最左边Python获取的系统时间和右边两个是有差异的,这种差异可能会给数据使用带来潜在风险。但通过getMultirotorState()获得的时间和IMU的时间是同步的。因此从数据准确性角度考虑,还是采用这种方式获得时间,尽管会牺牲一定的帧率(但其实300Hz也基本够用了)。当然你可能会好奇,我们能不能直接指定IMU帧率。目前来看是不行的。IMU帧率在AirSim的源码中被写死了,就是1000分之1秒,也就是1000Hz,可以参考这个源码。所以上面才说,最高可以达到1000Hz,是从这里来的。

至此,我们便采集好了IMU数据和位姿真值数据。在第二步中,我们就需要依靠这些数据,设置机器人位置,进行双目相机和LiDAR点云的采集。

2.2 第二步

第二步中核心问题是如何根据已有的位姿将机器人设置到该状态,以及双目、LiDAR数据的采集。这里还是,首先展示步骤二中用到的settings.json文件(以无人机为例)。和第一步用到的配置文件有所不同。

{
    "SeeDocsAt": "https://microsoft.github.io/AirSim/settings/",
    "SettingsVersion": 1.2,
  
    "SimMode": "Multirotor",
    "PhysicsEngineName":"ExternalPhysicsEngine",
  
     "Vehicles": {
        "Ours": {
            "VehicleType": "SimpleFlight",
            "AutoCreate": true,
            "Sensors": {
              "Imu": {
                "SensorType": 2,
                "Enabled" : true,
                "AngularRandomWalk": 0.3,
                "GyroBiasStabilityTau": 500,
                "GyroBiasStability": 4.6,
                "VelocityRandomWalk": 0.24,
                "AccelBiasStabilityTau": 800,
                "AccelBiasStability": 36,
                "X": 0, "Y": 0, "Z": -1,
                "Roll": 0, "Pitch": 0, "Yaw" : 0
                },
              "LidarSensor": {
                "SensorType": 6,
                  "Enabled" : true,
                  "NumberOfChannels": 32,
                  "RotationsPerSecond": 500,
                  "PointsPerSecond": 300000,
                  "VerticalFOVUpper": 30,
                  "VerticalFOVLower": -15,
                  "DrawDebugPoints": false,
                  "DataFrame": "SensorLocalFrame",
                  "range": 100,
                  "X": 0, "Y": 0, "Z": -1,
                  "Roll": 0, "Pitch": 0, "Yaw" : 0
               }
              },
  
              "Cameras": {
                "front_left": {
                  "CaptureSettings": [
                    {
                      "ImageType": 0,
                      "Width": 752,
                      "Height": 480,
                      "//": "这里的FOV主要指的是水平方向的角度,但事实上如果调整了这个角度,竖直方向视场角也会相应跟着变化",
                      "FOV_Degrees": 90
                    }
                  ],
                  "X": 0.35, "Y": -0.05, "Z": -0.1,
                  "Pitch": 0, "Roll": 0, "Yaw": 0
                },
                "front_right": {
                  "CaptureSettings": [
                    {
                      "ImageType": 0,
                      "Width": 752,
                      "Height": 480,
                      "FOV_Degrees": 90
                    }
                  ],
                  "X": 0.35, "Y": 0.05, "Z": -0.1,
                  "Pitch": 0, "Roll": 0, "Yaw": 0
                }
               },
               
               "//": "这下面的表示我们搭建的这个平台的位置与姿态",
               "X": 0, "Y": 0, "Z": 0,
              "Pitch": 0, "Roll": 0, "Yaw": 0
            }
      }
    
  }

该文件上传到了Github,点击查看。小车对应的文件则是这个。对参数文件的具体解释留到后面,这里暂时不介绍,只管用就好。

2.2.1 设置机器人位姿

在网上查阅了大量资料后发现,在AirSim中有一系列client.setXXXPose()函数可用于实现这个需求,比如client.simSetObjectPose()client.simSetCameraPose()client.simSetVehiclePose(),参见这个官方文档。在我们这个场景里主要用client.simSetVehiclePose()。因此,我们只需要读取上一步保存的位姿真值,再通过这个函数设置即可。理想总是很好,但现实会很麻烦。比如下面这一段代码就是实现这个功能的(以无人机为例)。

import airsim
import os
import numpy as np

def readGT(file_path):
    fin = open(file_path, "r")

    timestamps = []
    positions = []
    orientations = []
    poses = []

    line = fin.readline().strip()
    line = fin.readline().strip()

    while line:
        parts = line.split(",")

        ts = parts[0]
        pos_x = float(parts[1])
        pos_y = float(parts[2])
        pos_z = float(parts[3])

        quat_x = float(parts[4])
        quat_y = float(parts[5])
        quat_z = float(parts[6])
        quat_w = float(parts[7])

        cur_pos = airsim.Vector3r(pos_x, pos_y, pos_z)
        cur_ori = airsim.Quaternionr(quat_x, quat_y, quat_z, quat_w)

        timestamps.append(ts)
        positions.append(cur_pos)
        orientations.append(cur_ori)
        poses.append(airsim.Pose(cur_pos, cur_ori))

        line = fin.readline().strip()

    fin.close()
    return timestamps, positions, orientations, poses

def saveData(out_path, pose_gt, timestamps):
    fout = open(out_path, "w")
    print("Saving ground truth poses.")
    for i in range(len(pose_gt)):
        cur_pose = pose_gt[i]
        cur_quat_w = cur_pose.orientation.w_val
        cur_quat_x = cur_pose.orientation.x_val
        cur_quat_y = cur_pose.orientation.y_val
        cur_quat_z = cur_pose.orientation.z_val

        cur_pos_x = cur_pose.position.x_val
        cur_pos_y = cur_pose.position.y_val
        cur_pos_z = cur_pose.position.z_val

        fout.write(str(timestamps[i])+","+
                   str(cur_pos_x)+","+str(cur_pos_y)+","+str(cur_pos_z)+","+
                   str(cur_quat_x)+","+str(cur_quat_y)+","+str(cur_quat_z)+","+str(cur_quat_w)+"\n")
    fout.close()

def isDirExist(path='output'):
    if not os.path.exists(path):
        os.makedirs(path)
        return False
    else:
        return True

if __name__ == '__main__':
    # parameters for proper data collection
    gt_pose_path = "./data-gt/pose_gt.txt"
    stereo_out_dir = "./data-cam/"
    lidar_out_dir = "./data-lidar/"
    stereo_interval = 15
    lidar_interval = 30

    isDirExist(stereo_out_dir)
    isDirExist(lidar_out_dir)

    # step1. load gt trajectory
    print("loading gt poses ...")
    timestamps, positions, orientations, poses = readGT(gt_pose_path)
    print("successfully loaded "+str(len(poses))+ " gt poses in total.")
    
    # step2. link to airsim simulator
    client = airsim.VehicleClient()
    client.confirmConnection()

    stereo_images = []
    stereo_timestamps = []
    lidar_points = []
    lidar_timestamps = []

    airsim.wait_key('Press any key to start stereo and lidar collection')
    print("Start to record stereo data ...")

    # step3. start to collect data in airsim
    for x in range(0, len(poses)):
        # step3.1 set the vehicle pose
        client.simSetVehiclePose(airsim.Pose(positions[x], orientations[x]), True)

        # step3.2 collect stereo data if the current time is wanted
        if x % stereo_interval == 0:
            responses = client.simGetImages([
                airsim.ImageRequest("front_left", airsim.ImageType.Scene),
                airsim.ImageRequest("front_right", airsim.ImageType.Scene)])
            stereo_images.append(responses)
            stereo_timestamps.append(timestamps[x])
            print("progress", x+1, "/", len(poses))
        
        # step3.3 collect lidar data if the current time is wanted
        if x % lidar_interval == 0:
            lidar_data = client.getLidarData()
            lidar_points.append(lidar_data.point_cloud)
            lidar_timestamps.append(timestamps[x])

    # step4 output collected data
    # step4.1 stereo images
    fout_stereo = open(stereo_out_dir + "/timestamps.txt", "w")
    isDirExist(stereo_out_dir + "/cam_left/")
    isDirExist(stereo_out_dir + "/cam_right/")
    for i in range(len(stereo_images)):
        image_left = stereo_images[i][0]
        image_right = stereo_images[i][1]

        airsim.write_file(os.path.normpath(stereo_out_dir + "/cam_left/" + stereo_timestamps[i] + '.png'), image_left.image_data_uint8)
        airsim.write_file(os.path.normpath(stereo_out_dir + "/cam_right/" + stereo_timestamps[i] + '.png'), image_right.image_data_uint8)
        fout_stereo.write(stereo_timestamps[i] + "\n")

        print("stereo images: ", i+1, "/", len(stereo_images))
    fout_stereo.close()

    # step4.2 lidar points
    fout_lidar = open(lidar_out_dir+"/timestamps.txt", "w")
    for i in range(len(lidar_points)):
        np.save(lidar_out_dir + lidar_timestamps[i], lidar_points[i])
        fout_lidar.write(lidar_timestamps[i] + "\n")

        print("lidar points: ", i+1, "/", len(lidar_points))
    fout_lidar.close()

代码上传到了Github,点击查看。小车的对应文件在这里

但有问题,运行以后,无人机就会像奇行种一样反复横跳。 毫无疑问,它拍出来的照片可想而知了。但是整个双目数据、LiDAR点云都是可以正常采集的。而且各个传感器之间的相对关系都是按照配置文件里设置的。唯一美中不足的就是这个“反复横跳”的毛病。之所以会出现这种反复横跳的原因就在于,整个仿真环境中有真实的物理引擎。当我们把无人机人为设置到某个位姿之后,由于受重力作用,无人机会自然下落。由于在代码中是通过for循环实现的,如果每次循环时间都很快,那么几乎不会给无人机下落的时间,看起来还算比较平滑。可是一旦循环比较耗时,比如上上面代码中获取数据,那么获取数据的这段时间,无人机就会自动下落,直到下一次设置位姿。因此,这就挺无语的。必须要想其它办法。

而在AirSim中,还提供了另一种模式,叫ComputerVision。在这种模式下,物理引擎是被禁用的。所以我们自然就想到,为什么不在ComputerVision模式下采集数据呢?关于ComputerVision模式,在这个官方文档中有介绍。简单来说就是,在这个模式中,物理引擎会被禁用,并且没有机器人,只有相机。通过键盘操作相机的运动。为了开启这个模式,我们需要修改settings.json文件中的SimMode字段,改为ComputerVision。官方也给了一个利用Python API移动相机并获取影像的小例子。ComputerVision模式运行效果如下。 看起来一切都很好,没有重力的影响,也可以采集数据。然而这里依然有很多问题。首先是我们要采集双目数据,而在ComputerVision模式中,根据官方文档描述,双目的基线长度是固定的,25cm,无法更改。这显然是不行的。否则我们前面在配置文件里搭建的传感器就没有作用了。不仅如此,现阶段在ComputerVision模式下,经过实际测试和网上资料查找,我们无法采集LiDAR数据。因此,尽管ComputerVision模式可以禁用物理引擎,使得无人机设置位姿以后不会往下掉,但又难以采集我们需要的双目和LiDAR数据,ComputerVision模式就基本被淘汰了。当然了,如果你只是单纯采集单目数据,ComputerVision也许是很好的选择。

这样,我们就不得不又回到普通的模式。我们想要的其实很简单,无人机因为有重力的存在所以一直往下掉。那如果把重力去掉或者让重力为0就可以了,就像Isaac Sim中的零重力模式一样。然而,很可惜,经过查找,在AirSim中并不支持零重力模式,除非你修改AirSim源码。因此这个想法又不行了。就这样苦苦寻觅,沿着禁用物理引擎的思路不断寻找。终于,在一个Github的Issue里找到了PhysicsEngineNameExternalPhysicsEngine这两个关键词。通过设置这个属性,可以关闭AirSim中的物理引擎。沿着这个线索进一步搜寻在官方文档中找到了进一步描述。对于小车,目前AirSim只支持PhysX物理引擎。而对于无人机,支持FastPhysicsEngine和ExternalPhysicsEngine两种模式。在我电脑上经过实际测试,无人机会显著比小车运行要流畅一些。因此,如果没有特殊需求,可以考虑优先用无人机采集数据。在ExternalPhysicsEngine模式中,无人机是“一令一动”,不会在设置位姿以后因为重力的影响掉下来。而这正是我们需要的功能。而且文档中也确实提到“It is especially useful for moving the AirSim drone using an external simulator or on a saved path”。而到底如何使用呢?也很简单。在settings.json配置文件中加上一句"PhysicsEngineName":"ExternalPhysicsEngine"即可。 这样,我们再运行上面的代码,无人机就再也不会往下掉了,如下。 这样,我们就圆满完成了第二步中的第一部分。

2.2.2 采集双目与LiDAR数据

其实在2.2.1部分的代码中,已经写了双目与LiDAR数据采集的部分。对于双目数据,核心是client.simGetImages()函数,对于LiDAR,核心是client.getLidarData()函数。这一部分之前笔记中都有提到过,此处不再赘述。稍微和之前不同的是,之前我们基本都是用AirSim自带的Recording功能进行影像数据的获取,无论是单目还是双目。但事实上,这样是非常局限的。所以在这里我们采用了AirSim的API来获取,关于client.simGetImages()函数这个函数的更多用法可以参考官方文档。而且如果你对2.2.1部分代码看得比较细心的话,会有这么几个发现:

  • 我们不再依靠AirSim实时采集影像数据(尽管这种方法最简单,但对更高的需求来说是不够的),而是根据已有的位姿真值通过事后的方式离线采集。这样做的好处就是可以有效避免数据帧率分布不均。因为前面提到了,无论是单目还是双目,也无论硬件好坏,只要是实时采集,AirSim输出的相机帧率都是不稳定的。因此,我们没必要非要实时采集,而是多次、离线采集。
  • 我们并非每个位姿都采集了数据,而是根据不同的采集间隔进行了稀疏化。这样做的目的也是显而易见的。在我电脑上,位姿真值的帧率约为300Hz,显然我们是没有必要遍历每个位姿进行数据采集的。一般视觉20帧、LiDAR 10帧就差不多了。所以我们给他们设置的间隔分别是15和30。
  • 在数据采集的全部过程中,我们没有从其它地方获得新的时间戳,而是使用位姿真值里的时间戳。这也是可以理解的。如果我们又新获取了一套时间戳,那么还需要有额外的时间戳对齐步骤才可以,很麻烦。而这种方式可以巧妙地解决时间戳对齐问题,也不会影响数据帧的分布情况,导致分布不均。
  • 我们才采集数据的时候,并没有采集一帧就保存一帧。而是先全部放到内存里,等采集完成以后再统一写入硬盘。这样做的好处就是可以减少每次循环的时间。虽说现在使用了ExternalPhysicsEngine模式以后,我们无需担心采集的时候无人机掉下来的问题。但如果每次采集的时间过长,场景中的内容也有可能发生变化,导致潜在问题。毕竟禁用的只是无人机的物理引擎,整个场景其它物体的物理引擎,甚至运动物体还是在的。

至此,我们就圆满完成了利用AirSim进行高帧率、LVI多模态数据采集的全过程。当然你也可以基于我们之前写好的序列质量评价脚本对数据“评头论足”一下。比如利用上面的脚本采集的数据帧率如下。 可以看到,帧率还是不错的,符合预期。同时数据的分布也是比较均匀的。上面的评价结果是用这个脚本实现的。最后,用到的所有文件都上传到了Github,点击查看,欢迎Star或Fork。

3.数据采集完整步骤总结

在这一部分我们再简略回顾一下完整的数据采集流程。

  • 在AirSim Github项目网页下载AirSim仿真环境可执行文件。下载本文的数据采集工具包
  • 根据需要选择需要运行的仿真环境,先运行一下,看看环境,然后关闭。思考想要跑的设备(小车还是无人机)。
  • 在下载的工具包中,找到对应的文件夹中的settings-step1.json文件。比如选择无人机,则是vehicle-drone/settings-step1.json。打开该文件,根据需要修改相应参数。
  • 修改完成以后,将该文件拷贝到AirSim默认的工作路径,并把名字修改为settings.json。比如我的电脑上就是C:\Users\admin\Documents\AirSim\settings.json
  • 打开仿真环境,并且在工具包的vehicle-drone路径下打开终端,输入python step1.getImuDataV3.py。再打开一个终端,输入step1.getVehiclePoseGT.py。分别输入回车,即可开始录制IMU和位姿真值数据。
  • 操控平台在环境中移动,采集数据。对于小车,直接用方向键控制。如果是无人机,则在工具包根目录下打开终端,然后输入python tool_drone_control.py,并回车。按k键连接无人机,完成以后就可以利用w、s控制前进后退,a、d控制左右平移,方向上、下键控制垂直上升或下降,方向左、右键控制左右旋转。
  • 按Ctrl+C,停止IMU、位姿真值录制、无人机控制。关闭仿真环境。
  • 在下载的工具包中,找到对应的文件夹中的settings-step2.json文件。比如选择无人机,则是vehicle-drone/settings-step2.json。打开该文件,根据需要修改相应参数。
  • 修改完成以后,将该文件拷贝到AirSim默认的工作路径,并把名字修改为settings.json。比如我的电脑上就是C:\Users\admin\Documents\AirSim\settings.json
  • 打开仿真环境,并且在工具包的vehicle-drone路径下打开终端,输入python step2.getStereoAndLidarData.py并回车。AirSim就会重播刚刚的轨迹,并采集双目和LiDAR数据。

通过以上步骤,我们便完成了在AirSim里的多模态数据采集。

4.多传感器的内外参

在数据采集完成之后,我们还差一步就可以拿去跑SLAM了。那就是传感器之间的内外参。作为仿真环境,其实相比于真实传感器而言,要更容易拿到这些数据(因为不用标定,可以手动设置或者根据配置文件计算即可)。因此,这部分主要介绍AirSim中各传感器的内外参该如何获得。

4.1 传感器内参
4.1.1 相机

根据我们之前的知识,相机内参包括焦距\((f_x, f_y)\)和主点\((c_x, c_y)\)。当然了,影像的长宽等参数在SLAM中同样也是需要的。在这一部分我们重点探讨AirSim中的相机内参如何获得。

答案是在settings.json配置文件中自己指定一些内参,然后根据确定的部分算出其它需要的内参。首先,根据官方文档,我们给出AirSim支持的所有相机参数配置和对应默认值,也加了一些注释方便更好理解(注意json文件不支持注释,所以如果要复制下面的属性使用,记得把注释删掉,不然会报错),如下。

"CameraDefaults": {

  // 和影像捕获有关的参数
  "CaptureSettings": [
    {
      "ImageType": 0,
      "Width": 256,
      "Height": 144,
      "FOV_Degrees": 90,
      "AutoExposureSpeed": 100,
      "AutoExposureBias": 0,
      "AutoExposureMaxBrightness": 0.64,
      "AutoExposureMinBrightness": 0.03,
      "MotionBlurAmount": 0,
      "TargetGamma": 1.0,
      "ProjectionMode": "",
      "OrthoWidth": 5.12
    }
  ],

  // 和影像噪声有关的参数
  "NoiseSettings": [
    {
      "Enabled": false,
      "ImageType": 0,

      "RandContrib": 0.2,
      "RandSpeed": 100000.0,
      "RandSize": 500.0,
      "RandDensity": 2,

      "HorzWaveContrib":0.03,
      "HorzWaveStrength": 0.08,
      "HorzWaveVertSize": 1.0,
      "HorzWaveScreenSize": 1.0,

      "HorzNoiseLinesContrib": 1.0,
      "HorzNoiseLinesDensityY": 0.01,
      "HorzNoiseLinesDensityXY": 0.5,

      "HorzDistortionContrib": 1.0,
      "HorzDistortionStrength": 0.002
    }
  ],

  // 云台稳像相关参数
  "Gimbal": {
    "Stabilization": 0,
    "Pitch": NaN, "Roll": NaN, "Yaw": NaN
  },

  // 相机的位置和姿态
  "X": NaN, "Y": NaN, "Z": NaN,
  "Pitch": NaN, "Roll": NaN, "Yaw": NaN,

  // 影像渲染相关的参数
  "UnrealEngine": {
    "PixelFormatOverride": [
      {
        "ImageType": 0,
        "PixelFormat": 0
      }
    ]
  }
}

可以看到,主要分为五类,大部分参数根据字面意思就能猜到他的作用。在实际使用中,我们一般不会全部设置这些参数。比如在上面的配置文件中,我们就只设置了CaptureSettings相关属性和相机的位置,其它默认,如下。

"Cameras": {
    "front_left": {
        "CaptureSettings": [
        {
            "ImageType": 0,
            "Width": 752,
            "Height": 480,
            "//": "这里的FOV主要指的是水平方向的角度,但事实上如果调整了这个角度,竖直方向视场角也会相应跟着变化",
            "FOV_Degrees": 90
        }
        ],
        "X": 0.35, "Y": -0.05, "Z": -0.1,
        "Pitch": 0, "Roll": 0, "Yaw": 0
    },
    "front_right": {
        "CaptureSettings": [
        {
            "ImageType": 0,
            "Width": 752,
            "Height": 480,
            "FOV_Degrees": 90
        }
        ],
        "X": 0.35, "Y": 0.05, "Z": -0.1,
        "Pitch": 0, "Roll": 0, "Yaw": 0
    }
}

可以看到,我们设置了影像类型为普通的RGB影像,影像的长宽分别是752、480,视场角为90度(水平)。那么如何根据这些指定的参数求解得到焦距和主点。根据这个网页这个网页这个网页的介绍,我们可以根据视场角计算出对应的焦距信息。在仿真环境中,我们认为水平和竖直方向上的焦距是相同的,因此\(f_x=f_y\)。而根据FOV计算焦距的公式如下:

\[f = f_x = f_y = \frac{width/2}{tan(fov/2)}\]

其中\(width\)和\(fov\)这两个参数都可以在参数文件中找到,因此就可以计算了。而主点的计算则是\(width\)和\(height\)的一半,如下。

\[\left\{\begin{matrix} c_x = \frac{width}{2} \\ c_y = \frac{height}{2} \end{matrix}\right.\]

根据上面设置的参数,结合公式,便可以计算出相机的焦距和主点,进而可以用来跑SLAM了。另外,AirSim中还支持相机畸变参数,默认都为0(\(k_1\), \(k_2\), \(k_3\), \(p_1\), \(p_2\)),可以通过Camera API设置(simSetDistortionParams函数和simGetDistortionParams函数),感兴趣可以进一步参考官方文档,这里简单列一下函数说明:

Set camera distortion parameters

Args:
    camera_name (str): Name of the camera, for backwards compatibility, ID numbers such as 0,1,etc. can also be used
    distortion_params (dict): Dictionary of distortion param names and corresponding values
                                {"K1": 0.0, "K2": 0.0, "K3": 0.0, "P1": 0.0, "P2": 0.0}
    vehicle_name (str, optional): Vehicle which the camera is associated with
    external (bool, optional): Whether the camera is an External Camera

另外,在Github的这个Issue中,作者在仿真环境中做了个标定板,这样便可以在仿真环境中基于Kalibr等实现整个标定过程,感兴趣可以尝试,也是一种方式。最后,以上面给定的相机参数为例,结算出对应的相机内参如下:

  • \(f_x\): 376
  • \(f_y\): 376
  • \(c_x\): 376
  • \(c_y\): 240
  • \(k_1\): 0
  • \(k_2\): 0
  • \(k_3\): 0
  • \(p_1\): 0
  • \(p_2\): 0
4.1.2 IMU

对于IMU,它的内参主要是它的一些噪声参数,主要包括四个:加速度计的随机游走和高斯白噪声,陀螺仪的随机游走和高斯白噪声,这在之前这篇笔记中也提到过。根据这个官方文档,AirSim中配置文件可以设置的参数以及其默认值如下:

"Imu": {
    "SensorType": 2,
    "Enabled" : true,
    "AngularRandomWalk": 0.3,
    "GyroBiasStabilityTau": 500,
    "GyroBiasStability": 4.6,
    "VelocityRandomWalk": 0.24,
    "AccelBiasStabilityTau": 800,
    "AccelBiasStability": 36
}

简单复习一下,根据之前的这篇笔记,对于陀螺仪而言,主要包含角度随机游走(Angle Random Walk, ARW)和偏置稳定性(Bias Stability)两种噪声。角度随机游走主要由热机械噪声影响,它的频率远比传感器的采样频率要高。导致的结果是角度积分引入一种零均值随机游走误差,其与时间的平方根成比例。而偏置稳定性则是主要由电子器件的闪变噪声影响,其会随时间发生变化,用于描述偏置随时间变化的情况。类似的,对于加速度计,也包含速度随机游走(Velocity Random Walk, VRW)和偏置稳定性(Bias Stability)两种噪声。因此,可以发现,在我们的配置文件中,恰好是分别都有对应的参数可以设置。当然如果你细心观察,会发现,常规这四个参数一般都在10的负几次方量级,比如EuRoC的IMU内参如下: 而在配置文件中,为什么这里都是看起来比较“奇怪”的数。这就需要从这些误差的物理意义说起了。

先说陀螺仪

根据前面介绍过的知识,陀螺仪的角度随机游走误差的标准差如下(根据姿态积分反推出来的):

\[\sigma _{\theta } (t) = \sigma \cdot \sqrt{\delta t \cdot t}\]

这里的\(\delta t\)表示两次观测之间的时间间隔,而\(t\)表示一段固定的时间,\(\sigma\)可以看做是一个常量。而\(\sigma _{\theta } (t)\)则表示从某时刻经过\(\delta t\)以后,角度随机游走误差的标准差。在实际应用中,我们可以把\(t\)设为1小时,也就是\(t=1\)。那么带入上面的公式,就得到:

\[\sigma _{\theta } (1) = \sigma \cdot \sqrt{\delta t \cdot 1} = \sigma \cdot \sqrt{\delta t}\]

在这个式子中,只有\(\delta t\)是变量。也就是说,只要我知道了常量\(\sigma\)是多少,就可以利用上式很容易求出其它时刻的角度误差了。 而且可以很显然的看出,角度随机游走噪声的标准差与时间的平方根成比例。根据公式也可以很容易得到这个标准差的物理单位。如果常量\(\sigma\)以角度来表示,\(\delta t\)以小时来表示,那么他的单位就是\(^{\circ}/\sqrt{hour}\)(度每根号小时)。这个单位在实际中是非常常用的。而上面提到的AngularRandomWalk是0.3恰恰就是表示这个意思,代表一小时以后角度误差的标准差为0.3,这就是他的物理意义。当然你可能会好奇,那之前看到的那些十的负几次方的数据是怎么算出来的?不用着急,我们可以思考一下,\(\sqrt{1\ hour}\)是0.3度,那么一小时是3600秒,也就是\(\sqrt{3600\ sec}\)是0.3度。那么每秒自然就是0.3度除以\(\sqrt{3600 sec}\),也就是\(\sigma/\sqrt{3600\ sec}\)。当然,如果你想,还可以把角度以弧度来表示,那就是在此基础上乘以\(\pi/180\)。所以同样是角度随机游走误差,但以弧度每根号秒表示就是如下:

\[\sigma _{\theta } (3600\ sec)= \frac{\sigma}{\sqrt{3600}}\cdot \frac{\pi}{180} \sqrt{\delta t} =\sigma_{sec}\cdot \sqrt{\delta t}\]

这里的\(\sigma\)就是一开始提到的角度,而\(\sigma_{sec}\)则是新的需要求解的参数,他和前面那两个分数部分是对应的。正如上面提到的,只要有了\(\sigma\)我就可以求得\(\delta t\)时间内的误差标准差。将上面配置文件中的AngularRandomWalk带入,可以算得新的\(\sigma_{sec}\)为8.726646259971648e-05。看到这个数字,你可能就觉得“亲切”了很多,是10的负几次方的样子了。事实上,在AirSim中,就是采用上面的方法计算的,这点可以在IMU实现的源文件中找到印证。 至此,陀螺仪角度随机游走噪声介绍完了。

然后就是陀螺仪的偏置稳定性误差。其实是类似的。根据之前笔记,偏置稳定性就是用于描述某个设备在一段时间内(比如100s)偏置的变化情况,一般用\(^{\circ}/h\)或\(^{\circ}/s\)做单位。比如在参数文件中就明确指明了GyroBiasStability为4.6。翻译一下就是,经过1小时,陀螺仪偏置的标准差为4.6度。而这里的另一个参数\(\tau\)则表示偏置稳定性定义的时间长度,或者可以理解为有效的时间。超过这个时间我就认为偏置估计可能不可靠了。在配置文件中GyroBiasStabilityTau为500。简单练习一下,比如这里我们把4.6度每小时转化为弧度每秒。那么数值计算就应该如下:

\[Bias\ Stability = \frac{4.6}{3600} \cdot \frac{\pi}{180}\]

经过计算,这个值为2.2301429331038652e-05。但是其实这样还不够彻底,不利于误差的推算。因为,我们同样可以把稳定性也建模成随机游走模型,那么就是如下公式:

\[BRW = \frac{Bias\ Stability}{\sqrt{\tau} }\cdot \sqrt{\delta t} = {BS}_{new}\cdot \sqrt{\delta t}\]

这里\(Bias\ Stability\)就是刚刚算出来的结果,但是还有个\(\tau\)(配置文件里已经指定了),所以我们把这个整体作为新的整体偏置稳定度进行计算,这样在使用的时候会更方便一些。和角度随机游走类似,我们只要知道\(\delta t\)就可以计算对应的偏置稳定性误差了。根据参数文件中给定的\(\tau = 500\)以及刚刚算出的\(Bias\ Stability\),可以很容易算出新的参数为9.973502395922016e-07。而这个计算方法在官方的IMU源码文件1源码文件2中同样也可以得到验证。比如,其中对观测增加误差的代码如下,就是按照上面提到的公式计算误差然后更新的:

real_T sqrt_dt = static_cast<real_T>(sqrt(std::max<TTimeDelta>(dt, params_.min_sample_time)));

// Gyrosocpe
//convert arw to stddev
real_T gyro_sigma_arw = params_.gyro.arw / sqrt_dt;
angular_velocity += gauss_dist.next() * gyro_sigma_arw + state_.gyroscope_bias;
//update bias random walk
real_T gyro_sigma_bias = gyro_bias_stability_norm * sqrt_dt;
state_.gyroscope_bias += gauss_dist.next() * gyro_sigma_bias;

至此,介绍完了陀螺仪的内参。

再说加速度计

根据之前笔记的内容,加速度计的速度随机游走类似的也是表示误差随时间的变化情况,一般单位为\(m/s/\sqrt{h}\)。所以参数文件中VelocityRandomWalk为0.24即表示,每根号小时速度的误差为0.24m/s。而在AirSim的代码中,根据这个参数计算速度随机游走的公式是:

\[VRW = \frac{0.24 \cdot gravity}{1000}\]

这里\(gravity\)代码里给定的是9.80665,0.24来自于配置文件。实话实说目前没有理解为什么要这样算,为什么和重力有关还除了个1000。在代码的注释中也只是说了“mg converted to m/s^2”。如果有了解的小伙伴,欢迎评论区解释。利用上述公式,结合给定参数,可以算出VRW是0.002352。

而加速度计的偏置稳定性AirSim代码中的计算公式如下:

\[Bias\ Stability = 36 \cdot 10^{-6} \cdot gravity\]

这里的36来自于配置文件中的AccelBiasStability参数,和上面一样,我也不清楚为什么要这样算。和陀螺仪偏置稳定性类似的,我们也需要对其除以\(\tau\),如下。

\[Bias\ Stability = \frac{36 \cdot 10^{-6} \cdot gravity}{\sqrt{\tau}}\]

这里的\(\tau\)是参数文件中指定的,为800。因此计算可以得到值为1.24818276883015e-05。更新加速度计状态的代码和陀螺仪是类似的,这里也贴上来。

//accelerometer
//convert vrw to stddev
real_T accel_sigma_vrw = params_.accel.vrw / sqrt_dt;
linear_acceleration += gauss_dist.next() * accel_sigma_vrw + state_.accelerometer_bias;
//update bias random walk
real_T accel_sigma_bias = accel_bias_stability_norm * sqrt_dt;
state_.accelerometer_bias += gauss_dist.next() * accel_sigma_bias;

至此加速度计部分就介绍完了。另外,在AirSim的IMU源码中,也给出了这些默认参数的出处:Parameter values are for MPU 6000 IMU from InvenSense。感兴趣可以参考官方提供的规格文件。 对于AirSim中更详细的IMU内参分析可以参考这个网页这个网页这个网页

最后,我们总结一下AirSim中默认IMU参数对应的值。如果你改了其中某些值,那么就把上面计算公式的对应部分换掉,应该就可以了。

  • 陀螺仪角度随机游走:8.7266462e-5
  • 陀螺仪偏置稳定性:9.9735023e-7
  • 加速度计速度随机游走:0.002353596
  • 加速度计偏置稳定性:1.2481827e-5

以上是连续情况下的值,在实际中也考虑IMU频率,经常使用离散化的值。对于随机游走,离散化的公式是:

\[\sigma_{d} = \sigma \frac{1}{\sqrt{\Delta t} }\]

对于偏置稳定性,离散化的公式为:

\[\sigma_{d} = \sigma \sqrt{\Delta t}\]

如果帧率为300Hz,那么\(\Delta t=0.00333\),最后计算得到的离散化以后的参数为:

  • 陀螺仪角度随机游走:0.001512255776822746
  • 陀螺仪偏置稳定性:5.755324415413875e-08
  • 加速度计速度随机游走:0.04078587656397606
  • 加速度计偏置稳定性:7.202782084090172e-07

关于离散化的更详细内容参考这个网页

4.1.3 LiDAR

关于LiDAR传感器,官方文档中给出的属性以及对应的默认值如下所示。

"Lidar": {
    "SensorType": 6,
    "Enabled" : true,
    "NumberOfChannels": 16,
    "RotationsPerSecond": 10,
    "PointsPerSecond": 100000,
    "X": 0, "Y": 0, "Z": -1,
    "Roll": 0, "Pitch": 0, "Yaw" : 0,
    "VerticalFOVUpper": -15,
    "VerticalFOVLower": -25,
    "HorizontalFOVStart": -20,
    "HorizontalFOVEnd": 20,
    "DrawDebugPoints": true,
    "DataFrame": "SensorLocalFrame"
}

总体而言都是比较好理解的参数,包括LiDAR的线的个数、每秒钟多少转、产生多少点云、垂直视场角、水平视场角等都可以自定义修改,十分方便。相比于相机和IMU也简单很多。这里稍微需要注意的是,DrawDebugPoints属性。如果设为true的话,那么就会在场景里看到很多绿色的激光点。这些点在RGB影像中也同样会出现,所以如果不希望影像数据收到干扰,记得把这个属性设为false。而在我们的设置文件中,对相关参数进行了修改,就会自动覆盖默认的值。

4.2 传感器外参
4.2.1 AirSim中坐标系的定义

各传感器的外参本质上就是各传感器之间的相对位置关系。而要进一步探讨,就需要了解AirSim中的坐标系定义。

世界坐标系 根据官方文档描述,AirSim中的世界坐标系遵循NED坐标系统,也即+X指向北,+Y指向东,+Z指向下,所有单位是国际标准单位(单位是米)。无人机或小车的起点就是世界NED坐标的原点(0,0,0)。所以,这里有一个需要注意的地方。因为NED坐标系中Z轴向下为正,所以当无人机飞到空中以后,Z值反而变成负的了,而且负的数值越大飞得越高,这点需要注意。在AirSim中,这个坐标系被称为全局坐标系、NED坐标系或者世界坐标系。另外,在Unreal Engine中定义则稍有不同,Z轴向上为正,单位为厘米。另外需要注意的是,如果你手动设置了小车在世界坐标系中的位姿,那么此时世界坐标系的原点就不再是当前小车的位置了,而是距离你设置的位姿反向的那么远的位置。小结一下:世界坐标系以无人机或小车起点为原点,X轴指向北方(前),Y轴指向东方(右),Z轴指向下方,单位为米。

本体坐标系 除了世界坐标系,本体坐标系也是很常用的。在AirSim中,根据官方文档,定义如下: The body frame follows the Front Left Up (FLU) convention, and right-handedness。

  • X axis is along the Front direction of the quadrotor. Clockwise rotation about this axis defines a positive roll angle. Hence, rolling with a positive angle is equivalent to translating in the right direction, w.r.t. our FLU body frame.

  • Y axis is along the Left direction of the quadrotor. Clockwise rotation about this axis defines a positive pitch angle. Hence, pitching with a positive angle is equivalent to translating in the front direction, w.r.t. our FLU body frame.

  • Z axis is along the Up direction. Clockwise rotation about this axis defines a positive yaw angle. Hence, yawing with a positive angle is equivalent to rotated towards the left direction wrt our FLU body frame. Or in an anticlockwise fashion in the body XY / FL plane.

简单来说就是右手定则。X轴指向小车或无人机的前方,Y轴指向小车或无人机的左方,Z轴指向小车或无人机的上方。在AirSim中,根据这个网页的分析,IMU的坐标系是和本体坐标系一致的。换句话说,IMU坐标系设置为什么样,本体坐标系就为什么样。需要注意的是:经过实测,上面的这个定义是有问题的,在实际AirSim环境中本体坐标系是:X轴指向小车前方,Y轴指向小车右方,Z轴指向小车下方。这依然是一个标准的右手系。而且,这个坐标系是和前面提到的世界坐标系指向是一致的。所以在处理本体坐标系的时候要小心,不要被官方文档给出的定义“迷惑”了,如果实在不确定指向,自己测试一下就能明白。小结一下:本体坐标系以无人机或小车为原点,与世界坐标系同指向(X轴指向前方,Y轴指向右方,Z轴指向下方),单位为米。

相机坐标系 根据这个网页的描述,在AirSim中,相机坐标系定义为原点在相机光心,X轴指向相机右侧,Y轴指向相机下方,Z轴指向相机前方。这个定义没什么特别需要说的,就是和之前一样的普通相机坐标系定义。小结一下:相机坐标系以相机为原点,X轴指向相机右方,Y轴指向相机下方,Z轴指向相机前方,单位为米。

LiDAR坐标系 关于AirSim中的LiDAR坐标系,网上介绍的资料比较少。但其实我们可以直接试出来。用LiDAR采集数据以后,把点云可视化出来并和真实场景比对,就可以知道他是在哪个坐标系下了。如下图所示。 可以看到,无人机现在在地上,所以理论上只能拍摄到地面以上的物体。而可视化出来的激光点云可以发现Z方向都是负值,而且物体越高负值越大。而且我们还可以看到,激光点云的中心是(0,0)。所以LiDAR坐标系以LiDAR自身为中心,指向和本体坐标系是相同的。小结一下:LiDAR坐标系以LiDAR为原点,与本体坐标系同指向(X轴指向前方,Y轴指向右方,Z轴指向下方),单位为米。

4.2.2 传感器位姿的设置

前面我们介绍了不同坐标系的定义与意义。下面我们就介绍如何设置不同传感器的位置。

小车或无人机的位姿 小车或者无人机的位姿设置非常简单,直接在相应的机器人节点下设置就可以了。如下是官方文档中展示的两个例子,首先是小车的(简单对官方示例修改了一下)。

{
  "SettingsVersion": 1.2,
  "SimMode": "Car",

  "Vehicles": {
      "Car1": {
        "VehicleType": "PhysXCar",
        "X": 0, "Y": -2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Car2": {
        "VehicleType": "PhysXCar",
        "X": 0, "Y": 0, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Car3": {
        "VehicleType": "PhysXCar",
        "X": 0, "Y": 2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Car4": {
        "VehicleType": "PhysXCar",
        "X": 5, "Y": 0, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Car5": {
        "VehicleType": "PhysXCar",
        "X": 5, "Y": 2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Car6": {
        "VehicleType": "PhysXCar",
        "X": 5, "Y": -2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      }
    }
}

通过代码,我们轻松地在仿真环境里构造了一个6个车的车队,环境运行以后效果如下。 配置文件中,XYZ分别表示小车在世界坐标系下的位置,RollPitchYaw则是表示在世界坐标系下的姿态。

无人机的示例也是类似的,如下。

{
  "SettingsVersion": 1.2,
  "SimMode": "Multirotor",

  "Vehicles": {
      "Drone1": {
        "VehicleType": "SimpleFlight",
        "X": 0, "Y": -2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Drone2": {
        "VehicleType": "SimpleFlight",
        "X": 0, "Y": 0, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Drone3": {
        "VehicleType": "SimpleFlight",
        "X": 0, "Y": 2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Drone4": {
        "VehicleType": "SimpleFlight",
        "X": 5, "Y": 0, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Drone5": {
        "VehicleType": "SimpleFlight",
        "X": 5, "Y": 2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      },
      "Drone6": {
        "VehicleType": "SimpleFlight",
        "X": 5, "Y": -2, "Z": -2,
        "Roll": 0, "Pitch": 0, "Yaw" : 0
      }
    }
}

参数意义是类似的,结果如下。 通过上面的示例,我们便实现了对小车或无人机位姿的指定。小结一下:小车或者无人机的位姿是相对于世界坐标系的,或者说在世界坐标系下定义和设置的。

相机位姿的设置 相机位姿的设置本质上和前面是一样的,都是通过XYZRollPitchYaw属性设置。比如,官方示例中,一个包含左、中右三个相机的简单设置文件如下。

{
  "SettingsVersion": 1.2,
  "SimMode": "Multirotor",

  "Vehicles": {
    "drone_1": {
      "VehicleType": "SimpleFlight",

      "Cameras": {
        "front_center_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0, "Z": 0.10,
          "Pitch": 0, "Roll": 0, "Yaw": 0
        },

        "front_left_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": -0.6, "Z": 0.10,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        },

        "front_right_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0.6, "Z": 0.10,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        }
      },

      "X": 10, "Y": 0, "Z": 0,
      "Pitch": 0, "Roll": 0, "Yaw": 0
    }
  },
  "SubWindows": [
    {"WindowID": 0, "ImageType": 0, "CameraName": "front_left_custom", "Visible": true},
    {"WindowID": 1, "ImageType": 0, "CameraName": "front_center_custom", "Visible": true},
    {"WindowID": 2, "ImageType": 0, "CameraName": "front_right_custom", "Visible": true}
  ]
}

运行效果如下。 可以看到,左中右相机输出了不同位置拍摄到的影像。我们进一步对配置文件进行分析。首先,我们在drone_1这个节点下面设置了无人机的位置,也就是(10,0,0)。这样仿真环境启动以后,无人机就在这里。我们设置不同的位置,可以发现相机也是跟着无人机一起移动的,尽管我们没有显式改变相机的位置。 这样的原因在于,Cameras节点在drone_1节点下面,所以当我们移动或是指定drone_1节点位置的时候,相机也就跟着一起移动了。另外还需要说明的是,在上一部分介绍小车或无人机位置设置的时候,这个坐标是在世界坐标系下的,也就是NED坐标系,单位是米。而且我们也提到了,在AirSim中,Z轴为负才表示在空中。所以如果你把drone_1的Z坐标改成-10,无人机就会被设置在空中,然后迅速落下来(因为开着物理引擎,受重力影响),如下。 然后再看Cameras节点下面,我们分别定义了front_center_customfront_left_customfront_right_custom三个相机。在每个相机的CaptureSettings里,具体设置了相机传感器的位置。而根据前面的实验可以发现,相机是随着无人机或小车一起运动的。所以这里我们给相机设置的XYZ并非世界坐标系(NED坐标系)下的绝对坐标,而是相对于小车或无人机的相对坐标。这一点还希望明确。当然这里你可能会有新的问题,相对于无人机或者小车可以理解,那到底是相对于谁的坐标,或者说是在哪个坐标系下定义的呢?答案是无人机或小车的本体坐标系下。在4.2.1部分我们定义了本体坐标系,可以把它理解为和移动平台固连的坐标系。我们设置的相机所有坐标和姿态都是在这个坐标系下定义的。这里,我们可以验证之前的定义是否正确。根据我们之前对本体坐标系的定义:本体坐标系X轴指向小车或无人机的前方,Y轴指向小车或无人机的左方,Z轴指向小车或无人机的上方。这一点我们通过设置不同的X即可验证,如下。 可以看到,无人机往前为X轴正向,这点和定义是相同的。而Y轴,通过设置不同Y值可以发现,向左为负,右为正,如下图所示。 而这一点和之前的定义是相违背的。继续验证Z轴,如下。 可以明显看出来,Z轴是向下为正,向上为负。这和之前定义里的也是相违背的。不过经过实测的本体坐标系,你会发现:X轴指向小车前方,Y轴指向小车右方,Z轴指向小车下方。这依然是一个标准的右手系。而且,这个坐标系是和前面提到的世界坐标系指向是一致的。所以这一点务必注意。综上,便完成了对于相机位姿的设置,一句话就是:相机的位姿都是在本体坐标系下的。此外,还有一个双目+IMU的配置文件示例,感兴趣也可以看一下。小结一下:相机的位姿是相对于本体坐标系的,或者说在本体坐标系下定义和设置的。

IMU位姿的设置 前面也说了,如果没有显式设置IMU位姿,那么它的坐标系就和本体坐标系重合。也就是AirSim中真实的本体坐标系:X轴指向小车前方,Y轴指向小车右方,Z轴指向小车下方。当然,你也可以手动设置IMU的位姿。比如下面的示例展示了对IMU位姿的设置,方法都是类似的。

{
  "SettingsVersion": 1.2,
  "SimMode": "Multirotor",

  "Vehicles": {
    "drone_1": {
      "VehicleType": "SimpleFlight",

      "Sensors": {
        "Imu": {
          "SensorType": 2,
          "Enabled" : true,
          "AngularRandomWalk": 0.3,
          "GyroBiasStabilityTau": 500,
          "GyroBiasStability": 4.6,
          "VelocityRandomWalk": 0.24,
          "AccelBiasStabilityTau": 800,
          "AccelBiasStability": 36,
          "X": 0, "Y": 0, "Z": -1,
          "Roll": 0, "Pitch": 0, "Yaw" : 0
          }
        },

      "Cameras": {
        "front_center_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0, "Z": 0.1,
          "Pitch": 0, "Roll": 0, "Yaw": 0
        },

        "front_left_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": -0.6, "Z": 0.1,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        },

        "front_right_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0.6, "Z": 0.1,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        }
      },

      "X": 10, "Y": 0, "Z": 0,
      "Pitch": 0, "Roll": 0, "Yaw": 0
    }
  },
  "SubWindows": [
    {"WindowID": 0, "ImageType": 0, "CameraName": "front_left_custom", "Visible": true},
    {"WindowID": 1, "ImageType": 0, "CameraName": "front_center_custom", "Visible": true},
    {"WindowID": 2, "ImageType": 0, "CameraName": "front_right_custom", "Visible": true}
  ]
}

但这里面有两个问题:1. 如果我修改IMU的位姿,本体坐标系是否也会跟着变化?2. 设置的IMU位姿是在世界坐标系中的还是在本体坐标系中的?首先回答第一个问题,假如修改了IMU的位姿,本体坐标系也跟着发生了变化,那么相机的影像也一定会发生变化(因为前面说了,相机的位姿就是在本体坐标系下的)。这一点很容易验证,我们设置不同IMU位置,看影像是否有变化,如下。 结论是不管怎么修改IMU的位姿,影像没有任何变化。这也就说明,尽管IMU的坐标系是和本体坐标系重合的(原点相同、指向相同),但他们彼此并无关联,修改IMU位置和姿态不会对本体坐标系造成影响。而至于第二个问题,先说结论:IMU的位姿是在本体坐标系下设置的。因为IMU无法可视化,难以观察,直接测试。但是IMU和LiDAR一样,都是Sensors节点下面的一个节点,所以理论上而言,LiDAR的位姿设置和IMU是一样的,我们把测试放在LiDAR部分。小结一下:IMU的位姿是相对于本体坐标系的,或者说在本体坐标系下定义和设置的。

LiDAR位姿的设置 LiDAR作为Sensors传感器节点的其中一个,位姿设置方式也是类似的,下面展示了一个小例子。为了更好的观察效果,我把激光点云可视化打开了。

{
  "SettingsVersion": 1.2,
  "SimMode": "Multirotor",

  "Vehicles": {
    "drone_1": {
      "VehicleType": "SimpleFlight",

      "Sensors": {
        "Imu": {
          "SensorType": 2,
          "Enabled" : true,
          "AngularRandomWalk": 0.3,
          "GyroBiasStabilityTau": 500,
          "GyroBiasStability": 4.6,
          "VelocityRandomWalk": 0.24,
          "AccelBiasStabilityTau": 800,
          "AccelBiasStability": 36,
          "X": 0, "Y": 0, "Z": -1,
          "Roll": 0, "Pitch": 0, "Yaw" : 0
          },
        "LidarSensor": {
          "SensorType": 6,
            "Enabled" : true,
            "NumberOfChannels": 32,
            "RotationsPerSecond": 500,
            "PointsPerSecond": 300000,
            "VerticalFOVUpper": 30,
            "VerticalFOVLower": -15,
            "DrawDebugPoints": true,
            "DataFrame": "SensorLocalFrame",
            "range": 100,
            "X": 0, "Y": 0, "Z": -1,
            "Roll": 0, "Pitch": 0, "Yaw" : 0
         }
        },

      "Cameras": {
        "front_center_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0, "Z": 0.1,
          "Pitch": 0, "Roll": 0, "Yaw": 0
        },

        "front_left_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": -0.6, "Z": 0.1,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        },

        "front_right_custom": {
          "CaptureSettings": [
            {
              "ImageType": 0,
              "Width": 640,
              "Height": 480,
              "FOV_Degrees": 90
            }
          ],
          "X": 0.50, "Y": 0.6, "Z": 0.1,
          "Pitch": 0.0, "Roll": 0.0, "Yaw": 0.0
        }
      },

      "X": 20, "Y": 0, "Z": 0,
      "Pitch": 0, "Roll": 0, "Yaw": 0
    }
  },
  "SubWindows": [
    {"WindowID": 0, "ImageType": 0, "CameraName": "front_left_custom", "Visible": true},
    {"WindowID": 1, "ImageType": 0, "CameraName": "front_center_custom", "Visible": true},
    {"WindowID": 2, "ImageType": 0, "CameraName": "front_right_custom", "Visible": true}
  ]
}

效果如下。 我们还是要回答一个问题:这个LiDAR的位姿是在哪个坐标系下的?世界坐标系还是本体坐标系?其实答案已经显而易见了。因为这里LiDAR的X坐标设为0,而无人机的X坐标为20。根据可视化结果可以看到,LiDAR随着无人机一起移动了。因此LiDAR的位姿也是在本体坐标系下定义的。我们不妨再做一个测试来验证这个结论。前面说了,本体坐标系的Z轴指向是向下的。我们设置不同的Z值,看激光点云的效果,如下。 可以明显的看到,随着数值的减少(由正到负),LiDAR传感器的位置是越来越往上的。这进一步说明了LiDAR的位姿是在本体坐标系下的。小结一下:LiDAR的位姿是相对于本体坐标系的,或者说在本体坐标系下定义和设置的。

4.2.3 传感器坐标系间的转换与外参求解

在明确了各个坐标系的定义以及传感器的位姿是如何设置的之后,求解不同传感器之间的变换关系就会变得容易很多。下图展示了AirSim中各个传感器坐标系之间的关系。 可以看到,我们要寻找的各个传感器之间的关系其实就是灰色部分圈出来的各个变换。而这里面的每个变换其实都是根据前面我们参数文件里设置的参数可以解算出来的。这里我们以前面提到过的无人机多传感器这个配置文件进行解算,或者也可以点击查看对应源文件

{
  "SeeDocsAt": "https://microsoft.github.io/AirSim/settings/",
  "SettingsVersion": 1.2,

  "SimMode": "Multirotor",
  "PhysicsEngineName":"ExternalPhysicsEngine",

   "Vehicles": {
      "Ours": {
          "VehicleType": "SimpleFlight",
          "AutoCreate": true,
          "Sensors": {
            "Imu": {
              "SensorType": 2,
              "Enabled" : true,
              "AngularRandomWalk": 0.3,
              "GyroBiasStabilityTau": 500,
              "GyroBiasStability": 4.6,
              "VelocityRandomWalk": 0.24,
              "AccelBiasStabilityTau": 800,
              "AccelBiasStability": 36,
              "X": 0, "Y": 0, "Z": -1,
              "Roll": 0, "Pitch": 0, "Yaw" : 0
              },
            "LidarSensor": {
              "SensorType": 6,
                "Enabled" : true,
                "NumberOfChannels": 32,
                "RotationsPerSecond": 500,
                "PointsPerSecond": 300000,
                "VerticalFOVUpper": 30,
                "VerticalFOVLower": -15,
                "DrawDebugPoints": false,
                "DataFrame": "SensorLocalFrame",
                "range": 100,
                "X": 0, "Y": 0, "Z": -1,
                "Roll": 0, "Pitch": 0, "Yaw" : 0
             }
            },

            "Cameras": {
              "front_left": {
                "CaptureSettings": [
                  {
                    "ImageType": 0,
                    "Width": 752,
                    "Height": 480,
                    "//": "这里的FOV主要指的是水平方向的角度,但事实上如果调整了这个角度,竖直方向视场角也会相应跟着变化",
                    "FOV_Degrees": 90
                  }
                ],
                "X": 0.35, "Y": -0.05, "Z": -0.1,
                "Pitch": 0, "Roll": 0, "Yaw": 0
              },
              "front_right": {
                "CaptureSettings": [
                  {
                    "ImageType": 0,
                    "Width": 752,
                    "Height": 480,
                    "FOV_Degrees": 90
                  }
                ],
                "X": 0.35, "Y": 0.05, "Z": -0.1,
                "Pitch": 0, "Roll": 0, "Yaw": 0
              }
             },
             
             "//": "这下面的表示我们搭建的这个平台的位置与姿态",
             "X": 0, "Y": 0, "Z": 0,
            "Pitch": 0, "Roll": 0, "Yaw": 0
          }
    }
  
}

本体到IMU的变换\(T_{bi}\) 根据参数文件,IMU在本体坐标系下的坐标为(0,0,-1),指向完全相同。所以\(T_{bi}\)为:

\[T_{bi} = \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & -1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

本体到LiDAR的变换\(T_{bl}\) 根据参数文件,LiDAR在本体坐标系下的坐标为(0,0,-1),指向完全相同。所以\(T_{bl}\)为:

\[T_{bl} = \begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & -1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

本体到左相机的变换\(T_{bcl}\) 根据参数文件,相机在本体坐标系下的坐标为(0.35,-0.05,-0.1)。但坐标轴的指向不同。一个简单的旋转方法是,先绕着本体坐标系的Y轴转90度,再绕着本体坐标系的Z轴转90度就和本体坐标系指向相同了。 我们还是定义旋转方向:面对旋转轴正向,顺时针为正,逆时针为负。因此,这里绕着本体Y轴转了正90度,绕着本体Z轴也正向旋转90度。 根据之前的笔记知识,所以旋转部分应该为:

\[\begin{align} R = R_{Y}(90)R_{Z}(90) &= \begin{bmatrix} cos\alpha & 0 & sin\alpha\\ 0 & 1 & 0\\ -sin\alpha & 0 & cos\alpha \end{bmatrix}\begin{bmatrix} cos\alpha & -sin\alpha & 0\\ sin\alpha & cos\alpha & 0\\ 0 & 0 & 1 \end{bmatrix}\\ &= \begin{bmatrix} 0 & 0 & 1\\ 0 & 1 & 0\\ -1 & 0 & 0 \end{bmatrix}\begin{bmatrix} 0 & -1 & 0\\ 1 & 0 & 0\\ 0 & 0 & 1 \end{bmatrix}\\ &=\begin{bmatrix} 0 & 0 & 1\\ 1 & 0 & 0\\ 0 & 1 & 0 \end{bmatrix} \end{align}\]

z再配合平移部分,所以\(T_{bcl}\)为:

\[T_{bcl} = \begin{bmatrix} 0 & 0 & 1 & 0.35\\ 1 & 0 & 0 & -0.05\\ 0 & 1 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

本体到右相机的变换\(T_{bcr}\) 旋转部分和左相机是一样的,只是平移部分不一样,所以\(T_{bcr}\)为:

\[T_{bcr} = \begin{bmatrix} 0 & 0 & 1 & 0.35\\ 1 & 0 & 0 & 0.05\\ 0 & 1 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

求解得到了这些基本变换之后,就可以求解传感器之间的变换关系了。一般而言,我们习惯以相机作为基准,计算各个传感器到相机的变换关系。如果是双目相机,一般则选择左相机为基准。因此,这里需要计算三个变换:IMU到左相机的变换、LiDAR到左相机的变换、右相机到左相机的变换。根据上面的坐标系关系图,计算公式分别如下。

\[\left\{\begin{matrix} E_{IMU-CAM_{L}} = T_{bi}^{-1}T_{bcl} \\ E_{LiDAR-CAM_{L}} = T_{bl}^{-1}T_{bcl}\\ E_{CAM_{R}-CAM_{L}} = T_{bcr}^{-1}T_{bcl} \end{matrix}\right.\]

把上面计算出来的具体变换带入即可求解得到彼此之间的变换关系。关于内外参的计算,还可以参考ORB-SLAM3中官方的介绍文档,写得非常好,清晰明了。

5.AirSim配置文件中的属性

介绍完这些以后,你会发现,AirSim里有很多奇奇怪怪的属性。比如PhysicEngine、ClockSpeed等等。这些参数其实在开发文档中有介绍,并给出了他们的默认值,感兴趣可以参考、查阅这个文档。同时,在这个文档中,总结了传感器的相关配置属性,也可以参考。最后,关于AirSim跑SLAM的其它讨论可以见这个网页

6.参考资料

  • [1] https://github.com/kminoda/VIODE/issues/9#issuecomment-1100616613
  • [2] https://microsoft.github.io/AirSim/apis/#getmultirotorstate
  • [3] https://microsoft.github.io/AirSim/image_apis/#computer-vision-mode_1
  • [4] https://github.com/microsoft/AirSim/blob/main/PythonClient/computer_vision/cv_mode.py
  • [5] https://microsoft.github.io/AirSim/image_apis/#changing-resolution-and-camera-parameters
  • [6] https://github.com/microsoft/AirSim/issues/2907
  • [7] https://github.com/microsoft/AirSim/discussions/4217
  • [8] https://github.com/microsoft/AirSim/discussions/4191
  • [9] https://microsoft.github.io/AirSim/settings/#physicsenginename
  • [10] https://microsoft.github.io/AirSim/image_apis/#setting-pose-in-computer-vision-mode
  • [11] https://microsoft.github.io/AirSim/image_apis/#getting-images-with-more-flexibility
  • [12] https://github.com/microsoft/AirSim/releases
  • [13] https://zhuanlan.zhihu.com/p/469606040
  • [14] https://microsoft.github.io/AirSim/settings/
  • [15] https://microsoft.github.io/AirSim/sensors/#configuring-the-default-sensor-list
  • [16] https://github.com/microsoft/AirSim/issues/314
  • [17] https://github.com/microsoft/AirSim/issues/2396#issuecomment-578412715
  • [18] https://zhuanlan.zhihu.com/p/482098440
  • [19] https://microsoft.github.io/AirSim/image_apis/#camera-apis
  • [20] https://github.com/microsoft/AirSim/issues/269#issuecomment-313526623
  • [21] https://github.com/unrealcv/unrealcv/issues/14#issuecomment-487346581
  • [22] https://github.com/microsoft/AirSim/issues/3293#issuecomment-773348489
  • [23] https://blog.csdn.net/hanmoge/article/details/113675646
  • [24] https://github.com/microsoft/AirSim/blob/main/AirLib/include/sensors/imu/ImuSimpleParams.hpp
  • [25] https://github.com/microsoft/AirSim/blob/238c8e708dab831bf5835b1c954abfb0136e9277/AirLib/include/sensors/imu/ImuSimple.hpp
  • [26] https://www.invensense.com/wp-content/uploads/2015/02/MPU-6000-Datasheet1.pdf
  • [27] https://microsoft.github.io/AirSim/apis/#coordinate-system
  • [28] https://microsoft.github.io/AirSim/api_docs/html/#airsim.client.MultirotorClient.moveByAngleRatesThrottleAsync
  • [29] https://blog.csdn.net/kuvinxu/article/details/124467529
  • [30] https://microsoft.github.io/AirSim/multi_vehicle/#creating-multiple-cars
  • [31] https://microsoft.github.io/AirSim/multi_vehicle/#creating-multiple-drones
  • [32] https://github.com/microsoft/AirSim/blob/main/ros/src/airsim_tutorial_pkgs/settings/front_stereo_and_center_mono.json
  • [33] https://github.com/xuhao1/airsim_ros_pkgs/blob/master/vins_airsim/settings.json
  • [34] https://github.com/UZ-SLAMLab/ORB_SLAM3/blob/master/Calibration_Tutorial.pdf

本文作者原创,未经许可不得转载,谢谢配合

返回顶部