Livox Lidar+海康Camera实时生成彩色点云
Livox Lidar? + HIKROBOT Camera系列
最近在開發(fā)相機(jī)和激光雷達(dá)融合的slam算法,主要用于三維重建,想實(shí)時的得到彩色點(diǎn)云地圖,傳感器選擇了海康威視的工業(yè)相機(jī)和大疆的固態(tài)激光雷達(dá)。
海康Camera MVS Linux SDK二次開發(fā)封裝ROS packge過程記錄(c++)
Livox Lidar+海康Camera實(shí)時生成彩色點(diǎn)云
Livox Lidar+海康Camera實(shí)時三維重建生成RGB彩色點(diǎn)云地圖
前言
大部分基于點(diǎn)云的三維重建算法,輸出的mesh或點(diǎn)云都是不帶rgb信息,我希望重建后的地圖是帶rgb信息的,因?yàn)椴徽撌菫榱嗽谥亟ǖ牡貓D上做分割(引入紋理信息)還是人的直接觀測(直觀比對),rgb信息都很重要。
已封裝為Ros package,地址:https://github.com/luckyluckydadada/LIVOX_COLOR
硬件環(huán)境
- 一個livox的激光雷達(dá)
- 一個hikrobot的工業(yè)相機(jī)
- 一臺linux系統(tǒng)的電腦
軟件環(huán)境
我的測試環(huán)境是:
- Ubuntu18.04
- ros(melodic)
- livox sdk(https://github.com/Livox-SDK/Livox-SDK)
- livox ros driver(https://github.com/Livox-SDK/livox_ros_driver)
- hikrobot camera sdk (mvs sdk 安裝參考海康Camera MVS Linux SDK二次開發(fā)ROS packge過程記錄(c++))??
- hikrobot camera ros driver?(camera ros driver是我自己開發(fā)的,安裝參考海康Camera MVS Linux SDK二次開發(fā)ROS packge過程記錄(c++))??
聯(lián)合標(biāo)定
我們要得到兩個傳感器的坐標(biāo)系的變換關(guān)系,以及相機(jī)的內(nèi)參,才可以將相機(jī)的彩色信息賦值給點(diǎn)云。
標(biāo)定過程參考livox的官方文檔:https://github.com/Livox-SDK/livox_camera_lidar_calibration,文檔對標(biāo)定過程描述比較清晰,下面是對文檔中沒說明的做一些補(bǔ)充。
在獲得標(biāo)定板(泡棉板)的四個角點(diǎn)時,跳出的窗口并沒有顯示像素值,我將每副去畸變的照片都save下來,用windows的畫圖軟件找的角點(diǎn)的像素值。
只需在corner_photo.cpp:101行增加 cv::imwrite(photo_path+".bak.bmp",src_img); 即可。
注意不要在原照片上直接采集角點(diǎn),一定要先運(yùn)行這個cpp對應(yīng)的launch,得到去畸變后的照片,再在新的照片上獲得像素值,再次運(yùn)行這個launch執(zhí)行后續(xù)操作。
修改cornerPhoto.launch文件(可選操作):
<?xml version="1.0" encoding="UTF-8"?> <launch><arg name="arg1" default="$(find camera_lidar_calibration)/../../data/photo/0.bmp"/><param name="intrinsic_path" value="$(find camera_lidar_calibration)/../../data/parameters/intrinsic.txt" /> <!-- intrinsic file --><param name="input_photo_path" value="$(arg arg1)" /> <!-- photo to find the corner --><param name="ouput_path" value="$(find camera_lidar_calibration)/../../data/corner_photo.txt" /> <!-- file to save the photo corner --><node pkg="camera_lidar_calibration" name="cornerPhoto" type="cornerPhoto" output="screen"></node></launch>修改后可以直接在命令行指定文件:roslaunch camera_lidar_calibration cornerPhoto.launch arg1:=/home/yijiankeji/data/photo/0.bmp?
pcdTransfer.launch中只有一個參數(shù)要修改:data_num,修改為你錄制的bag包的數(shù)量。
生成彩色點(diǎn)云
進(jìn)過標(biāo)定得到intrinsic.txt和extrinsic.txt文件后就可以使用我的ros包進(jìn)行彩色點(diǎn)云的生成了。
安裝過程參看:https://github.com/luckyluckydadada/LIVOX_COLOR
需要注意的是catkin_make 執(zhí)行前需要修改main.cpp中的void CalibrationData(void)函數(shù),將你的標(biāo)定結(jié)果寫入對應(yīng)的位置。
例如:
// extrinsic// 0.0451423 -0.998715 0.0230348 0.00925535// 0.0558064 -0.0205011 -0.998231 0.0499455// 0.997421 0.046348 0.0548092 0.42788// 0 0 0 1extrinsicMat_RT.at<double>(0, 0) = 0.0451423;extrinsicMat_RT.at<double>(0, 1) = -0.998715;extrinsicMat_RT.at<double>(0, 2) = 0.0230348;extrinsicMat_RT.at<double>(0, 3) = 0.00925535;extrinsicMat_RT.at<double>(1, 0) = 0.0558064;extrinsicMat_RT.at<double>(1, 1) = -0.0205011;extrinsicMat_RT.at<double>(1, 2) = -0.998231;extrinsicMat_RT.at<double>(1, 3) = 0.0499455;extrinsicMat_RT.at<double>(2, 0) = 0.997421;extrinsicMat_RT.at<double>(2, 1) = 0.046348;extrinsicMat_RT.at<double>(2, 2) = 0.0548092;extrinsicMat_RT.at<double>(2, 3) = 0.42788;extrinsicMat_RT.at<double>(3, 0) = 0.0;extrinsicMat_RT.at<double>(3, 1) = 0.0;extrinsicMat_RT.at<double>(3, 2) = 0.0;extrinsicMat_RT.at<double>(3, 3) = 1.0;// intrinsic// 2875.097131590431 0 1369.668059923329;// 0 2896.420251825658 1114.244269170673;// 0 0 1// ditortion// -0.008326874784366894 -0.06967846599874981 0.006185220615585947 -0.01133018681519818 0.5462976722456516intrisicMat.at<double>(0, 0) = intrisic.at<double>(0, 0) = 2875.097131590431;intrisicMat.at<double>(0, 1) = 0.000000e+00;intrisicMat.at<double>(0, 2) = intrisic.at<double>(0, 2) = 1369.668059923329;intrisicMat.at<double>(0, 3) = 0.000000e+00;intrisicMat.at<double>(1, 0) = 0.000000e+00;intrisicMat.at<double>(1, 1) = intrisic.at<double>(1, 1) = 2896.420251825658;intrisicMat.at<double>(1, 2) = intrisic.at<double>(1, 2) = 1114.244269170673;intrisicMat.at<double>(1, 3) = 0.000000e+00;intrisicMat.at<double>(2, 0) = 0.000000e+00;intrisicMat.at<double>(2, 1) = 0.000000e+00;intrisicMat.at<double>(2, 2) = 1.000000e+00;intrisicMat.at<double>(2, 3) = 0.000000e+00;distCoeffs.at<double>(0) = -0.008326874784366894;distCoeffs.at<double>(1) = -0.06967846599874981;distCoeffs.at<double>(2) = 0.006185220615585947;distCoeffs.at<double>(3) = -0.01133018681519818;distCoeffs.at<double>(4) = 0.5462976722456516;彩色點(diǎn)云對比原始livox點(diǎn)云
原始livox:
color livox:
總結(jié)
以上是生活随笔為你收集整理的Livox Lidar+海康Camera实时生成彩色点云的全部內(nèi)容,希望文章能夠幫你解決所遇到的問題。
- 上一篇: 开始研究反垃圾评论
- 下一篇: 产品经理(12)#竞品调研