D435i相机标定(不同标定方法总结)

一、张正友标定法用Matlab实现相机标定

棋盘格规格:390 :12X9 角点数:11X8 方格尺寸:20mm

二、kalibr标定

2.1安装应用包

2.1.1 Ceres-Solver安装

git clone https://github.com/ceres-solver/ceres-solver

依赖:

在这里插# Cmake
sudo apt-get install cmake
# google-glog + gflags
sudo apt-get install libgoogle-glog-dev
# BLAS & LAPAC
sudo apt-get install libatlas-base-dev
# Eigen3
sudo apt-get install libeigen3-dev
# SuiteSparse和CXSparse(可选)
# - 如果您希望将Ceres构建为*static*库(默认),则可以在Ubuntu主包repository中使用SuiteSparse包
sudo apt-get install libsuitesparse-dev
sudo apt-get update
sudo apt-get install libsuitesparse-dev
入代码片

安装:

cd ceres-solver
mkdir build
cd build
camke ..
make
sudo make install

2.1.2 code_utils 安装

code_utils下载地址为: https://github.com/gaowenliang/code_utils

cd ~/catkin_biao/src
git clone https://github.com/gaowenliang/code_utils
cd ..
catkin_make

编译错误:code_utils-master/src/sumpixel_test.cpp:2:24: fatal error: backward.hpp:No such file or directory
修改:在code_utils下面找到sumpixel_test.cpp,修改#include "backward.hpp"为 #include “code_utils/backward.hpp”,再编译。

2.1.3 imu_utils安装

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

注:先编译code_utils再放置imu_utils文件,不要同时把imu_utilscode_utils一起放到src下进行编译。

2.1.4 kalibr 安装

cd ~/catkin_biao/src
git clone https://github.com/ethz-asl/Kalibr.git
cd ..
catkin_make

注错误:
D435i相机标定(不同标定方法总结)_第1张图片解决:修改CMakeLists.txt内容:

ExternalProject_Add(suitesparse_src
  CMAKE_ARGS -DCMAKE_C_COMPILER=${
     CMAKE_C_COMPILER} -DCMAKE_CXX_COMPILER=${
     CMAKE_CXX_COMPILER}
  DOWNLOAD_COMMAND rm -f SuiteSparse-${
     VERSION}.tar.gz && wget http://faculty.cse.tamu.edu/davis/SuiteSparse/SuiteSparse-${
     VERSION}.tar.gz
  PATCH_COMMAND tar -xzf ../SuiteSparse-${
     VERSION}.tar.gz && rm -rf ../suitesparse_src-build/SuiteSparse && sed -i.bu "s/\\/usr\\/local\\/lib/..\\/lib/g" SuiteSparse/SuiteSparse_config/SuiteSparse_config.mk && sed -i.bu "s/\\/usr\\/local\\/include/..\\/include/g" SuiteSparse/SuiteSparse_config/SuiteSparse_config.mk && mv SuiteSparse ../suitesparse_src-build/
  CONFIGURE_COMMAND ""
  BUILD_COMMAND cd SuiteSparse && make library -j8 -l8
  INSTALL_COMMAND cd SuiteSparse && mkdir -p lib && mkdir -p include && make install && cd lib && cp libamd.2.3.1.a libcamd.2.3.1.a libcholmod.2.1.2.a libcxsparse.3.1.2.a libldl.2.1.0.a libspqr.1.3.1.a libumfpack.5.6.2.a libamd.a	libcamd.a libcholmod.a	libcxsparse.a libldl.a libspqr.a libumfpack.a libbtf.1.2.0.a	libccolamd.2.8.0.a libcolamd.2.8.0.a libklu.1.2.1.a librbio.2.1.1.a libsuitesparseconfig.4.2.1.a libbtf.a	libccolamd.a libcolamd.a		libklu.a librbio.a libsuitesparseconfig.a  ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_LIB_DESTINATION}/ && cd .. && mkdir -p ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_INCLUDE_DESTINATION}/suitesparse && cd include && cp amd.h cholmod_matrixops.h SuiteSparseQR_definitions.h umfpack_load_symbolic.h umfpack_save_symbolic.h btf.h cholmod_modify.h SuiteSparseQR.hpp umfpack_numeric.h umfpack_scale.h camd.h cholmod_partition.h umfpack_col_to_triplet.h umfpack_qsymbolic.h umfpack_solve.h ccolamd.h cholmod_supernodal.h umfpack_defaults.h umfpack_report_control.h umfpack_symbolic.h cholmod_blas.h cholmod_template.h umfpack_free_numeric.h umfpack_report_info.h umfpack_tictoc.h cholmod_camd.h colamd.h umfpack_free_symbolic.h umfpack_report_matrix.h umfpack_timer.h cholmod_check.h cs.h umfpack_get_determinant.h umfpack_report_numeric.h umfpack_transpose.h cholmod_cholesky.h klu.h umfpack_get_lunz.h umfpack_report_perm.h umfpack_triplet_to_col.h cholmod_complexity.h ldl.h umfpack_get_numeric.h umfpack_report_status.h umfpack_wsolve.h cholmod_config.h RBio.h umfpack_get_symbolic.h umfpack_report_symbolic.h cholmod_core.h spqr.hpp umfpack_global.h umfpack_report_triplet.h cholmod.h SuiteSparse_config.h umfpack.h umfpack_report_vector.h cholmod_io64.h SuiteSparseQR_C.h umfpack_load_numeric.h umfpack_save_numeric.h ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_INCLUDE_DESTINATION}/suitesparse 
)

修改为:

  ExternalProject_Add(suitesparse_src
  CMAKE_ARGS -DCMAKE_C_COMPILER=${
     CMAKE_C_COMPILER} -DCMAKE_CXX_COMPILER=${
     CMAKE_CXX_COMPILER}
  DOWNLOAD_COMMAND rm -f SuiteSparse-${
     VERSION}.tar.gz && wget -O SuiteSparse-${
     VERSION}.tar.gz "https://github.com/jluttine/suitesparse/archive/v${VERSION}.tar.gz"
  #DOWNLOAD_COMMAND wget "https://www.baidu.com"
  PATCH_COMMAND tar -xzf ../SuiteSparse-${
     VERSION}.tar.gz && mv suitesparse-${
     VERSION} ./SuiteSparse && rm -rf ../suitesparse_src-build/SuiteSparse && sed -i.bu "s/\\/usr\\/local\\/lib/..\\/lib/g" SuiteSparse/SuiteSparse_config/SuiteSparse_config.mk && sed -i.bu "s/\\/usr\\/local\\/include/..\\/include/g" SuiteSparse/SuiteSparse_config/SuiteSparse_config.mk && mv SuiteSparse ../suitesparse_src-build/
  CONFIGURE_COMMAND ""
  BUILD_COMMAND cd SuiteSparse && make library -j8 -l8
  INSTALL_COMMAND cd SuiteSparse && mkdir -p lib && mkdir -p include && make install && cd lib && cp libamd.2.3.1.a libcamd.2.3.1.a libcholmod.2.1.2.a libcxsparse.3.1.2.a libldl.2.1.0.a libspqr.1.3.1.a libumfpack.5.6.2.a libamd.a	libcamd.a libcholmod.a	libcxsparse.a libldl.a libspqr.a libumfpack.a libbtf.1.2.0.a	libccolamd.2.8.0.a libcolamd.2.8.0.a libklu.1.2.1.a librbio.2.1.1.a libsuitesparseconfig.4.2.1.a libbtf.a	libccolamd.a libcolamd.a		libklu.a librbio.a libsuitesparseconfig.a  ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_LIB_DESTINATION}/ && cd .. && mkdir -p ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_INCLUDE_DESTINATION}/suitesparse && cd include && cp amd.h cholmod_matrixops.h SuiteSparseQR_definitions.h umfpack_load_symbolic.h umfpack_save_symbolic.h btf.h cholmod_modify.h SuiteSparseQR.hpp umfpack_numeric.h umfpack_scale.h camd.h cholmod_partition.h umfpack_col_to_triplet.h umfpack_qsymbolic.h umfpack_solve.h ccolamd.h cholmod_supernodal.h umfpack_defaults.h umfpack_report_control.h umfpack_symbolic.h cholmod_blas.h cholmod_template.h umfpack_free_numeric.h umfpack_report_info.h umfpack_tictoc.h cholmod_camd.h colamd.h umfpack_free_symbolic.h umfpack_report_matrix.h umfpack_timer.h cholmod_check.h cs.h umfpack_get_determinant.h umfpack_report_numeric.h umfpack_transpose.h cholmod_cholesky.h klu.h umfpack_get_lunz.h umfpack_report_perm.h umfpack_triplet_to_col.h cholmod_complexity.h ldl.h umfpack_get_numeric.h umfpack_report_status.h umfpack_wsolve.h cholmod_config.h RBio.h umfpack_get_symbolic.h umfpack_report_symbolic.h cholmod_core.h spqr.hpp umfpack_global.h umfpack_report_triplet.h cholmod.h SuiteSparse_config.h umfpack.h umfpack_report_vector.h cholmod_io64.h SuiteSparseQR_C.h umfpack_load_numeric.h umfpack_save_numeric.h ${
     CATKIN_DEVEL_PREFIX}/${
     CATKIN_GLOBAL_INCLUDE_DESTINATION}/suitesparse 
)

2.2 imu标定

2.2.1 imu的launch文件设置

复制rs_camera.launch文件命名rs_imu_calibration.launch,修改内容
显示话题:打开imu相关话题
D435i相机标定(不同标定方法总结)_第2张图片其中影响IMU数据同步的为:unite_imu_method
若使用linear_interpolation选项,可以将加速计的数据以插值的方式对齐到陀螺仪数据时间轴上;

若使用copy选项,则是在每一个陀螺仪数据上,附加上时间最近邻的加速计数据。

默认选项为:None
在该文件中将unite_imu_method对应设置为“linear_interpolation”,两路数据即可以同步为同一个topic: /camera/imu
D435i相机标定(不同标定方法总结)_第3张图片使用命令行rostopic echo /camera/imu查看IMU数据,同一个数据中同时包含两个传感器数据
D435i相机标定(不同标定方法总结)_第4张图片

2.2.2 标定参数文件撰写

cd ~/catkin_biao/src/imu_utils/launch
touch d435i_imu_calibration.launch
gedit d435i_imu_calibration.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= "d435i_imu_calibration"/>
        <param name="data_save_path" type="string" value= "$(find imu_utils)/data/"/>
        <param name="max_time_min" type="int" value= "10"/>
        <param name="max_cluster" type="int" value= "100"/>
    </node>
</launch>

max_time_min代表的是标定时间,这里的单位是分钟

2.2.3 录制IMU数据包

保持相机静止

roslaunch roslaunch realsense2_camera rs_imu_calibration.launch
cd ~/相机标定结果存储
rosbag record -O imu_calibration /camera/imu 

2.2.4 标定

添加环境变量:

sudo  gedit ~/.bashrc
source ~/catkin_biao/devel/setup.bash
# 更新
source ~/.bashrc

标定:

roslaunch imu_utils d435i_imu_calibration.launch 
# 2
cd ~/相机标定结果存储
rosbag play -r 200 imu_calibration.bag

结束后标定结果保存在cd ~/catkin_biao/src/imu_utils/data文件夹下,文件名为d435i_imu_calibration_imu_param.yaml
结果如下:

%YAML:1.0
---
type: IMU
name: d435i_imu_calibration
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 2.9731456108076613e-03
      gyr_w: 4.6757866248202665e-05
   x-axis:
      gyr_n: 1.9146867645158580e-03
      gyr_w: 4.0793210309672591e-05
   y-axis:
      gyr_n: 4.3985139109595879e-03
      gyr_w: 7.0425101846912364e-05
   z-axis:
      gyr_n: 2.6062361569475388e-03
      gyr_w: 2.9055286588023026e-05
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 7.1287226520511573e-02
      acc_w: 1.2369641418984393e-03
   x-axis:
      acc_n: 6.5809731513744446e-02
      acc_w: 1.1504376872998382e-03
   y-axis:
      acc_n: 8.0287824597207832e-02
      acc_w: 1.4939345312911317e-03
   z-axis:
      acc_n: 6.7764123450582442e-02
      acc_w: 1.0665202071043480e-03

在与相机标定中用到参数:陀螺仪和加速度计的随机游走和 高斯白噪声的平均值

2.2.5 查看imu默认参数

rostopic echo /camera/gyro/imu_info
rostopic echo /camera/accel/imu_info
rostopic echo /camera/color/camera_info #相机参数

D435i相机标定(不同标定方法总结)_第5张图片

2.3 相机标定

2.3.1 ros 下 kalibr制作标定板

下载标定板:https://github.com/ethz-asl/kalibr/wiki/downloads
注:利用棋盘格标定:12X9格子
步骤1:撰写yaml配置文件:命名为checkerboard.yaml

target_type: 'checkerboard' #gridtype
targetCols: 11               #number of internal chessboard corners
targetRows: 8               #number of internal chessboard corners
rowSpacingMeters: 0.02      #size of one chessboard square [m]
colSpacingMeters: 0.02      #size of one chessboard square [m]

2.3.2 修改相机帧数

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

修改相机帧数到4hz(要求图像频率不可过高),这里采用了新的话题去发布:/color、 /infra_left 、/infra_right
所以下面录制要写/color、 /infra_left 、/infra_right话题

2.3.3 录制ROS数据包

rosbag record -O d435i /color /infra_left /infra_right

在相应文件夹下出现d435i.bag

2.3.4 利用kalibr进行标定

kalibr_calibrate_cameras --target /home/wyh/相机标定结 果存储/biaoding/checkerboard.yaml --bag /home/wyh/相机标定结果存储/biaoding/d435i.bag --models pinhole-radtan --topic /color /infra_left /infra_right

注:

kalibr_calibrate_cameras --target /位置/文件名.yaml --bag /位置/camd435i.bag --bag-from-to 26 100 --models pinhole-radtan --topics /color /infra_left /infra_right

26-100 指的是录制的第26秒到100秒这段时间
pinhole-radtan指的是针孔相机模型和畸变模型
标定后结果:cam-...colord435i.yamlresults-cam-...colord435i.txtreport-cam-...colord435i.pdf
yaml文件内容:只放color

cam0:
  cam_overlaps: []
  camera_model: pinhole
  distortion_coeffs: [0.03061169802734056, 0.28579101214348585, -0.00442664291101413,
    0.0017385060135640883]
  distortion_model: radtan
  intrinsics: [600.4493794180136, 600.5049023578657, 331.6952192994212, 238.70096282330277]
  resolution: [640, 480]
  rostopic: /color

下列为各误差:
D435i相机标定(不同标定方法总结)_第6张图片
D435i相机标定(不同标定方法总结)_第7张图片
D435i相机标定(不同标定方法总结)_第8张图片
D435i相机标定(不同标定方法总结)_第9张图片

2.4、camera_imu联合标定

2.4.1 调节帧率

官网提出参数:

rosrun topic_tools throttle messages /camera/color/image_raw 20.0 /color
rosrun topic_tools throttle messages /camera/imu 200.0 /imu

2.4.2 录制数据包

rosbag record -O cam_imu /color /imu

2.4.3 yaml标定文件修改

标定需要的3个文件:
1 相机的标定文件:cam-...colord435i.yaml 为上述标定结果
2 imu的标定文件:
格式如下:

#Accelerometers
accelerometer_noise_density: 1.86e-03   #Noise density (continuous-time)
accelerometer_random_walk:   4.33e-04   #Bias random walk

#Gyroscopes
gyroscope_noise_density:     1.87e-04   #Noise density (continuous-time)
gyroscope_random_walk:       2.66e-05   #Bias random walk

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

根据上述标定结果填写:

%YAML:1.0
---
type: IMU
name: d435i_imu_calibration
Gyr:
   unit: " rad/s"
   avg-axis:
      gyr_n: 2.9731456108076613e-03
      gyr_w: 4.6757866248202665e-05
Acc:
   unit: " m/s^2"
   avg-axis:
      acc_n: 7.1287226520511573e-02
      acc_w: 1.2369641418984393e-03

更改后imu.yaml文件如下

#Accelerometers
accelerometer_noise_density: 7.1287226520511573e-02   #Noise density (continuous-time)
accelerometer_random_walk:   1.2369641418984393e-03  #Bias random walk

#Gyroscopes
gyroscope_noise_density:     2.9731456108076613e-03   #Noise density (continuous-time)
gyroscope_random_walk:       .6757866248202665e-05   #Bias random walk

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

3 数据包为上述录制

2.4.4 标定

kalibr_calibrate_imu_camera --target 标定板位置/标定板名称.yaml --cam 相机标定位置/相机标定名称.yaml --imu imu.yaml --bag cam_imu.bag --show-extraction

生成的结果中camchain-imucam-cam_imu.yaml为所需文件,T_cam_imu为外参

三、autoware标定

3.1 软件安装

3.1.1 autoware安装

依赖环境:

sudo apt update
sudo apt install -y python-catkin-pkg python-rosdep ros-$ROS_DISTRO-catkin
sudo apt install -y python3-pip python3-colcon-common-extensions python3-setuptools python3-vcstool
pip3 install -U setuptools

autoware依赖2:

sudo apt-get install ros-melodic-grid-map-ros
sudo apt-get install ros-melodic-nmea-msgs
sudo apt-get install libglew-dev
sudo apt-get install ros-melodic-autoware-msgs
sudo apt-get install ros-melodic-automotive-platform-msgs
sudo apt-get install ros-melodic-automotive-navigation-msgs
sudo apt-get install ros-melodic-velodyne-pointcloud
sudo apt-get install ros-melodic-gps-common
sudo apt install libopenblas-dev liblapack-dev

安装:
a:创建工作区

mkdir -p autoware.ai/src
cd autoware.ai

b: 下载Autoware.AI的工作区配置
主版本:

wget -O autoware.ai.repos "https://raw.githubusercontent.com/Autoware-AI/autoware.ai/master/autoware.ai.repos"

以1.12.0为例

wget -O autoware.ai.repos "https://raw.githubusercontent.com/Autoware-AI/autoware.ai/1.12.0/autoware.ai.repos"

c 下载到工作区

vcs import src < autoware.ai.repos

d 使用安装依赖rosdep

rosdep update
rosdep install -y --from-paths src --ignore-src --rosdistro $ROS_DISTRO

e:编译工作区:

#有CUDA
AUTOWARE_COMPILE_WITH_CUDA=1 colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
#无CUDA
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release

f:编译后运行

cd autoware.ai
source install/setup.bash
roslaunch runtime_manager runtime_manager.launch

3.1.2 autoware1.12之上单独安装雷达相机标定工具

3.1.2.1 安装nlopt

链接:https://github.com/stevengj/nlopt

git clone git://github.com/stevengj/nlopt
cd nlopt
mkdir build
cd build
cmake ..
make
sudo make install

3.1.2.2 autoware标定工具箱

链接:https://github.com/XidianLemon/calibration_camera_lidar
安装编译:
在ROS工作空间下

cd ~/catkin_biao/src$ 
git clone https://github.com/XidianLemon/calibration_camera_lidar.git
cd ..
catkin_make
source devel/setup.bash

使用:

roscore
rosrun calibration_camera_lidar calibration_toolkit

运行出错:
D435i相机标定(不同标定方法总结)_第10张图片
解决: ubuntu18.04 将/home/wyh/catkin_biao/src/calibration_camera_lidar/ls_calibration/calibration_camera_lidar下的CMakeLists.txt中第72行、944、114行中分别增加三个melodic

#第72行、944、114行修改前
if ("${ROS_VERSION}" MATCHES "(indigo|jade|kinetic)")
#第72行、944、114行修改后
if ("${ROS_VERSION}" MATCHES "(indigo|jade|kinetic|melodic)")

重新编译出错:
在这里插入图片描述解决:刚才安装的libnlopt.so.0的位置不对,只需要在/etc/ld.so.conf.d目录下新建一个libnlopt.conf文件,在其中输入/usr/local/lib是其库文件安装到的位置

cd /etc/ld.so.conf.d/
sudo gedit libnlopt.conf #在其中输入/usr/local/lib,:wq保存退出
sudo ldconfig使配置生效

更改后重新编译运行。

3.2 相机内参标定

3.2.1 数据获取

实时数据

roslaunch realsense2_camera rs_rgbd.launch 
roslaunch 
# 或者
roslaunch realsense2_camera rs_camera.launch 
roslaunch 

数据包:

rosbag record -O d435i /color/image_raw 

3.2.2启动autoware的相机标定节点

cd autoware.ai
source install/setup.bash

单目:

rosrun autoware_camera_lidar_calibrator cameracalibrator.py --size 11x8 --square 0.02 image:=/color/image_raw camera:=/camera --no-service-check

双目

rosrun autoware_camera_lidar_calibrator cameracalibrator.py --size 11x8 --square 0.02 image:=/camera/infra1/image_rect_raw /camera/infra2/image_rect_raw  --no-service-check

标定完成后,点击SAVE,标定结果保存在home文件夹下20210923_0932_autoware_camera_calibration.yaml:

%YAML:1.0
---
CameraExtrinsicMat: !!opencv-matrix
   rows: 4
   cols: 4
   dt: d
   data: [ 1., 0., 0., 0., 0., 1., 0., 0., 0., 0., 1., 0., 0., 0., 0.,
       1. ]
CameraMat: !!opencv-matrix
   rows: 3
   cols: 3
   dt: d
   data: [ 6.5055720688885719e+02, 0., 3.3276918188990044e+02, 0.,
       6.4990868815582769e+02, 2.4630999814936723e+02, 0., 0., 1. ]
DistCoeff: !!opencv-matrix
   rows: 5
   cols: 1
   dt: d
   data: [ 6.8641294614044765e-02, 3.2902097109600531e-01,
       1.8755845953358030e-03, 2.2316380587360627e-03,
       -1.7254670555737144e+00 ]
ImageSize: [640, 480]
Reprojection Error: 0.0
DistModel: plumb_bob

3.3 联合标定

3.3.1 数据包录制

运行相机雷达文件:雷达话题:/rslidar_points
相机:/camera/color/image_raw

 rosbag record -o /rslidar_points /camera/color/image_raw

3.3.2 联合标定

3.3.2.1 数据包播放

rosbag play 2021-09-22-07-28-38.bag /rslidar_points:=/points_raw /camera/color/image_raw --loop

将激光雷达的原始节点名称改为/points_raw,因为在标定功能包的mainwindow函数中,订阅的是/points_raw这个话题,所以需要修改名字,或者修改源码重新再编译一次;--loop循环播放
rostopic list查看话题

3.3.2.2 标定

rosrun calibration_camera_lidar calibration_toolkit

在下拉框中选择相机话题/camera/color/image_raw
D435i相机标定(不同标定方法总结)_第11张图片

  • 在下一个框中选择Camera->velodyne
  • D435i相机标定(不同标定方法总结)_第12张图片
  • 打开标定窗口,在最上方Patter Size填入0.02x0.02(单位m);Pattern Number为11 x 8(棋盘格数目为12 x 9,去掉最外面的一圈,实际内部角点数为11 x 8)
  • D435i相机标定(不同标定方法总结)_第13张图片
  • load处加载上述相机内参文件,需要将yaml文件命名为.yml
    -D435i相机标定(不同标定方法总结)_第14张图片D435i相机标定(不同标定方法总结)_第15张图片
    D435i相机标定(不同标定方法总结)_第16张图片
  • 加载完毕后会看到相机内参信息

D435i相机标定(不同标定方法总结)_第17张图片
D435i相机标定(不同标定方法总结)_第18张图片

  • 右侧会出现数据包中摄像机与激光雷达的同步数据内容,在数据包运行终端按空格健暂停。
  • 注:右侧的激光雷达区域在开始时看不到,按数字2进行数据显示。
    D435i相机标定(不同标定方法总结)_第19张图片
  • 基本操作如下:
  • 1右侧数字小键盘中“上”,“下”,“左”,“右”,“PgUp”以及“PgDn”这六个按键用于平移激光点云。
  • 2 a、d、w、s、q、e用来旋转激光点云。
  • 3 数字“1”,“2”用来设置是perspective projection透视投影还是orthogonal projection正交投影。
  • 4 用“o”,“p”控制点云的大小,o变小,p变粗。
  • 5 用+、-控制放大、缩小。
  • 6 用“b"来改变激光点云区域的背景颜色

D435i相机标定(不同标定方法总结)_第20张图片

  • 最后通过上述键盘按键的调整,将左侧摄像头与右侧激光点云画面同步,方便左右选择对应的标定板特征点,并且标定板的点云也很好区分,处于视角正中心。
  • 点击右上角的“Grab”按钮,用来捕获当前时刻的图像与点云,
  • 当grab到差不多15组点云与图像对后,点击窗口右上角的"Calibrate"按钮进行标定D435i相机标定(不同标定方法总结)_第21张图片
  • 标定结后,会在左侧的"CameraExtrinsicMat"窗口显示出外参矩阵
  • D435i相机标定(不同标定方法总结)_第22张图片D435i相机标定(不同标定方法总结)_第23张图片D435i相机标定(不同标定方法总结)_第24张图片
    D435i相机标定(不同标定方法总结)_第25张图片
  • 点击save进行保存,其中在出现的界面中选择NO,选是的话,会将所有的标定信息都存入yaml文件中

3.3.3 标定结果测试

  • 运行打开autoware
cd autoware.ai
source install/setup.bash
roslaunch runtime_manager runtime_manager.launch
  • 切换到Sensing感知模块,点击右下区域的Calibration Publisher
    D435i相机标定(不同标定方法总结)_第26张图片
  • 选择参数文件
    D435i相机标定(不同标定方法总结)_第27张图片
  • 打开右下角的Point image节点,在camera ID输入相机节点
  • 点击Rviz,进行显示Panels/Add New Panel内添加ImageViewerPlugin,填写Image Topic,本例为/camrea/color/image_raw,Point Topic,本例为/points_image
    D435i相机标定(不同标定方法总结)_第28张图片D435i相机标定(不同标定方法总结)_第29张图片在图像中显示

你可能感兴趣的:(ROS,深度相机D435i,自动驾驶,人工智能)