Ubuntu 20.04 Intel RealSense D435i 相机标定教程

下载编译code_utils

mkdir -p ~/imu_catkin_ws/src
cd ~/imu_catkin_ws/src
catkin_init_workspace
source ~/imu_catkin_ws/devel/setup.bash
git clone https://github.com/gaowenliang/code_utils.git
cd ..
catkin_make

报错:sumpixel_test.cpp:2:10: fatal error: backward.hpp: 没有那个文件或目录,将sumpixel_test.cpp中# include "backward.hpp"改为:#include “code_utils/backward.hpp”。
报错

修改成: cv::IMREAD_UNCHANGED
Mat img1 = imread( "/home/gao/IMG_1.png",  cv::IMREAD_UNCHANGED );
sudo apt-get install libdw-dev
添加
#include 
#include 

下载编译imu_utils

cd ~/imu_catkin_ws/src/
git clone https://github.com/gaowenliang/imu_utils.git
cd ..
catkin_make

安装kalibr 依赖

sudo apt-get install python3-setuptools
 
sudo apt-get install python3-setuptools python3-rosinstall python3-ipython libeigen3-dev libboost-all-dev doxygen libopencv-dev
 
sudo apt-get install libopencv-dev ros-noetic-vision-opencv ros-noetic-image-transport-plugins ros-noetic-cmake-modules python3-software-properties software-properties-common libpoco-dev python3-matplotlib python3-scipy python3-git python3-pip libtbb-dev libblas-dev liblapack-dev python3-catkin-tools libv4l-dev

sudo pip install python-igraph --upgrade

如果不成功,则可以直接安装:
 
sudo apt-get install python-igraph

sudo apt-get install python3-pyx

sudo apt-get install python3-wxgtk4.0
sudo apt-get install python3-igraph
sudo apt-get install python3-scipy

mkdir -p ~/kalibr_ws/src
cd ~/kalibr_ws
source /opt/ros/noetic/setup.bash
catkin init
catkin config --extend /opt/ros/noetic
catkin config --cmake-args -DCMAKE_BUILD_TYPE=Release
cd ~/kalibr_ws/src
git clone https://github.com/ethz-asl/Kalibr.git
cd ~/kalibr_ws
catkin build -DCMAKE_BUILD_TYPE=Release -j32

重新打开一个终端:
echo "source ~/kalibr_ws/devel/setup.bash" >> ~/.bashrc
source ~/.bashrc

IMU标定

创建rs_imu_calibration.launch

找到realsense-ros包,进入/catkin_ws/src/realsense2_camera/launch(路径仅供参考),复制其中的rs_camera.launch,并重命名为rs_imu_calibration.launch(命名随意),并对里面的内容做如下更改

<arg name="unite_imu_method"          default=""/>
//       ########### 改为#############
<arg name="unite_imu_method"          default="linear_interpolation"/>
<arg name="enable_gyro"         default="false"/>  “false” 改为”true”
<arg name="enable_accel"        default="false"/>   “false” 改为”true”
<launch>
  <arg name="serial_no"           default=""/>
  <arg name="usb_port_id"         default=""/>
  <arg name="device_type"         default=""/>
  <arg name="json_file_path"      default=""/>
  <arg name="camera"              default="camera"/>
  <arg name="tf_prefix"           default="$(arg camera)"/>
  <arg name="external_manager"    default="false"/>
  <arg name="manager"             default="realsense2_camera_manager"/>
  <arg name="output"              default="screen"/>
  <arg name="respawn"              default="false"/>

  <arg name="fisheye_width"       default="-1"/>
  <arg name="fisheye_height"      default="-1"/>
  <arg name="enable_fisheye"      default="false"/>

  <arg name="depth_width"         default="640"/>
  <arg name="depth_height"        default="480"/>
  <arg name="enable_depth"        default="true"/>

  <arg name="confidence_width"    default="-1"/>
  <arg name="confidence_height"   default="-1"/>
  <arg name="enable_confidence"   default="true"/>
  <arg name="confidence_fps"      default="-1"/>

  <arg name="infra_width"         default="640"/>
  <arg name="infra_height"        default="480"/>
  <arg name="enable_infra"        default="true"/>
  <arg name="enable_infra1"       default="true"/>
  <arg name="enable_infra2"       default="true"/>
  <arg name="infra_rgb"           default="false"/>

  <arg name="color_width"         default="640"/>
  <arg name="color_height"        default="480"/>
  <arg name="enable_color"        default="true"/>

  <arg name="fisheye_fps"         default="-1"/>
  <arg name="depth_fps"           default="30"/>
  <arg name="infra_fps"           default="30"/>
  <arg name="color_fps"           default="30"/>
  <arg name="gyro_fps"            default="-1"/>
  <arg name="accel_fps"           default="-1"/>
  <arg name="enable_gyro"         default="true"/>
  <arg name="enable_accel"        default="true"/>

  <arg name="enable_pointcloud"         default="false"/>
  <arg name="pointcloud_texture_stream" default="RS2_STREAM_COLOR"/>
  <arg name="pointcloud_texture_index"  default="0"/>
  <arg name="allow_no_texture_points"   default="false"/>
  <arg name="ordered_pc"                default="false"/>

  <arg name="enable_sync"               default="true"/>
  <arg name="align_depth"               default="true"/>

  <arg name="publish_tf"                default="true"/>
  <arg name="tf_publish_rate"           default="0"/>

  <arg name="filters"                   default=""/>
  <arg name="clip_distance"             default="-2"/>
  <arg name="linear_accel_cov"          default="0.01"/>
  <arg name="initial_reset"             default="false"/>
  <arg name="reconnect_timeout"         default="6.0"/>
  <arg name="wait_for_device_timeout"   default="-1.0"/>
  <arg name="unite_imu_method"          default="linear_interpolation"/>
  <arg name="topic_odom_in"             default="odom_in"/>
  <arg name="calib_odom_file"           default=""/>
  <arg name="publish_odom_tf"           default="true"/>
  <arg name="hold_back_imu_for_frames"  default="true"/>

  <arg name="stereo_module/exposure/1"  default="7500"/>
  <arg name="stereo_module/gain/1"      default="16"/>
  <arg name="stereo_module/exposure/2"  default="1"/>
  <arg name="stereo_module/gain/2"      default="16"/>
  
  

  <group ns="$(arg camera)">
    <include file="$(find realsense2_camera)/launch/includes/nodelet.launch.xml">
      <arg name="tf_prefix"                value="$(arg tf_prefix)"/>
      <arg name="external_manager"         value="$(arg external_manager)"/>
      <arg name="manager"                  value="$(arg manager)"/>
      <arg name="output"                   value="$(arg output)"/>
      <arg name="respawn"                  value="$(arg respawn)"/>
      <arg name="serial_no"                value="$(arg serial_no)"/>
      <arg name="usb_port_id"              value="$(arg usb_port_id)"/>
      <arg name="device_type"              value="$(arg device_type)"/>
      <arg name="json_file_path"           value="$(arg json_file_path)"/>

      <arg name="enable_pointcloud"        value="$(arg enable_pointcloud)"/>
      <arg name="pointcloud_texture_stream" value="$(arg pointcloud_texture_stream)"/>
      <arg name="pointcloud_texture_index"  value="$(arg pointcloud_texture_index)"/>
      <arg name="enable_sync"              value="$(arg enable_sync)"/>
      <arg name="align_depth"              value="$(arg align_depth)"/>

      <arg name="fisheye_width"            value="$(arg fisheye_width)"/>
      <arg name="fisheye_height"           value="$(arg fisheye_height)"/>
      <arg name="enable_fisheye"           value="$(arg enable_fisheye)"/>

      <arg name="depth_width"              value="$(arg depth_width)"/>
      <arg name="depth_height"             value="$(arg depth_height)"/>
      <arg name="enable_depth"             value="$(arg enable_depth)"/>

      <arg name="confidence_width"         value="$(arg confidence_width)"/>
      <arg name="confidence_height"        value="$(arg confidence_height)"/>
      <arg name="enable_confidence"        value="$(arg enable_confidence)"/>
      <arg name="confidence_fps"           value="$(arg confidence_fps)"/>

      <arg name="color_width"              value="$(arg color_width)"/>
      <arg name="color_height"             value="$(arg color_height)"/>
      <arg name="enable_color"             value="$(arg enable_color)"/>

      <arg name="infra_width"              value="$(arg infra_width)"/>
      <arg name="infra_height"             value="$(arg infra_height)"/>
      <arg name="enable_infra"             value="$(arg enable_infra)"/>
      <arg name="enable_infra1"            value="$(arg enable_infra1)"/>
      <arg name="enable_infra2"            value="$(arg enable_infra2)"/>
      <arg name="infra_rgb"                value="$(arg infra_rgb)"/>

      <arg name="fisheye_fps"              value="$(arg fisheye_fps)"/>
      <arg name="depth_fps"                value="$(arg depth_fps)"/>
      <arg name="infra_fps"                value="$(arg infra_fps)"/>
      <arg name="color_fps"                value="$(arg color_fps)"/>
      <arg name="gyro_fps"                 value="$(arg gyro_fps)"/>
      <arg name="accel_fps"                value="$(arg accel_fps)"/>
      <arg name="enable_gyro"              value="$(arg enable_gyro)"/>
      <arg name="enable_accel"             value="$(arg enable_accel)"/>

      <arg name="publish_tf"               value="$(arg publish_tf)"/>
      <arg name="tf_publish_rate"          value="$(arg tf_publish_rate)"/>

      <arg name="filters"                  value="$(arg filters)"/>
      <arg name="clip_distance"            value="$(arg clip_distance)"/>
      <arg name="linear_accel_cov"         value="$(arg linear_accel_cov)"/>
      <arg name="initial_reset"            value="$(arg initial_reset)"/>
      <arg name="reconnect_timeout"        value="$(arg reconnect_timeout)"/>
      <arg name="wait_for_device_timeout"  value="$(arg wait_for_device_timeout)"/>
      <arg name="unite_imu_method"         value="$(arg unite_imu_method)"/>
      <arg name="topic_odom_in"            value="$(arg topic_odom_in)"/>
      <arg name="calib_odom_file"          value="$(arg calib_odom_file)"/>
      <arg name="publish_odom_tf"          value="$(arg publish_odom_tf)"/>
      <arg name="stereo_module/exposure/1" value="$(arg stereo_module/exposure/1)"/>
      <arg name="stereo_module/gain/1"     value="$(arg stereo_module/gain/1)"/>
      <arg name="stereo_module/exposure/2" value="$(arg stereo_module/exposure/2)"/>
      <arg name="stereo_module/gain/2"     value="$(arg stereo_module/gain/2)"/>

      <arg name="allow_no_texture_points"  value="$(arg allow_no_texture_points)"/>
      <arg name="ordered_pc"               value="$(arg ordered_pc)"/>
      
    </include>
  </group>
</launch>

将accel和gyro的数据合并得到imu话题,如果不这样做发布的topic中只有加速度计和陀螺仪分开的topic,没有合并的camera/imu 话题。

创建d435i_imu_calibration.launch

在~/imu_catkin_ws/src/imu_utils/launch路径创建d435i_imu_calibration.launch

cd ~/imu_catkin_ws/src/imu_utils/launch
gedit d435i_imu_calibration.launch
<launch>
    <node pkg="imu_utils" type="imu_an" name="imu_an" output="screen">
    	<!--TOPIC名称和上面一致-->
        <param name="imu_topic" type="string" value= "/camera/imu"/>
        <!--imu_name 无所谓-->
        <param name="imu_name" type="string" value= "d435i"/>
        <!--标定结果存放路径-->
        <param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
        <!--数据录制时间-min 120分钟 可以自行修改 一般要大于60-->
        <param name="max_time_min" type="int" value= "120"/>
        <!--采样频率,即是IMU频率,采样频率可以使用rostopic hz /camera/imu查看,设置为400,为后面的rosbag play播放频率-->
        <param name="max_cluster" type="int" value= "400"/>
    </node>
</launch>

录制imu数据包

插上相机,realsense静止放置,放置时间要稍大于d435i_imu_calibration.launch中的录制时间,即大于120分钟。
roscore 
roslaunch realsense2_camera rs_imu_calibration.launch
cd ~/imu_catkin_ws      //等下录制到这个文件夹上
rosbag record -O imu_calibration /camera/imu    // 生成的包名称imu_calibration.bag

目录有一个名为 imu_calibration.bag的文件,其中imu_calibration是bag包的名字,可以更改,/camera/imu是发布的IMU topic,可以通过以下命令查看。

rostopic list -v

运行校准程序

首先激活imu_util工作空间的setup.bash

source ~/imu_catkin_ws/devel/setup.bash
roslaunch imu_utils d435i_imu_calibration.launch

回放数据包

  打开新的终端,cd 存放imu_calibration.bag的路径。
source ~/imu_catkin_ws/devel/setup.sh 
cd ~/imu_catkin_ws //数据包在这个文件夹下
rosbag play -r 400 imu_calibration.bag  其中 -r 400是指400速播放bag数据

标定结果

标定结束后在imu_catkin_ws/src/imu_utils/data中生成许多文件,其中d435i_imu_param.yaml就是我们想要的结果
Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第1张图片这是我的

%YAML:1.0
---
type: IMU
name: d435i
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 2.3713647521442301e-03
      gyr_w: 1.6634786328395575e-05
   x-axis:
      gyr_n: 2.5527723048677621e-03
      gyr_w: 1.8248792841502254e-05
   y-axis:
      gyr_n: 3.5989014238402488e-03
      gyr_w: 2.4626070373926136e-05
   z-axis:
      gyr_n: 9.6242052772467902e-04
      gyr_w: 7.0294957697583380e-06
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 1.2272815309641657e-02
      acc_w: 2.2269630970713836e-04
   x-axis:
      acc_n: 1.0855035063883016e-02
      acc_w: 1.9977097068680263e-04
   y-axis:
      acc_n: 1.2175166782188903e-02
      acc_w: 1.8151134885911570e-04
   z-axis:
      acc_n: 1.3788244082853051e-02
      acc_w: 2.8680660957549681e-04

realsense自带的参数:

roslaunch realsense2_camera rs_camera.launch
rostopic echo /camera/accel/imu_info 
rostopic echo /camera/gyro/imu_info

双目标定

创建april_6x6_A4.yaml文件

target_type: 'aprilgrid' #gridtype
tagCols: 6               #number of apriltags
tagRows: 6               #number of apriltags
tagSize: 0.021           #这个为a要亲自拿尺子量一下
tagSpacing: 0.308          #这个就是b/a

Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第2张图片

关闭结构光

roslaunch realsense2_camera rs_imu_calibration.launch
rosrun rqt_reconfigure rqt_reconfigure

Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第3张图片

rviz

Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第4张图片

修改相机的帧数(官方推荐是4Hz)

rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left
rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right

录制ROS数据包

rosbag record -O multicameras_calibration /infra_left /infra_right /color

bag文件属性信息:

rosbag info multicameras_calibration.bag

使用Kalibr标定

注意:标定前先关掉相机,否者会报错

source devel/setup.bash
//kalibr_calibrate_cameras --target /位置/文件名.yaml --bag /位置/camd435i.bag --bag-from-to 26 100 --models pinhole-radtan --topics /color --show-extraction

kalibr_calibrate_cameras --target april_6x6_A4.yaml --bag  multicameras_calibration.bag --models pinhole-equi pinhole-equi pinhole-equi --topics /infra_left /infra_right /color --bag-from-to 10 100 --show-extraction

报错:ImportError: No module named wx
sudo apt-get install python3-wxgtk4.0
sudo apt-get install python3-igraph
sudo apt-get install python3-scipy

Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第5张图片

multicameras_calibration-camchain.yaml

cam0:
  cam_overlaps: [1, 2]
  camera_model: pinhole
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  distortion_model: equidistant
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  resolution: [640, 480]
  rostopic: /infra_left
cam1:
  T_cn_cnm1:
  - [0.9994978959284028, -0.0004960676303391997, 0.031681381781581835, -0.049405645049756246]
  - [0.0006353578883581325, 0.9999901766268545, -0.00438668099301463, 1.6793675995192084e-05]
  - [-0.03167889447310175, 0.004404607438456279, 0.9994883926681007, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0, 2]
  camera_model: pinhole
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  distortion_model: equidistant
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  resolution: [640, 480]
  rostopic: /infra_right
cam2:
  T_cn_cnm1:
  - [0.9991511714157386, 0.020802684247929682, -0.03555537915201736, 0.06452938946495283]
  - [-0.020609341536016703, 0.9997708061292826, 0.005795709884189747, -0.0014703526867445732]
  - [0.035667796399758, -0.005058017367587453, 0.9993509017158588, -0.0007200130467801373]
  - [0.0, 0.0, 0.0, 1.0]
  cam_overlaps: [0, 1]
  camera_model: pinhole
  distortion_coeffs: [0.3039064497137355, 2.82427913352034, -12.205548022168468, 18.250389840037823]
  distortion_model: equidistant
  intrinsics: [617.5837233756131, 622.6983038282931, 334.8320211033824, 228.30163838242865]
  resolution: [640, 480]
  rostopic: /color

multicameras_calibration-results-cam.txt

Calibration results 
====================
Camera-system parameters:
cam0 (/infra_left):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [0.42241274 0.20864813 0.39792383 0.58980037] +- [0.00610485 0.032712   0.08188243 0.11031642]
    projection: [394.73897935 397.07609983 328.08812328 229.97427393] +- [0.19306522 0.20612486 0.24778634 0.28703445]
    reprojection error: [0.000124, 0.000100] +- [0.657585, 0.919360]

cam1 (/infra_right):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [ 0.51276066 -0.5373699   3.8471623  -5.20463483] +- [0.00641909 0.03425317 0.07009558 0.09962364]
    projection: [395.31081334 396.67650877 315.7121625  232.01383312] +- [0.21098982 0.21177575 0.24814252 0.27660172]
    reprojection error: [0.000054, 0.000101] +- [0.574125, 0.899336]

cam2 (/color):
    type: <class 'aslam_cv.libaslam_cv_python.EquidistantDistortedPinholeCameraGeometry'>
    distortion: [  0.30390645   2.82427913 -12.20554802  18.25038984] +- [0.01032272 0.08120627 0.17338616 0.1112109 ]
    projection: [617.58372338 622.69830383 334.8320211  228.30163838] +- [0.2006613  0.19860848 0.35937867 0.42222736]
    reprojection error: [0.000159, 0.000139] +- [0.970352, 1.187701]

baseline T_1_0:
    q: [-0.0021981  -0.0158421  -0.00028289  0.99987205] +- [0.00041294 0.00031982 0.00009754]
    t: [-0.04940565  0.00001679  0.00142563] +- [0.00005321 0.00004922 0.0001863 ]

baseline T_2_1:
    q: [0.00271402 0.01780964 0.01035524 0.99978409] +- [0.00043723 0.00034848 0.00010065]
    t: [ 0.06452939 -0.00147035 -0.00072001] +- [0.00005198 0.00004369 0.00017821]



Target configuration
====================

  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]

imu+双目标定

创建:camchain.yaml:

gedit camchain.yaml
cam0:
  camera_model: pinhole
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  distortion_model: equidistant
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  rostopic: /infra_left
  resolution: [640, 480]
cam1:
  T_cn_cnm1:
  - [0.9994978959284028, -0.0004960676303391997, 0.031681381781581835, -0.049405645049756246]
  - [0.0006353578883581325, 0.9999901766268545, -0.00438668099301463, 1.6793675995192084e-05]
  - [-0.03167889447310175, 0.004404607438456279, 0.9994883926681007, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  distortion_model: equidistant
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  
  rostopic: /infra_right
  resolution: [640, 480]

创建: imu.yaml
gedit imu.yaml

#Accelerometers
accelerometer_noise_density: 1.2272815309641657e-02   #Noise density (continuous-time)
accelerometer_random_walk:   2.2269630970713836e-04   #Bias random walk

#Gyroscopes
gyroscope_noise_density:     2.3713647521442301e-03   #Noise density (continuous-time)
gyroscope_random_walk:       1.6634786328395575e-05   #Bias random walk

rostopic:                    /imu      #the IMU ROS topic
update_rate:                 200.0      #Hz (for discretization of the values above)

修改:rs_imu_stereo.launch

复制realsense-ros包中rs_camera.launch,重命名为rs_imu_stereo.launch,更改内容为

<arg name="enable_sync"               default="false"/>
//改为:
<arg name="enable_sync"               default="true"/>

这样来使imu和双目数据时间对齐

<arg name="unite_imu_method"          default=""/>
//改为
<arg name="unite_imu_method"          default="linear_interpolation"/>

开启相机

roslaunch realsense2_camera rs_imu_calibration.launch

关闭IR结构光,参考上面

rosrun rqt_reconfigure rqt_reconfigure

录制 相机 和 imu 的联合数据

调整 相机 和 imu 的 topic 的发布频率以及以新的topic名发布它们,其中双目图像的发布频率改为20Hz,imu发布频率改为200Hz

rosrun topic_tools throttle messages /camera/color/image_raw 4.0 /color
rosrun topic_tools throttle messages /camera/infra1/image_rect_raw 4.0 /infra_left
rosrun topic_tools throttle messages /camera/infra2/image_rect_raw 4.0 /infra_right
rosrun topic_tools throttle messages /camera/imu 200.0 /imu
开始录制
rosbag record /infra_left /infra_right /imu -O  imu_stereo.bag

注意:完成录制后把相机关掉,和其他的发布的话题也关闭

运行

rosrun  kalibr kalibr_calibrate_imu_camera --bag  imu_stereo.bag --cam  camchain.yaml --imu imu.yaml --target april_6x6_A4.yaml --bag-from-to 10 50 --show-extraction

Ubuntu 20.04 Intel RealSense D435i 相机标定教程_第6张图片

其中:

--target ../Aprilgrid/april_6x6_50x50cm_A4.yaml是标定板的配置文件,如果选择棋格盘,注意targetCols和targetRows表示的是内侧角点的数量,不是格子数量。
--bag ../multicameras_calibration_2020-10-29-20-19-06.bag是录制的数据包;
--models pinhole-equi pinhole-equi pinhole-equi表示三个摄像头的相机模型和畸变模型(解释参考https://github.com/ethz-asl/kalibr/wiki/supported-models,根据需要选取);
--topics /infra_left /infra_right /color表示三个摄像头对应的拍摄的数据话题;
–bag-from-to 10 100表示处理bag中10-100秒的数据。(我在实验过程中没有加–bag-from-to 10 100,所以处理的是bag里所有的数据,标定时间比较长)
–show-extraction表示显示检测特征点的过程。
这些参数可以相应的调整。
imu_stereo-camchain-imucam.yaml
cam0:
  T_cam_imu:
  - [0.9998706466800502, -0.0005514101338320241, 0.016074385042181456, -0.009727195729487593]
  - [0.0004398826122011197, 0.9999758147457678, 0.0069409240614884855, 0.002409052480480027]
  - [-0.016077823574958232, -0.006932955387435725, 0.99984670710999, -0.02941555702845951]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  distortion_coeffs: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  distortion_model: equidistant
  intrinsics: [394.73897935327875, 397.07609983064, 328.08812327934135, 229.9742739261273]
  resolution: [640, 480]
  rostopic: /infra_left
  timeshift_cam_imu: -0.01115013714316784
cam1:
  T_cam_imu:
  - [0.9988590216788663, -0.0012668345078801814, 0.047739396111261004, -0.06006107726015477]
  - [0.0011456822768613126, 0.9999960539310532, 0.0025650603195308754, 0.0025486789058311375]
  - [-0.04774245723524004, -0.0025074394612811563, 0.9988565315021419, -0.02765611642952738]
  - [0.0, 0.0, 0.0, 1.0]
  T_cn_cnm1:
  - [0.9994978959284052, -0.0004960676303391998, 0.03168138178158184, -0.049405645049756246]
  - [0.0006353578883581324, 0.999990176626857, -0.004386680993014631, 1.6793675995192084e-05]
  - [-0.03167889447310176, 0.00440460743845628, 0.9994883926681032, 0.0014256336467758425]
  - [0.0, 0.0, 0.0, 1.0]
  camera_model: pinhole
  distortion_coeffs: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  distortion_model: equidistant
  intrinsics: [395.31081333647796, 396.67650876842976, 315.71216250025896, 232.01383312375893]
  resolution: [640, 480]
  rostopic: /infra_right
  timeshift_cam_imu: -0.01179951195993147
imu_stereo-imu.yaml
imu0:
  T_i_b:
  - [1.0, 0.0, 0.0, 0.0]
  - [0.0, 1.0, 0.0, 0.0]
  - [0.0, 0.0, 1.0, 0.0]
  - [0.0, 0.0, 0.0, 1.0]
  accelerometer_noise_density: 0.012272815309641657
  accelerometer_random_walk: 0.00022269630970713836
  gyroscope_noise_density: 0.00237136475214423
  gyroscope_random_walk: 1.6634786328395575e-05
  model: calibrated
  rostopic: /imu
  time_offset: 0.0
  update_rate: 200.0
imu_stereo-results-imucam.txt
Calibration results
===================
Normalized Residuals
----------------------------
Reprojection error (cam0):     mean 0.3935652501477467, median 0.34647466427290496, std: 0.24000390105212327
Reprojection error (cam1):     mean 0.40672475151297405, median 0.35408707621982244, std: 0.25805651611847996
Gyroscope error (imu0):        mean 0.25718333066848914, median 0.1978018986985239, std: 0.1868255561754322
Accelerometer error (imu0):    mean 0.16651624576366744, median 0.1500647834791136, std: 0.08979584592008485

Residuals
----------------------------
Reprojection error (cam0) [px]:     mean 0.3935652501477467, median 0.34647466427290496, std: 0.24000390105212327
Reprojection error (cam1) [px]:     mean 0.40672475151297405, median 0.35408707621982244, std: 0.25805651611847996
Gyroscope error (imu0) [rad/s]:     mean 0.008624941825093504, median 0.006633516506428987, std: 0.006265412106085885
Accelerometer error (imu0) [m/s^2]: mean 0.028901195472671417, median 0.026045816857109837, std: 0.015585309911764239

Transformation (cam0):
-----------------------
T_ci:  (imu0 to cam0): 
[[ 0.99987065 -0.00055141  0.01607439 -0.0097272 ]
 [ 0.00043988  0.99997581  0.00694092  0.00240905]
 [-0.01607782 -0.00693296  0.99984671 -0.02941556]
 [ 0.          0.          0.          1.        ]]

T_ic:  (cam0 to imu0): 
[[ 0.99987065  0.00043988 -0.01607782  0.00925194]
 [-0.00055141  0.99997581 -0.00693296 -0.00261829]
 [ 0.01607439  0.00694092  0.99984671  0.02955069]
 [ 0.          0.          0.          1.        ]]

timeshift cam0 to imu0: [s] (t_imu = t_cam + shift)
-0.01115013714316784


Transformation (cam1):
-----------------------
T_ci:  (imu0 to cam1): 
[[ 0.99885902 -0.00126683  0.0477394  -0.06006108]
 [ 0.00114568  0.99999605  0.00256506  0.00254868]
 [-0.04774246 -0.00250744  0.99885653 -0.02765612]
 [ 0.          0.          0.          1.        ]]

T_ic:  (cam1 to imu0): 
[[ 0.99885902  0.00114568 -0.04774246  0.05866926]
 [-0.00126683  0.99999605 -0.00250744 -0.0026941 ]
 [ 0.0477394   0.00256506  0.99885653  0.03048523]
 [ 0.          0.          0.          1.        ]]

timeshift cam1 to imu0: [s] (t_imu = t_cam + shift)
-0.01179951195993147

Baselines:
----------
Baseline (cam0 to cam1): 
[[ 0.9994979  -0.00049607  0.03168138 -0.04940565]
 [ 0.00063536  0.99999018 -0.00438668  0.00001679]
 [-0.03167889  0.00440461  0.99948839  0.00142563]
 [ 0.          0.          0.          1.        ]]
baseline norm:  0.04942621243940179 [m]


Gravity vector in target coords: [m/s^2]
[-0.33626366 -9.79119923 -0.43332124]


Calibration configuration
=========================

cam0
-----
  Camera model: pinhole
  Focal length: [394.73897935327875, 397.07609983064]
  Principal point: [328.08812327934135, 229.9742739261273]
  Distortion model: equidistant
  Distortion coefficients: [0.42241273556155506, 0.20864813180833605, 0.3979238261062836, 0.5898003650060837]
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]

cam1
-----
  Camera model: pinhole
  Focal length: [395.31081333647796, 396.67650876842976]
  Principal point: [315.71216250025896, 232.01383312375893]
  Distortion model: equidistant
  Distortion coefficients: [0.5127606598499351, -0.5373699037573214, 3.847162303528836, -5.204634833610096]
  Type: aprilgrid
  Tags: 
    Rows: 6
    Cols: 6
    Size: 0.021 [m]
    Spacing 0.006468000000000001 [m]



IMU configuration
=================

IMU0:
 ----------------------------
  Model: calibrated
  Update rate: 200.0
  Accelerometer:
    Noise density: 0.012272815309641657 
    Noise density (discrete): 0.17356381859395387 
    Random walk: 0.00022269630970713836
  Gyroscope:
    Noise density: 0.00237136475214423
    Noise density (discrete): 0.03353616193815883 
    Random walk: 1.6634786328395575e-05
  T_ib (imu0 to imu0)
    [[1. 0. 0. 0.]
     [0. 1. 0. 0.]
     [0. 0. 1. 0.]
     [0. 0. 0. 1.]]
  time offset with respect to IMU0: 0.0 [s]

参考
https://blog.csdn.net/qq_38364548/article/details/124917067
https://blog.csdn.net/qq_44998513/article/details/132713079

你可能感兴趣的:(#,C++视觉处理,ubuntu,数码相机,linux)