Isaac Sim、AirSim、XTDrone仿真平台中双目、IMU、LiDAR传感器内外参获取与计算

Nov 21,2023   15615 words   56 min

Tags: Simulation

在之前的笔记中,我们已经在Isaac Sim中搭建了搭载双目相机、IMU、LiDAR的移动小车,以便采集数据。如下。 小车的底盘是基于Nidia JetBot修改的,本身没什么问题。唯一的缺点就是有时候容易“翻车”。因为我们在它上面强行增加了一个传感器,使得小车的重心整体提高了,再加上底盘比较小,就比较容易翻车。所以我们可以重新换个底座,比如换成这种四轮小车,整体的稳定性会好很多。 此外,也给这个LVI传感器模块增加了一点纹理,看起来更好看一些。左右相机分别用不同的颜色以示区分,左相机为橙色,右相机为灰色。这个四轮小车的源文件放在了Github上,点击查看。这里需要注意,由于我们涉及到了ROS Bridge的相关功能,所以这个文件最好不要在Windows下打开。如果在Windows下打开之后,再用Ubuntu打开,会发现ROS Bridge的Action Graph节点可能会失效。还要重新设置,比较麻烦。可以拷贝一个副本在Windows下面查看,也可以键盘控制,但无法使用ROS功能。

尽管小车搭建好了,可以采集数据,但还剩最后一步没有解决,就是各传感器内参以及传感器之间外参的求解。因此本篇笔记,我们首先完成对Isaac Sim小车传感器内参以及外参的求解。然后顺便复习一下之前AirSim、XTDrone中外参的求解过程。最后,展示一下,如何在Isaac Sim中将小车放到不同的环境中采集数据。

首先根据之前的知识,需要明确的是,变换方向的问题。对于\(\mathbf{T}_{AB}\),表示一个从坐标系B到坐标系A的变换。换句话说,当给定一个坐标系B中的坐标时,就可以通过它转换到坐标系A中。概念性公式如下:

\[\mathbf{x}_{A}=\mathbf{T}_{AB}\mathbf{x}_{B}\]

算外参的本质就是求解坐标系之间的变换关系。一个通用的做法是先找到各个传感器相对于本体坐标系的关系,再根据变换规则算相对关系。而不是上来就算相对关系,因为这样不一定好算。一般而言,把各个坐标系位置和指向定义好、弄明白,外参就没问题了。

1.Isaac Sim中LVI传感器内参

1.1 相机

在Isaac Sim中,相机的内参通过界面即可查看、修改。选中某个相机对象,找到Lens标签即可查看。 仿真环境里的焦距为400,fx=fy。成像的像素长宽为1280×720(界面中显示的渲染分辨率)。畸变参数没有设置,因此均为0(需要的话可以手动通过API设置)。双目相机的基线长度为abs(-0.3)+abs(0.3)=0.6,单位为米。因此,如果按照ORB-SLAM2中双目的bf计算,bf为400×0.6=240。相机帧率这里我们在采集的时候没有显式设置,因此,可以根据实际采集的数据估算。

1.2 IMU

根据前面的笔记,IMU的内参主要就是加速度计和陀螺仪的两个偏置和随机游走噪声。但根据Isaac Sim的文档论坛,目前Isaac Sim中并不支持直接设置IMU的噪声参数。也就是说,这四个IMU内参都为0。如果要添加噪声还有个办法,先采集、后手动对干净的IMU观测添加噪声。 而至于IMU的采集频率,在采集脚本里可以设置。这里我们在采集脚本里显式指定了IMU的帧率为500Hz。

1.3 LiDAR

在前面的笔记中介绍过了,Isaac Sim中使用的LiDAR参数可以在对应的json配置文件中找到。这里就列出我们采集用到的LiDAR的一些内参:

  • 最近量程距离:对应配置文件里的nearRangeM属性,默认为1米
  • 最远量程距离:对应配置文件里的farRangeM属性,默认为200米
  • 竖直向上的视场角:对应配置文件里的upElevationDeg属性,默认为10度
  • 竖直向下的视场角:对应配置文件里的downElevationDeg属性,默认为-15度
  • 水平方向开始视场角:对应配置文件里的startAzimuthDeg属性,默认为0度
  • 水平方向终止视场角:对应配置文件里的endAzimuthDeg属性,默认为360度
  • 激光线数:对应配置文件里的numberOfEmitters属性,默认为128
  • 激光帧率:对应配置文件里的scanRateBaseHz属性,默认为10

2.Isaac Sim中LVI传感器外参

以我们上面新搭建的小车为例,涉及双目相机、IMU和LiDAR三个传感器,进一步涉及本体坐标系、相机坐标系、IMU坐标系和LiDAR坐标系。下面分别介绍。

2.1 坐标系定义
2.1.1 世界坐标系

世界坐标系是Isaac Sim中的全局坐标系,简记为W,点击右侧对象树中的World对象即可查看世界坐标系的原点与指向,如下。 这是一个标准的右手系。在这个例子中,世界坐标系W的X轴指向小车前方,Y轴指向小车左方,Z轴遵循右手定则,指向上方

2.1.2 本体坐标系

本体坐标系可以看作是一种局部坐标系,所有传感器相对于它的变换就可以看作是外参,简记为B。在这里,我们选中LVI Sensor对象,其展示的坐标系指向即为局部的本体坐标系指向,如下。 可以看到,在这里,局部地本体坐标系和世界坐标系的指向是相同的。当然,也有可能不同,存在一定旋转等。 同时,需要注意的是,在Isaac Sim中,有两种坐标展示方式,一种是全局坐标(世界坐标),另一种是局部坐标。通过点击左边的工具栏中的按钮进行切换。全局坐标的原点是蓝色的,局部坐标的原点是橙色的。因为我们在计算外参的时候,需要关注不同坐标系的指向,所以,这里采用局部坐标的方式显示会更好。 在这个例子中,本体坐标系B的指向和世界坐标系完全相同:X轴指向小车前方,Y轴指向小车左方,Z轴遵循右手定则,指向上方。本体坐标系原点在世界坐标系下的位置为(2, 0, 0.65)。据此,我们可以得到从本体到世界坐标系的变换\(\mathbf{T}_{WB}\):

\[\mathbf{T}_{WB}=\begin{bmatrix} 1 & 0 & 0 & 2\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0.65\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

可以带入一个本体坐标系下的坐标点转换一下,看看对不对,比如本体坐标系下的原点(0, 0, 0)。经过转换后为:

\[\mathbf{x}_{W}=\mathbf{T}_{WB}\mathbf{x}_{B}=\begin{bmatrix} 1 & 0 & 0 & 2\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0.65\\ 0 & 0 & 0 & 1 \end{bmatrix}\begin{bmatrix} 0 \\ 0 \\ 0 \\ 1 \end{bmatrix}=\begin{bmatrix} 2 \\ 0\\ 0.65\\ 1 \end{bmatrix}\]

这是齐次坐标表示,取前三维,可以看到,就是我们上面提到的位置,说明这个转换是正确的。

2.1.3 IMU坐标系

在本例子中,IMU坐标系和本体坐标系完全重合:原点一致、指向相同。IMU坐标系简记为I。 我们也可以进一步通过它测量地数据进行验证,如下。 可以看到,当小车启动的时候,X方向数值有明显变化,且数值为正。当减速停止时,数值变为负。符合前面坐标系的定义。因此,IMU坐标系和本体坐标系指向相同:X轴指向小车前方,Y轴指向小车左方,Z轴遵循右手定则,指向上方。IMU坐标系原点在本体坐标系中地坐标为(0, 0, 0)。因此,从IMU坐标系I到本体坐标系B的变换\(\mathbf{T}_{BI}\)为:

\[\mathbf{T}_{BI}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
2.1.4 LiDAR坐标系

在本例子中,LiDAR和本体坐标系同样有相同地指向,但是存在平移,简记为L。但在Isaac Sim中,显示地LiDAR传感器坐标轴的指向是错误的,如下。 可以看到,显示来看,LiDAR坐标系和本体坐标系除了平移还存在旋转关系。但根据实际输出地LiDAR点云来看,点云的坐标是符合本体坐标系的指向的,如下所示。 可以看到,首先,随着X轴视角沿正向移动,物体越来越小,因此说明LiDAR坐标轴的X轴是指向前方的。然后沿Y方向移动,物体向左移动,说明Y轴正向指向左。然后向上移动,物体也越来越往下,说明Z轴向上。把这个结果和前面本体坐标系以及IMU坐标系进行比对,会发现是一致的。因此,LiDAR坐标系和本体坐标系指向一致:X轴指向小车前方,Y轴指向小车左方,Z轴遵循右手定则,指向上方。LiDAR坐标系原点在本体坐标系中的坐标为(0, 0, 3)。从LiDAR坐标系L到本体坐标系B的变换\(\mathbf{T}_{BL}\)为:

\[\mathbf{T}_{BL}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 3\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

另外,一句题外话,之所以出现这种显示的指向不正确地情况是因为,我们人为对LiDAR传感器分别绕X和Y轴进行了旋转,使得点云符合我们地认知。如果不旋转,输出地点云是竖起来的。

2.1.5 相机坐标系

类似地,Isaac Sim中显示地相机坐标系地指向并非实际指向,原因在于我们也对相机做了旋转,如下。 首先看平移部分,可以看到,本体坐标系向左为正,所以左相机的平移部分为正,而右相机地平移部分为负,符合预期。但显示地指向是不对的。经过旋转的相机,现在成像是符合我们实际的认知的,如下。 可以看到,随着传感器左移,画面整体向右移动。上移,则画面向下。因此,我们根据惯例来定义这里的相机坐标系:相机坐标系的Z轴指向前方,X轴水平向右,Y轴竖直向下,这个指向和本体坐标系是不同的。左相机坐标系在本体坐标系中的位置为(0, 0.3, 0),右相机坐标系在本体坐标系中的位置为(0, -0.3, 0)。左相机坐标系记为\(C_{L}\),右相机记为\(C_{R}\)。两个坐标系均和本体坐标系B存在旋转。从相机坐标系到本体坐标系的旋转部分\(\mathbf{R}\)可以这样得出:先把相机坐标系绕着本体系Y轴旋转90度,再绕着本体系Z轴旋转90度,相机坐标系指向即可与本体系一致。这里一定要注意旋转角度的方向问题。不管你采用什么规则,请在计算的时候保持一致,这样才不至于出错。比如在这里,我们定义旋转方向:从旋转轴的正向看,顺时针为正、逆时针为负。因此,首先,绕着本体系Y轴旋转90度,从面对本体系Y轴正向看去,我们是顺时针转了90度。然后绕着本体系Z轴转90度,从面对本体系Z轴正向看去,我们是逆时针旋转了90度。因此,旋转\(\mathbf{R}\)为:

\[\begin{align} \mathbf{R} = \mathbf{R}_{Y}(90)\mathbf{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}\]

因此,从左相机坐标系\(C_{L}\)到本体坐标系B的变换\(\mathbf{T}_{BC_{L}}\)为:

\[\mathbf{T}_{BC_{L}}=\begin{bmatrix} 0 & 0 & 1 & 0\\ -1 & 0 & 0 & 0.3\\ 0 & -1 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

类似的,从右相机坐标系\(C_{R}\)到本体坐标系B的变换\(\mathbf{T}_{BC_{R}}\)为:

\[\mathbf{T}_{BC_{R}}=\begin{bmatrix} 0 & 0 & 1 & 0\\ -1 & 0 & 0 & -0.3\\ 0 & -1 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

和前面一样,你也可以随便带入一个相机坐标系中的点,转换到本体系中,看看对不对。

2.2 外参计算

有了前面的明确的坐标系的定义以及各坐标系相对于本体坐标系的关系,结合基本的变换原则,就可以很容易求解各传感器之间的变换了。对于双目、IMU、LiDAR的传感器,一般而言我们比较关注三个变换:双目左右相机之间的变换(一般为右相机到左相机的变换\(\mathbf{T}_{C_{L}C_{R}}\))、双目相机和IMU之间的变换(一般为IMU到左相机的变换\(\mathbf{T}_{C_{L}I}\))、双目相机和LiDAR之间的变换(一般为LiDAR到左相机的变换\(\mathbf{T}_{C_{L}L}\))。根据上面已有的变换关系,可以得到如下公式:

\[\left\{\begin{matrix} \mathbf{T}_{C_{L}C_{R}} = \mathbf{T}_{BC_{L}}^{-1} \mathbf{T}_{BC_{R}}\\ \mathbf{T}_{C_{L}I} = \mathbf{T}_{BC_{L}}^{-1} \mathbf{T}_{BI} \\ \mathbf{T}_{C_{L}L} = \mathbf{T}_{BC_{L}}^{-1} \mathbf{T}_{BL} \end{matrix}\right.\]

带入上面得到的具体变换矩阵,可以分别求出各传感器的外参。

2.2.1 双目相机之间的变换

双目相机之间的变换\(\mathbf{T}_{C_{L}C_{R}}\)为:

\[\mathbf{T}_{C_{L}C_{R}}=\begin{bmatrix} 1 & 0 & 0 & 0.6\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

可以看到,这里旋转部分为单位阵,说明两个相机之间不存在旋转关系。而平移部分的X分量为-0.6,表示两个相机之间的基线长度。如何理解呢?根据前面的描述和定义,两个相机是沿着本体系的Y轴(左相机的X轴)排列的。右相机坐标系原点在左相机的坐标系下X方向的位置为0.6。现在切换到左相机坐标系下,方向为负表示逆着X轴平移。

2.2.2 双目相机和IMU之间的变换

双目相机和IMU之间的变换\(\mathbf{T}_{C_{L}I}\)为:

\[\mathbf{T}_{C_{L}I}=\begin{bmatrix} 0 & -1 & 0 & 0.3\\ 0 & 0 & -1 & 0\\ 1 & 0 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

这也是符合前面的认知的。

2.2.3 双目相机和LiDAR之间的变换

双目相机和LiDAR之间的变换\(\mathbf{T}_{C_{L}L}\)为:

\[\mathbf{T}_{C_{L}L}=\begin{bmatrix} 0 & -1 & 0 & 0.3\\ 0 & 0 & -1 & -3\\ 1 & 0 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

也是符合前面的介绍的。

2.2.4 小结

根据前面的描述还有计算,我们可以画出我们在Isaac Sim中搭建的小车LVI传感器的真实外参示意图,如下。

3.XTDrone中LVI传感器内参

XTDrone中传感器内参相关知识在这篇笔记里已经说过,这里为了方便查阅,再贴一下。

3.1 相机

之前例子中使用的是stereo_camera模块,因此寻找对应的sdf文件即可。主要内容都在sensor节点下面,简单列举如下。

  • camera.horizontal_fov: 相机的水平视场角,弧度表示,默认为1.5708
  • camera.image.width: 影像宽度,以像素表示,默认为752
  • camera.image.height: 影像高度,以像素表示,默认为480
  • sensor.plugin.Fx: 相机的x方向上的焦距,默认为376
  • sensor.plugin.Fy: 相机的y方向上的焦距,默认为376
  • sensor.plugin.Cx: 相机的x方向上的主点,默认为376
  • sensor.plugin.Cy: 相机的y方向上的主点,默认为240
  • sensor.plugin.distortionK1: 相机的畸变参数K1,对应径向畸变,默认为0.1
  • sensor.plugin.distortionK2: 相机的畸变参数K2,对应径向畸变,默认为0.01
  • sensor.plugin.distortionK3: 相机的畸变参数K3,对应径向畸变,默认为0
  • sensor.plugin.distortionT1: 相机的畸变参数T1,对应切向畸变,默认为5e-5
  • sensor.plugin.distortionT2: 相机的畸变参数T2,对应切向畸变,默认为-1e-4
  • sensor.update_rate: 相机Topic发布的帧率,默认为30(在sensor.plugin下面也有一个update_date属性,但经过实测修改它不会有影响)
3.2 IMU

我们使用的IMU模块为imu_gazebo,打开对应的sdf文件即可找到内参。简单列举如下。

  • sensor.plugin.gyroscopeNoiseDensity: 陀螺仪噪声密度,默认为0.0006
  • sensor.plugin.gyroscopeRandomWalk: 陀螺仪随机游走,默认为0.000003
  • sensor.plugin.gyroscopeTurnOnBiasSigma: 陀螺仪偏置稳定性,默认为0.03
  • sensor.plugin.accelerometerNoiseDensity: 加速度计噪声密度,默认为0.002
  • sensor.plugin.accelerometerRandomWalk: 加速度计随机游走,默认为0.00002
  • sensor.plugin.accelerometerTurnOnBiasSigma: 加速度计偏置稳定性,默认为0.1
  • sensor.update_rate: IMU帧率设置,默认为250
3.3 LiDAR

这里我们使用的LiDAR模块为3d_gpu_lidar,打开对应的sdf文件即可找到内参。简单列举如下。

  • sensor.ray.scan.horizontal.samples: 水平方向上的采样数量,默认为512
  • sensor.ray.scan.horizontal.min_angle: 水平方向起始角度,-pi到pi之间,弧度表示,默认为-3.1415926535897931
  • sensor.ray.scan.horizontal.max_angle: 水平方向中止角度,-pi到pi之间,弧度表示,默认为3.1415926535897931
  • sensor.ray.scan.vertical.samples: 竖直方向上的采样数量,默认为32(所谓的竖直方向上的采样数量指的就是多少线的激光雷达的意思,32就表示32线LiDAR)
  • sensor.ray.scan.vertical.min_angle: 竖直方向起始角度,-pi/2到pi/2之间,弧度表示,默认为-0.2617993877991494365
  • sensor.ray.scan.vertical.max_angle: 竖直方向中止角度,-pi/2到pi/2之间,弧度表示,默认为0.2617993877991494365
  • sensor.ray.range.min: 最小量程距离,单位米,默认为0.2
  • sensor.ray.range.max: 最大量程距离,单位米,默认为30
  • sensor.ray.range.resolution: 距离分辨率,单位米,默认为0.01
  • sensor.update_rate: LiDAR测量的帧率,默认为15

4.XTDrone中LVI传感器外参

关于我们之前在XTDrone中搭建的LVI传感器的外参计算,在这篇笔记中已经介绍过了。这里为了完整性,以及和Isaac Sim进行对比,把相关结果贴上来。

4.1 坐标系定义
4.1.1 世界坐标系

本质上来说,计算外参不需要世界坐标系的参与。在XTDrone中,其世界坐标系就是Gazebo中的世界坐标系。符合右手系。比如,我们假设X轴指向前方,Y轴指向左方,Z轴指向上方。

4.1.2 本体坐标系

XTDrone的配置文件里其实也并没有明确指定什么是本体坐标系,不过有base_link,可以看作是一种本体坐标系,但并没有明确说明指向。这里我们就以一般习惯,和世界坐标系指向相同进行定义:X轴指向前方,Y轴指向左方,Z轴指向上方。

4.1.3 IMU坐标系

对于IMU坐标系,以无人机或小车为原点,与本体坐标系同指向(X轴指向前方,Y轴指向左方,Z轴指向上方),单位为米。结合参数文件,可以得到从IMU坐标系I到本体坐标系B的变换\(\mathbf{T}_{BI}\):

\[\mathbf{T}_{BI}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0.25\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.1.4 LiDAR坐标系

LiDAR坐标系,以LiDAR为原点,与本体坐标系同指向(X轴指向前方,Y轴指向左方,Z轴指向上方),单位为米。结合参数文件,可以得到从LiDAR坐标系L到本体坐标系B的变换\(\mathbf{T}_{BL}\):

\[\mathbf{T}_{BL}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0.08\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.1.5 相机坐标系

相机坐标系,以相机为原点,X轴指向相机右方,Y轴指向相机下方,Z轴指向相机前方,单位为米。类似的,根据配置文件和定义,相机坐标系和本体坐标系间一个简单的旋转关系是:先绕着本体坐标系的Y轴转90度,再绕着本体坐标系的Z轴转90度就和本体坐标系指向相同了。类似的,我们定义旋转方向:面对旋转轴正向,顺时针为正,逆时针为负。因此,绕Y轴旋转为正向90度,绕Z轴旋转为负向90度。因此,左相机坐标系\(C_{L}\)到本体系的变换\(\mathbf{T}_{BC_{L}}\)为:

\[\mathbf{T}_{BC_{L}}=\begin{bmatrix} \mathbf{R}_{Y}(90)\mathbf{R}_{Z}(-90) & \mathbf{t}\\ \mathbf{0} & 1 \end{bmatrix}=\begin{bmatrix} 0 & 0 & 1 & 0.1\\ -1 & 0 & 0 & 0.06\\ 0 & -1 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

右相机坐标系\(C_{R}\)到本体系的变换\(\mathbf{T}_{BC_{R}}\)为:

\[\mathbf{T}_{BC_{R}}=\begin{bmatrix} \mathbf{R}_{Y}(90)\mathbf{R}_{Z}(-90) & \mathbf{t}\\ \mathbf{0} & 1 \end{bmatrix}=\begin{bmatrix} 0 & 0 & 1 & 0.1\\ -1 & 0 & 0 & -0.06\\ 0 & -1 & 0 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.2 外参计算
4.2.1 双目相机之间的变换

双目相机之间的变换\(\mathbf{T}_{C_{L}C_{R}}\)为:

\[\mathbf{T}_{C_{L}C_{R}} = =\begin{bmatrix} 1 & 0 & 0 & 0.12\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.2.2 双目相机和IMU之间的变换

双目相机和IMU之间的变换\(\mathbf{T}_{C_{L}I}\)为:

\[\mathbf{T}_{C_{L}I} = =\begin{bmatrix} 0 & -1 & 0 & 0.06\\ 0 & 0 & -1 & -0.25\\ 1 & 0 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.2.3 双目相机和LiDAR之间的变换

双目相机和LiDAR之间的变换\(\mathbf{T}_{C_{L}L}\)为:

\[\mathbf{T}_{C_{L}L} = =\begin{bmatrix} 0 & -1 & 0 & 0.06\\ 0 & 0 & -1 & -0.08\\ 1 & 0 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
4.2.4 小结

根据前面的描述还有计算,我们可以画出我们在XTDrone中搭建的无人机LVI传感器的真实外参示意图,如下。

5.AirSim中LVI传感器内参

AirSim中传感器内参相关知识在这篇笔记里已经说过,这里为了方便查阅,再贴一下。

5.1 相机

AirSim中的内参都在settings.json中设置。一般设置的内参包括:

  • Width: 752
  • Height: 480
  • FOV_Degress: 90
  • 畸变参数均为0
  • fx和fy根据公式(width/2)/tan(fov/2),由Width和FOV算出,这里结果是376
  • cx和cy没有误差,所以为理论值,也就是长宽的一半,分别是376、240
  • 相机帧率没有显式可以设置的地方,可以根据保存的数据估算,比如在我电脑上约为10
5.2 IMU

内参都在settings.json中设置。一般设置的内参包括:

  • AngularRandomWalk: 0.3
  • GyroBiasStabilityTau: 500
  • GyroBiasStability: 4.6
  • VelocityRandomWalk: 0.24
  • AccelBiasStabilityTau: 800
  • AccelBiasStability: 36

根据这些参数,可以进一步求解出陀螺仪和加速度计的内参(连续):

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

同时,IMU帧率没有显式可以设置的地方,可以根据保存的数据估算,比如在我电脑上约为300。

5.3 LiDAR

内参都在settings.json中设置。一般设置的内参包括:

  • NumberOfChannels: 16
  • RotationsPerSecond: 10
  • PointsPerSecond: 100000
  • VerticalFOVUpper: -15
  • VerticalFOVLower: -25
  • HorizontalFOVStart: -20
  • HorizontalFOVEnd: 20

类似的,LiDAR帧率没有显式可以设置的地方,可以根据保存的数据估算,比如在我电脑上约为10。

6.AirSim中LVI传感器外参

关于我们之前在AirSim中搭建的LVI传感器的外参计算,在这篇笔记中已经介绍过了。这里为了完整性,以及和Isaac Sim进行对比,把相关结果贴上来。

6.1 坐标系定义
6.1.1 世界坐标系

根据官方文档描述,AirSim中的世界坐标系遵循NED坐标系统,也即+X指向北,+Y指向东,+Z指向下,所有单位是国际标准单位(单位是米)。世界坐标系以无人机或小车起点为原点,X轴指向北方(前),Y轴指向东方(右),Z轴指向下方,单位为米。

6.1.2 本体坐标系

本体坐标系以无人机或小车为原点,与世界坐标系同指向(X轴指向前方,Y轴指向右方,Z轴指向下方),单位为米。为右手系。

6.1.3 IMU坐标系

在AirSim中,IMU的坐标系是和本体坐标系原点一致、指向一致。也就是说,X轴指向前方,Y轴指向右方,Z轴指向下方。根据参数文件设置,IMU坐标系I到本体坐标系B的变换\(\mathbf{T}_{BI}\)为:

\[\mathbf{T}_{BI}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & -1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.1.4 LiDAR坐标系

LiDAR坐标系以LiDAR为原点,与本体坐标系同指向(X轴指向前方,Y轴指向右方,Z轴指向下方),单位为米。根据参数文件设置,LiDAR坐标系L到本体坐标系B的变换\(\mathbf{T}_{BL}\)为:

\[\mathbf{T}_{BL}=\begin{bmatrix} 1 & 0 & 0 & 0\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & -1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.1.5 相机坐标系

相机坐标系以相机为原点,X轴指向相机右方,Y轴指向相机下方,Z轴指向相机前方,单位为米。根据配置文件和定义,相机坐标系和本体坐标系间一个简单的旋转关系是:先绕着本体坐标系的Y轴转90度,再绕着本体坐标系的Z轴转90度就和本体坐标系指向相同了。 我们还是定义旋转方向:面对旋转轴正向,顺时针为正,逆时针为负。因此,这里绕着本体Y轴转了正90度,绕着本体Z轴也正向旋转90度。因此,左相机坐标系\(C_{L}\)到本体系的变换\(\mathbf{T}_{BC_{L}}\)为:

\[\mathbf{T}_{BC_{L}}=\begin{bmatrix} \mathbf{R}_{Y}(90)\mathbf{R}_{Z}(90) & \mathbf{t}\\ \mathbf{0} & 1 \end{bmatrix}=\begin{bmatrix} 0 & 0 & 1 & 0.35\\ 1 & 0 & 0 & -0.05\\ 0 & 1 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]

右相机坐标系\(C_{R}\)到本体系的变换\(\mathbf{T}_{BC_{R}}\)为:

\[\mathbf{T}_{BC_{R}}=\begin{bmatrix} \mathbf{R}_{Y}(90)\mathbf{R}_{Z}(90) & \mathbf{t}\\ \mathbf{0} & 1 \end{bmatrix}=\begin{bmatrix} 0 & 0 & 1 & 0.35\\ 1 & 0 & 0 & 0.05\\ 0 & 1 & 0 & -0.1\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.2 外参计算
6.2.1 双目相机之间的变换

双目相机之间的变换\(\mathbf{T}_{C_{L}C_{R}}\)为:

\[\mathbf{T}_{C_{L}C_{R}}=\begin{bmatrix} 1 & 0 & 0 & 0.1\\ 0 & 1 & 0 & 0\\ 0 & 0 & 1 & 0\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.2.2 双目相机和IMU之间的变换

双目相机和IMU之间的变换\(\mathbf{T}_{C_{L}I}\)为:

\[\mathbf{T}_{C_{L}I}=\begin{bmatrix} 0 & 1 & 0 & 0.05\\ 0 & 0 & 1 & -0.9\\ 1 & 0 & 0 & -0.35\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.2.3 双目相机和LiDAR之间的变换

双目相机和LiDAR之间的变换\(\mathbf{T}_{C_{L}L}\)为:

\[\mathbf{T}_{C_{L}L}=\begin{bmatrix} 0 & 1 & 0 & 0.05\\ 0 & 0 & 1 & -0.9\\ 1 & 0 & 0 & -0.35\\ 0 & 0 & 0 & 1 \end{bmatrix}\]
6.2.4 小结

根据前面的描述还有计算,我们可以画出我们在AirSim中搭建的无人机LVI传感器的真实外参示意图,如下。

7.将小车放到不同的环境中采集数据

将小车采放到不同环境中采集数据其实非常简单。下面简单介绍一下步骤。

7.1 打开USD Composer搭建环境

打开USD Composer以后,在下面的面板中有个”Asset Stores”,点击即可看到有很多素材。 双击即可下载,然后拖拽到舞台中即可插入场景。当然,你可以根据需要随意修改或者组合。

7.2 导出场景素材

一般情况下,usd文件本身并不支持另一个usd文件的插入。所以我们需要将刚刚搭建好的环境导出成Isaac Sim能够导入的素材。选中需要导出的素材,然后选择File->Export。 在弹出的保存界面中选择FBX File格式(Isaac Sim支持的格式),保存即可。保存完成以后,会出现一个fbx文件,以及一个对应的材料文件夹。

7.3 导入场景素材

利用Isaac Sim打开我们配置好的传感器usd文件,比如我们在笔记一开头搭建好的小车文件。打开以后,选择File->Import,如下。 找到对应文件,打开,如下。 这样,场景素材就被插入进来了,如下。 这样场景就被导入了。

7.4 按需修改场景并采集数据

导入以后可能场景尺度等相对于小车过大了,导致数据采集出现问题,如下所示。 这时候就可以调整场景的Scale属性,也可以调整场景的整体位置,达到最佳状态,如下。 当然了,这里白色的地面我们可以通过设置GroundPlane的Visual属性的Visibility属性进行修改,改成invisible就可以了,如下。 至此,我们便完成了场景的插入,保存该usd文件,下次再打开的时候还是会有场景内容的。拷贝usd文件的时候记得连同纹理等文件也一并拷贝,不然可能会有纹理缺失的问题。在导入成功以后,Isaac Sim会在usd同目录下生成一个资产文件夹,将usd文件配合资产文件夹一并拷贝就可以了。

最后,在场景中操纵小车,即可采集数据。

8.参考资料

  • [1] https://forums.developer.nvidia.com/t/isaac-simulator-imu-sensor-noise-parameter/246669/
  • [2] https://docs.omniverse.nvidia.com/isaacsim/latest/features/sensors_simulation/sensor_simulation_physics_sensors.html

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

返回顶部