KITTI in Vins
本文参考:
https://zhuanlan.zhihu.com/p/75672946
https://zhuanlan.zhihu.com/p/115562083、
https://blog.csdn.net/GuanLingde/article/details/133938758
数据集下载
KITTI数据集的网页导航栏中每一栏代表不同的任务模块:
- home - 网站主页,提供项目概览。
- setup - 数据集设置说明,解释如何获取数据和配置相关环境。
- stereo - 立体视觉任务模块,包括立体匹配的测试数据和基准。
- flow - 光流任务模块,提供图像间的像素运动数据,用于评估光流算法。
- sceneflow - 场景流任务模块,类似于光流,但包含3D运动信息。
- depth - 深度估计任务模块,用于测试单目或双目相机深度估计算法。
- odometry - 视觉里程计模块,提供车辆轨迹数据,常用于评估SLAM或视觉里程计算法。
- object - 物体检测任务模块,包含带标签的图像和3D边界框,用于评估物体检测算法。
- tracking - 物体跟踪任务模块,包含连续帧的标签数据,用于评估多目标跟踪算法。
- road - 道路分割任务模块,用于评估道路检测和分割算法。
- semantics - 语义分割任务模块,包含每个像素的语义标签数据。
- raw data - 原始数据模块,包含未经处理的原始传感器数据(如相机和激光雷达数据)。
- submit results - 提交结果模块,允许用户提交算法的评估结果以获取基准排名。
现在我们进入raw data栏目下载数据集。每个数据集包含两个版本的图像数据:unsynced+unrectified data(原始数据,未同步+未校正)和synced+rectified data(处理数据,同步+校正)。
此外,还包括Calibration(校准数据),部分数据集还可能包含3D Velodyne激光雷达点云、3D GPS/IMU数据以及3D物体跟踪标签。
同时,网站提供了多种辅助工具,方便用户处理和使用数据集:
- raw data development kit:原始数据开发工具包
- raw dataset download script:原始数据集下载脚本
- velodyne calibration file:Velodyne校准文件
- QT-based visualizer:QT可视化工具,用于点云和跟踪序列
- PCL tools:使用PCL库处理KITTI原始数据
- python parser:Python解析器,用于读取对象标签XML文件
- python tools:加载和解析KITTI原始数据和里程计数据集
- kitti2bag与kitti_to_rosbag:将原始KITTI数据集转换为ROS bag文件
- KITTI MoSeg dataset:带有地面真值注释的运动物体检测数据集
- extended KittiMoSeg dataset:扩展版KittiMoSeg数据集,提供了10倍的运动物体检测地面真值注释
- motion compensation library:用于KITTI数据集中激光扫描的运动补偿库
网页下方提供了原始数据的下载链接,涵盖城市、住宅、道路、校园、个人和校准五个板块。
每个板块都包含对应的数据集。每个数据集旁边详细列出了以下信息:名称、文件大小、时长与帧数、图像分辨率、标签信息,以及该数据集的下载链接。
在KITTI数据集中,Raw Data中的特定驾驶数据集与Odometry Benchmark中的序列编号(00-10)存在对应关系。
- 序列 00:对应 2011_10_03_drive_0027
- 序列 01:对应 2011_10_03_drive_0042
- 序列 02:对应 2011_10_03_drive_0034
- 序列 03:对应 2011_09_26_drive_0067
- 序列 04:对应 2011_09_30_drive_0016
- 序列 05:对应 2011_09_30_drive_0018
- 序列 06:对应 2011_09_30_drive_0020
- 序列 07:对应 2011_09_30_drive_0027
- 序列 08:对应 2011_09_30_drive_0028
- 序列 09:对应 2011_09_30_drive_0033
- 序列 10:对应 2011_09_30_drive_0034
现在我们选中Residential板块下的2011_10_03_drive_0027 (17.6 GB)数据集也就是00,下载unsynced+unrectified data、synced+rectified data和calibration
数据集修改
extract.zip包含的IMU数据是100Hz, 但是视觉的数据没有去畸变,此外激光数据是以txt格式存储的,在转换为bag格式的时候非常耗时
sync.zip数据中的IMU是10Hz, 但是视觉数据已经去畸变了,并且视觉和激光的时间戳已经同步好了,激光数据的存储格式是二进制格式bin存储的
所以我们将extract.zip和sync.zip解压,把extract/oxts文件夹替换了sync/oxts文件夹
克隆修改数据的项目
git clone https://github.com/data01666/kitti-to-bag.git
该项目下存在2个文件,分别对应imu时间戳问题以及转换文件
imu时间戳问题
由于KITTI提供的的原始的IMU数据的时间戳存在断续和逆序的情况
先把oxts/timestamp.txt里面的时标画出来,然后看看哪些地方有这些情况
修改imu.py里的文件路径并运行,该文件会把断续和逆序的结果用图展示出来,并把结果保存到时间戳目录下
然后再手动改正,当要注意不是所有问题我们都能解决,打开oxtx文件夹下的timstamps.txt找到这些地方
# 不能解决,例如第一行,这种断续我们是无法处理的
2011-10-03 12:55:34.478375790
2011-10-03 12:55:36.397971133
# 逆序问题可以解决,修改时加0.01,例如2814行
#修改前
2011-10-03 12:56:04.504892391
2011-10-03 12:56:04.514964053
2011-10-03 12:56:04.524901913
2011-10-03 12:56:04.594821093
2011-10-03 12:56:04.544898836
2011-10-03 12:56:04.554804286
#修改后
2011-10-03 12:56:04.504892391
2011-10-03 12:56:04.514964053
2011-10-03 12:56:04.524901913
2011-10-03 12:56:04.534821093
2011-10-03 12:56:04.544898836
2011-10-03 12:56:04.554804286
数据集转换为bag
解压标定数据calibration,将里面的3个txt文件放入到与sync同级目录下
路径如下:~/dataset/kitti/raw_data/00/2011_10_03,该目录下放有2个文件夹(矫正与未矫正)和3个标定txt文件
现在执行转换命令,-t参数为指定数据集的日期,-r参数为指定驱动编号,最后生成bag文件到~/dataset/kitti/raw_data/00/
python kitti2bag.py raw_synced ~/dataset/kitti/raw_data/00 -t 2011_10_03 -r 0027
添加配置文件
在KITTI数据集中,标定文件夹解压后得到的这三个文件分别是:
- calib_cam_to_cam.txt:相机到相机的标定文件
- 包含摄像头之间的标定参数,主要是左右摄像头的内参和外参。
- 其中的内容包括每个摄像头的内参矩阵、畸变系数、旋转矩阵和平移向量,定义了左右摄像头在车辆上的相对位置和角度。
- 在KITTI数据集中,虽然车辆上只有左右两个相机,但每个相机都提供了灰度和彩色两种图像,因此标定文件会列出四个摄像头的参数:左前(灰度)、右前(灰度)、左前(彩色)和右前(彩色)。
- calib_imu_to_velo.txt:IMU到Velodyne激光雷达的标定文件
- 定义了IMU(惯性测量单元)与激光雷达(Velodyne)之间的外参。
- 包含旋转矩阵和平移向量,用于将IMU坐标系的数据转换到激光雷达的坐标系中。
- 这对于将IMU数据与激光雷达数据对齐十分重要,特别是在融合IMU和激光雷达数据时。
- calib_velo_to_cam.txt:Velodyne激光雷达到相机的标定文件
- 定义了激光雷达与摄像头之间的外参。
- 包含旋转矩阵和平移向量,用于将激光雷达的点云数据映射到相机坐标系中。
- 这对于在图像上叠加点云数据或进行视觉-激光雷达数据融合非常关键。
我们在添加配置文件时只需参考第一个相机之间的标定数据,下面解释一下文件里的各个部分
全局信息:
-
calib_time:标定时间,用于记录相机标定数据的时间戳。
-
corner_dist:标定板角点间的距离,用于标定过程中测量的参考距离。
相机参数(针对四个相机,分别是 00、01、02 和 03):
-
S_00, S_01, S_02, S_03代表原始图像尺寸,而S_rect_00, S_rect_01, S_rect_02, S_rect_03代表矫正图像的尺寸:
- S_rect_00: 1.241000e+03 3.760000e+02,我们需要关注矫正后的图像尺寸
-
K_00, K_01, K_02, K_03代表相机内参矩阵:
- 这是3x3的内参矩阵,描述相机的焦距和主点位置,格式为:
$$
\begin{bmatrix}
fx & 0 & cx \\
0 & fy & cy \\
0 & 0 & 1
\end{bmatrix}
$$ - fx和fy是焦距,cx和cy是主点位置。K_00: 9.799200e+02 0.000000e+00 6.900000e+02 0.000000e+00 9.741183e+02 2.486443e+02 0.000000e+00 0.000000e+00 1.000000e+00。
- 这是3x3的内参矩阵,描述相机的焦距和主点位置,格式为:
-
D_00, D_01, D_02, D_03代表畸变系数:
- 包括径向畸变系数(k1, k2, k3)和切向畸变系数(p1, p2)。这些系数用于去除图像中的畸变效果。
- 示例:D_00: -3.745594e-01 2.049385e-01 1.110145e-03 1.379375e-03 -7.084798e-02
-
R_00, R_01, R_02, R_03代表旋转矩阵:
- 这是一个3x3的旋转矩阵,用于将相机坐标系对齐到参考坐标系。对于大多数相机,这个矩阵是单位矩阵,表示没有旋转。
- 示例:R_00: 1.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 1.000000e+00 0.000000e+00 0.000000e+00 0.000000e+00 1.000000e+00
-
T_00, T_01, T_02, T_03代表平移向量:
- 表示相机在参考坐标系中的位置,用平移向量表示。
- 示例:T_01: **-5.370000e-01 5.964270e-03 -1.274584e-02**表示相机01相对于基准相机的平移。
-
R_rect_00, R_rect_01, R_rect_02, R_rect_03代表矫正后的旋转矩阵:
- 表示在立体校正过程中应用的旋转矩阵,用于对图像进行对齐。
- 示例:R_rect_00: 9.999454e-01 7.259129e-03 -7.519551e-03 -7.292213e-03 9.999638e-01 -4.381729e-03 7.487471e-03 4.436324e-03 9.999621e-01
-
P_rect_00, P_rect_01, P_rect_02, P_rect_03代表投影矩阵:
-
用于从3D点投影到图像平面,主要包含相机的内参信息和平移信息。格式为一个3x4矩阵:
-
$$
\begin{bmatrix}
fx & 0 & cx & tx \\
0 & fy & cy & ty \\
0 & 0 & 1 & 0
\end{bmatrix}
$$ -
示例:P_rect_00: 7.188560e+02 0.000000e+00 6.071928e+02 0.000000e+00 0.000000e+00 7.188560e+02 1.852157e+02 0.000000e+00 0.000000e+00 0.000000e+00 1.000000e+00 0.000000e+00
-
注意kitti的00-02,04-10两者配置文件不同,2个配置文件我们需要修改projection_parameters以及extrinsicRotation、extrinsicTranslation
#common parameters
imu_topic: "/kitti/oxts/imu"
image_topic: "/kitti/camera_gray_left/image_raw"
output_path: "/home/ubuntu/output/"
#camera calibration
model_type: PINHOLE
camera_name: camera
image_width: 1241
image_height: 376
distortion_parameters:
k1: 0
k2: 0
p1: 0
p2: 0
projection_parameters:
fx: 7.188560000000e+02
fy: 7.188560000000e+02
cx: 6.071928000000e+02
cy: 1.852157000000e+02
extrinsicRotation: !!opencv-matrix
rows: 3
cols: 3
dt: d
data: [0.00875116, -0.00479609, 0.99995014,
-0.99986423, -0.01400249, 0.00868325,
0.01396015,-0.99989048, -0.00491798]
#Translation from camera frame to imu frame, imu^T_cam
extrinsicTranslation: !!opencv-matrix
rows: 3
cols: 1
dt: d
data: [1.10224299,-0.31907193, 0.74606591]
评估
以序列00为例我们对KITTI数据集GT进行转换
# 下载转换文件
cd ~/dataset/kitti/odometry/dataset/poses && curl -o kitti_poses_and_timestamps_to_trajectory.py https://raw.githubusercontent.com/MichaelGrupp/evo/master/contrib/kitti_poses_and_timestamps_to_trajectory.py
# 转换序列00
python kitti_poses_and_timestamps_to_trajectory.py ~/dataset/kitti/odometry/dataset/poses/00.txt ~/dataset/kitti/odometry/dataset/sequences/00/times.txt ~/dataset/kitti/odometry/dataset/poses/00_tum.txt
因为转换后的GT时间戳是从0开始的,而vins生成的结果不是,所以需要将其换为相对时间,也就是减去第一行的起始时间
# 将vins_result_no_loop.csv的时间戳转换为相对时间
awk 'NR==1{t0=$1} {print $1-t0, $2, $3, $4, $5, $6, $7, $8}' vins_result_no_loop.csv > vins_result_no_loop_relative.csv
# 将vins_result_loop.csv的时间戳转换为相对时间
awk 'NR==1{t0=$1} {print $1-t0, $2, $3, $4, $5, $6, $7, $8}' vins_result_loop.csv > vins_result_loop_relative.csv
现在进行评估
# 无回环
# 轨迹对比
evo_traj tum vins_result_no_loop_relative.csv --ref=/root/dataset/kitti/odometry/dataset/poses/00_tum.txt -p --plot_mode=xyz --align --correct_scale --save_plot traj_plot_no_loop.pdf
# ATE
evo_ape tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_no_loop_relative.csv -va --plot --plot_mode xyz --save_plot ape_plot_no_loop.pdf --save_results ape_results_no_loop.zip
# RPE
# 平移 RPE
evo_rpe tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_no_loop_relative.csv -r trans_part -va --plot --plot_mode xyz --save_plot rpe_plot_translation_no_loop.pdf --save_results rpe_results_translation_no_loop.zip
# 旋转 RPE(单位为角度)
evo_rpe tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_no_loop_relative.csv -r angle_deg -va --plot --plot_mode xyz --save_plot rpe_plot_rotation_no_loop.pdf --save_results rpe_results_rotation_no_loop.zip
# 有回环
# 轨迹对比
evo_traj tum vins_result_loop_relative.csv --ref=/root/dataset/kitti/odometry/dataset/poses/00_tum.txt -p --plot_mode=xyz --align --correct_scale --save_plot traj_plot_loop.pdf
# ATE
evo_ape tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_loop_relative.csv -va --plot --plot_mode xyz --save_plot ape_plot_loop.pdf --save_results ape_results_loop.zip
# RPE
# 平移 RPE
evo_rpe tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_loop_relative.csv -r trans_part -va --plot --plot_mode xyz --save_plot rpe_plot_translation_loop.pdf --save_results rpe_results_translation_loop.zip
# 旋转 RPE(单位为角度)
evo_rpe tum /root/dataset/kitti/odometry/dataset/poses/00_tum.txt vins_result_loop_relative.csv -r angle_deg -va --plot --plot_mode xyz --save_plot rpe_plot_rotation_loop.pdf --save_results rpe_results_rotation_loop.zip
评论区