Livox Lidar + HIKROBOT Camera系列
最近在开发相机和激光雷达融合的slam算法,主要用于三维重建,想实时的得到彩色点云地图,传感器选择了海康威视的工业相机和大疆的固态激光雷达。
海康Camera MVS Linux SDK二次开发封装ROS packge过程记录(c++)
Livox Lidar+海康Camera实时三维重建生成RGB彩色点云地图
前言
目标是利用Livox Lidar+海康Camera实时三维重建生成RGB彩色点云,算法基于 loam 及其各种变种的优化改进,已开源https://github.com/luckyluckydadada/livox_color_mapping。
有关loam及其各种变种的原理网上解析很多,这里不做解释,各种loam原理的文章整理参见:各种版本loam整理
livox_color_mapping我的这个loam版本代码支持生成带有RGB信息的彩色地图,并对代码进行了详细的中文注释,欢迎star
pipline
- 利用livox ros包中的节点调用激光雷达生成/livox/lidar(Topic) ;
- 利用hikrobot ros包中的节点调用相机生成/hikrobot_camera/rgb(Topic);
- 通过livox_color ros包【参看 Livox Lidar+海康Camera实时生成彩色点云】中的节点订阅/hikrobot_camera/rgb(Topic)和/livox/lidar(Topic)实时处理,并生成彩色点云/livox/color_lidar(Topic);
- 通过livox_color_mapping ros包中的节点订阅/livox/color_lidar(Topic),生成彩色点云地图,请在livox_color_mapping/launch/mapping_mid_color.launch文件中指定地图保存路径/home/xxx,保存的格式为bin形式的pcd文件,可直接用pcl_viewer all_points.pcd打开查看。也可转为ply格式:pcl_pcd2ply demo.pcd demo.ply
安装
请先行完成依赖安装:
海康Camera MVS Linux SDK二次开发封装ROS packge过程记录(c++)
livox_color_mapping安装:
cd ws_livox/src # 前面 livox ros driver的安装目录(https://github.com/Livox-SDK/livox_ros_driver)
git clone https://github.com/luckyluckydadada/livox_color_mapping.git
cd ..
catkin_make
运行
请结合前面的《pipeline》对照执行,一个终端的执行对应一条原理。
终端1:
cd ~/ws_livox
source devel/setup.bash
roslaunch livox_ros_driver livox_lidar.launch
终端2:
cd ~/ws_hikrobot_camera
source devel/setup.bash
roslaunch hikrobot_camera hikrobot_camera.launch
终端3:
cd ~/ws_livox_color
source devel/setup.bash
roslaunch livox_color color_livox-for-color-mapping.launch
终端4:
cd ~/ws_livox
source devel/setup.bash
# 注意要修改 mapping_mid_color.launch中的map存储路径,不然会覆盖上次的map结果
roslaunch livox_color_mapping mapping_mid_color.launch
实时建图效果
室外室内