D435i标定摄像头和IMU笔记三(IMU标定篇)
前言:使用realsense官网驱动进行标定
参考视频
D435i标定摄像头和IMU笔记一(配置环境篇)
D435i标定摄像头和IMU笔记二(RGB摄像头标定篇)
D435i标定摄像头和IMU笔记二-2(RGB+双目多摄像头标定篇)
D435i标定摄像头和IMU笔记三(IMU标定篇)
D435i标定摄像头和IMU笔记四(RGB摄像头和IMU联合标定篇)
D435i标定摄像头和IMU笔记四-2(双目摄像头与IMU联合标定篇)
一、RealSense官网驱动标定IMUbias和三个轴的对齐
1.1 驱动安装
D435i标定摄像头和IMU教程一(配置环境篇)中3.2.1
1.2 标定
- 确保设备能够被检测到。
- 切换到标定程序所在目录
cd ~/librealsense/tools/rs-imu-calibration
- 运行标定程序
如果是python2
python rs-imu-calibration.py
如果是python3
python3 rs-imu-calibration.py
Writing files:
accel_y.txt
gyro_y.txt
[-0.00120186 -0.0018734 0.00066989]
[1000 1000 1000 1000 1000 1000]
using 6000 measurements.
[[ 1.01887676 0.03164905 0.01183849]
[-0.00274971 1.02552497 0.04045647]
[ 0.00388669 0.00146226 1.01379306]
[ 0.24034104 0.24627437 0.17273827]]
residuals: [ 15.13285754 317.9954511 322.56032617]
rank: 4
singular: [ 439.06403525 433.77356534 418.40952537 77.27478454]
norm (raw data ): 9.619754
norm (fixed data): 9.799943 A good calibration will be near 9.806650
2)生成文档
accel_y.txt,calibration.bin, calibration.json, gyro_y.txt
二、港科大imu_utils标定IMU随机游走
2.1 环境及文件准备
1) 安装code_utils
- 安装依赖
sudo apt-get install libdw-dev
cd ~/imuCali_ws/src
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make
问题一:fatal error: backward.hpp: 没有那个文件或目录 #include “backward.hpp”
解决办法:修改~/imuCali_ws/src/code_utils/src/sumpixel_test.hpp文件中的头文件为:
#include "code_utils/backward.hpp"
2) 安装imu_utils(必须先编译上面的code_utils)
cd ~/imuCali_ws/src
git clone https://github.com/gaowenliang/imu_utils.git
cd ..
catkin_make
3) 添加工作空间path
echo "source ~/imuCali_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc
4) 增加D435i的IMU标定launch
在/imu_utils/launch/文件夹下面添加一个D435i_imuCali.launch,内容如下:
<launch>
<node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
<param name="imu_topic" type="string" value= "/camera/imu"/>
<param name="imu_name" type="string" value= "Realsense"/>
<param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
<param name="max_time_min" type="int" value= "120"/>
<param name="max_cluster" type="int" value= "100"/>
</node>
</launch>
max_time_min:标定最短时长,可以自行更改,要比实际录制短,要不然不会停。
imu_name:标定生成的yaml文件就会是这个参数开头的,比如我的Realsense_imu_param.yaml
data_save_path:注意修改标定保存文件地址
2.2 录制rosbag
- 确保realsense中launch配置。参考3.2.2
- 将设备静止不动,录制两个小时的rosbag。
roslaunch realsense2_camera rs_camera.launch
rosbag record -O D435i_imu /camera/imu
当然也可以边运行realsense边标定
2.3 标定
400倍速回放rosbag,并运行launch文件进行标定
roslaunch imu_utils D435i_imuCali.launch
rosbag play -r 400 D435i_imu.bag
2.3 标定结果
会在/imu_utils/data文件夹下生成标定结果,Realsense_imu_param.yaml:
%YAML:1.0
---
type: IMU
name: Realsense
Gyr:
unit: " rad/s"
avg-axis:
gyr_n: 3.0285738136227973e-03
gyr_w: 3.0037305993425518e-05
x-axis:
gyr_n: 2.8531446471369171e-03
gyr_w: 1.6461435038695691e-05
y-axis:
gyr_n: 4.7821836176415505e-03
gyr_w: 5.7314346898355047e-05
z-axis:
gyr_n: 1.4503931760899249e-03
gyr_w: 1.6336136043225812e-05
Acc:
unit: " m/s^2"
avg-axis:
acc_n: 2.7260051759783317e-02
acc_w: 5.7981798863344241e-04
x-axis:
acc_n: 2.7072982983966404e-02
acc_w: 7.6419397302127524e-04
y-axis:
acc_n: 2.4941077177495441e-02
acc_w: 4.8124818065445443e-04
z-axis:
acc_n: 2.9766095117888112e-02
acc_w: 4.9401181222459762e-04
2.4 为联合标定准备的参数
上面:
Gyr:
avg-axis:
gyr_n: 3.0285738136227973e-03
gyr_w: 3.0037305993425518e-05
Acc:
avg-axis:
acc_n: 2.7260051759783317e-02
acc_w: 5.7981798863344241e-04
三、kalibr_allan标定IMU随机游走
还没做。