Kalibr标定d435i

figure it out.

最近准备使用realsense d435i,先对其进行标定。整体环境是基于ROS的,因为Kalibr是在ROS环境下。大致过程如下:

  imu标定  ----> 双目标定----> 双目+imu联合标定

Notes:

 1) 先配置好realsense的驱动,包括ROS环境下的;

 2)realsense的ROS launch文件中有将acc和gyr两个整成一个imu话题的配置,设置一下就好,对应为:         

 
 

其中,linear_interpolation可以换成其他的,具体是啥目前不太清楚。

3)在双目标定的时候,录制bag包控制一下两个摄像头的频率,可以用ROS提供的节流命令来做。因为当频率很高如30HZ的时候,后面在标定的时候会报出这样的错误

[ERROR] [1560840525.647491]: [TargetViewTable]: Tried to add second view to a given cameraId & timestamp. Maybe try to reduce the approximate syncing tolerance..

不过这个错误好像不管也能继续下去,但不知道对标定结果有没有影响。ROS的截流命令如下(参考贺博士的博客):

rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 5.0 /left

rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 5.0 /right

4)标定imu时,配置imu_utils和code_utils时,先catkin_make code_utils后再将imu_utils放进去catkin_make, 不然会报错,还有会报出一个头文件的小错误,按照github issues上的修改一下就行,报出的错误如下:

fatal error: backward.hpp: No such file or directory

5)标定imu时的launch文件记得修改max_time_min对应的参数,默认是120,意味着两个小时,要是你的ros包里的imu数据长度没有两个小时,就进行不下去,始终停留在wait for imu data这里。

6)标定imu时对应的launch文件大致如下:


    
        
        
        
        
        
    

1.imu标定

在catkin工作空间下按照配置说明配置好imu_utils,对imu进行Allan方差标定。输入为一定时长的包含imu数据的bag包,注意代码中要求bag包里的时间长度不能小于10min,另外,在采集imu数据这段时间内要保持传感器静置。标定结束后会在data文件夹下得到对应的一系列以bag包命名的标定结果,主要看对应的yaml文件

%YAML:1.0
---
type: IMU
name: d435i
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 3.0247286551398204e-03
      gyr_w: 2.2901170839457266e-05
   x-axis:
      gyr_n: 3.0486121293259861e-03
      gyr_w: 2.3588043857742811e-05
   y-axis:
      gyr_n: 3.9906956275203298e-03
      gyr_w: 3.8510954801834231e-05
   z-axis:
      gyr_n: 2.0348782085731448e-03
      gyr_w: 6.6045138587947500e-06
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 2.8949600741350223e-02
      acc_w: 4.5552273079824281e-04
   x-axis:
      acc_n: 2.4870413946165581e-02
      acc_w: 3.5175805157083910e-04
   y-axis:
      acc_n: 2.7808521377206314e-02
      acc_w: 4.8805723243924246e-04
   z-axis:
      acc_n: 3.4169866900678782e-02
      acc_w: 5.2675290838464703e-04

然后将Acc和Gyr的第一组平均数据拷贝到kalibr对应的imu.yml文件中,

rostopic: /camera/imu
update_rate: 200.0 #Hz

accelerometer_noise_density: 2.89e-01 #continous
accelerometer_random_walk: 4.55e-04 
gyroscope_noise_density: 3.02e-03 #continous
gyroscope_random_walk: 2.29e-05

2.双目标定和双目+imu标定

先配置好kalibr工作空间,这里开始的过程和别的参考过程并无二致,记录一下命令,

kalibr_calibrate_cameras --bag ~/workspace/datasets/d435i_calib.bag --topics /camera/infra1/image_rect_raw /camera/infra2/image_rect_raw --models pinhole-radtan pinhole-radtan --target april_6x6_8.8x8.8cm.yaml

双目这里采用的是pin-hole +radtan模型,但是标定出来的重投影误差特别大,这个问题目前还没有解决,准备换个model试试看。

kalibr_calibrate_imu_camera --target april_6x6_8.8x8.8cm.yaml --cam camchain-homeliuzhenworkspacedatasetsd435i_calib.yaml --imu imu_d435i.yaml --bag  ~/workspace/datasets/d435i_calib.bag

这个是标定imu和camera的。

你可能感兴趣的:(ubuntu,摄像头标定)