zed2i中imu内参的标定
参考:
https://blog.csdn.net/weixin_42681311/article/details/126109617
https://blog.csdn.net/weixin_43135184/article/details/123444090
值得注意,imu内参的标定其实不是那么重要,大致上给一个值应该影响不大,比如下面是官方给的参数imu-params.yaml
,直接拿来用应该也影响不大:
#Accelerometers
accelerometer_noise_density: 1.4e-03 #Noise density (continuous-time)
accelerometer_random_walk: 8.0e-05 #Bias random walk
#Gyroscopes
gyroscope_noise_density: 8.6e-05 #Noise density (continuous-time)
gyroscope_random_walk: 2.2e-06 #Bias random walk
rostopic: /zed2i/zed_node/imu/data_raw #the IMU ROS topic
update_rate: 400.0 #Hz (for discretization of the values above)
值得注意的是,zed2i提供的imu话题有两个,一个是/zed2i/zed_node/imu/data
,一个是zed2i/zed_node/imu/data_raw
,前者应该是在后者基础上做了一定的滤波处理,我后面采用了前者。
如果自行标定,可以采用imu_utils
,项目链接。安装时要先下载code_utils
在workspace中,并且先catkin_make
完,然后再放入imu_utils
,再次catkin_make
。
1. 录制
找个地方放置相机,保持静止,录制2个多小时。
source ~/桌面/zed/ros/catkin_ws/devel/setup.bash
roslaunch zed_wrapper zed2i.launch
rosbag record -O /zed2i/zed_node/imu/data /zed2i/zed_node/imu/data
2. 标定
在~/桌面/liweidong/imu_utils_ws/src/imu_utils-master/launch
下创建文件zed2i.launch
,内容如下:
<launch>
<node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
<param name="imu_topic" type="string" value= "/zed2i/zed_node/imu/data"/>
<param name="imu_name" type="string" value= "zed2i"/>
<param name="data_save_path" type="string" value= "$(find imu_utils)/data/zed2i/"/>
<param name="max_time_min" type="int" value= "120"/>
<param name="max_cluster" type="int" value= "100"/>
</node>
</launch>
其中,需要注意max_time_min
是要标定的时间长度(分钟),应当与录制的bag的时间长度一致,或者短一点,切不可比录制时间还长,不然标定会一直卡住。接下来进行标定:
source ~/桌面/liweidong/imu_utils_ws/devel/setup.bash
roslaunch imu_utils zed2i.launch
rosbag play -r 200 xxx.bag
这里将bag的播放速度加速为200倍。最后得到标定结果如下:
%YAML:1.0
---
type: IMU
name: zed2i
Gyr:
unit: " rad/s"
avg-axis:
gyr_n: 1.9907361538269255e-03
gyr_w: 3.9258772229758955e-05
x-axis:
gyr_n: 1.7828571086570984e-03
gyr_w: 3.7532900901648101e-05
y-axis:
gyr_n: 2.3517096252728287e-03
gyr_w: 4.4818844873917894e-05
z-axis:
gyr_n: 1.8376417275508495e-03
gyr_w: 3.5424570913710870e-05
Acc:
unit: " m/s^2"
avg-axis:
acc_n: 2.1014029979335751e-02
acc_w: 4.5856543488109373e-04
x-axis:
acc_n: 2.1554014733711498e-02
acc_w: 3.7798512464262918e-04
y-axis:
acc_n: 2.0157270328875061e-02
acc_w: 5.3636489912956887e-04
z-axis:
acc_n: 2.1330804875420693e-02
acc_w: 4.6134628087108308e-04
用得到的数据替换最上边官方给的结果imu_params.yaml
#Accelerometers
accelerometer_noise_density: 2.1014029979335751e-02 #Noise density (continuous-time)
accelerometer_random_walk: 4.5856543488109373e-04 #Bias random walk
#Gyroscopes
gyroscope_noise_density: 1.9907361538269255e-03 #Noise density (continuous-time)
gyroscope_random_walk: 3.9258772229758955e-05 #Bias random walk
rostopic: /zed2i/zed_node/imu/data #the IMU ROS topic
update_rate: 400.0 #Hz (for discretization of the values above)
标定zed2i中cam-imu之间的外参
将相机标定时录制的bag,相机标定得到的结果camchain.yaml
、标定板参数文件aprilgrid.yaml
和imu标定得到的结果imu-params.yaml
放在同个目录下。
执行以下命令对外参进行标定:
rosrun kalibr kalibr_calibrate_imu_camera --bag xxx.bag --cam camchain.yaml --imu imu-params.yaml --target aprilgrid.yaml
需要等几分钟,然后就会得到标定结果