link
一、运行环境
环境:ubutu18.04+ros:melodic+pcl:1.8+gtsam+metis
环境配置:
- Eigen 3.3.4
- PCL 1.8.1 (1.11不能用)
- ceres 2.0.0
- gtsam 4.0.0
雷达参数:
二、下载编译运行
已修改配置的源码文件,下载catkin_make即可跑通。
https://gitee.com/zhankun3280/lslidar_c16_lego_loam
首先,要注意的是SC-LeGo-LOAM和16线雷神激光雷达源码的版本不一样,源码也可能稍有区别。这里找的是修改之后能跑得通的两个版本。
还要注意雷达的IP,我配置的是192.168.0.200
git clone https://gitee.com/zhankun3280/lslidar_c16_lego_loam
catkin_make
roslaunch lslidar_c16_decoder lslidar_c16.launch --screen
roslaunch lego_loam run.launch
- 1
- 2
- 3
- 4
- 5
- 6
三、lslidar的相关修改
- 首先LeGO-LOAM默认的接受的topic name是velodyne_points,点云的frame_id是velodyne。
- 镭神驱动发布的topic name为lslidar_point_cloud,frame_id为laser_link。
- 这里需要修改一下lslidar_c16.launch文件,remap一下topic name,再修改frame_id为velodyne。
<launch>
<arg name="device_ip" default="192.168.0.200" />
<arg name="msop_port" default="2368" />
<arg name="difop_port" default="2369" />
<arg name="return_mode" default="1" />
<arg name="time_synchronization" default="false" />
<node pkg=“lslidar_c16_driver” type=“lslidar_c16_driver_node” name=“lslidar_c16_driver_node” output=“screen”>
<param name=“device_ip” value=“KaTeX parse error: Expected 'EOF', got '&' at position 19: …g device_ip)" /&̲gt; <par…(arg msop_port)” />
<param name=“difop_port” value=“KaTeX parse error: Expected 'EOF', got '&' at position 19: …g difop_port)"/&̲gt; <par…(arg return_mode)”/>
<param name=“time_synchronization” value=“$(arg time_synchronization)”/>
</node>
<node pkg=“lslidar_c16_decoder” type=“lslidar_c16_decoder_node” name=“lslidar_c16_decoder_node” output=“screen”>
<param name=“calibration_file” value=“KaTeX parse error: Expected 'EOF', got '&' at position 57: …_c16_db.yaml" /&̲gt; <par…(arg return_mode)”/>
<param name=“degree_mode” value=“2”/>
<param name=“config_vert_file” value=“false”/>
<param name=“distance_unit” value=“0.25”/>
<param name=“time_synchronization” value=“$(arg time_synchronization)”/>
<param name=“scan_start_angle” value=“0.0”/>
<param name=“scan_end_angle” value=“36000.0”/>
<param name=“scan_num” value=“8”/>
<param name=“publish_scan” value=“false”/>
<remap from=“lslidar_point_cloud” to=“/velodyne_points” /> <!–add–>
</node>
</launch>
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
- 18
- 19
- 20
- 21
- 22
- 23
- 24
- 25
- 26
- 27
- 28
- 29
- 30
- 31
- 32
- 33
- 34
- 35
- 36
- 37
- 38
- 39
- 40
- 41
由于镭神C16的驱动中对点云强度的定义是uint8_t类型,LOAM能接收的是float32类型,并且LOAM在运行时是根据采集的点云不停的计算来估计自身位置的,所以如果点云强度不匹配,会出现坐标轴baselink漂移的现象。(注意:由于没有惯导,在LOAM运行时,如果雷达前方出现不规则快速运动的物体,比如拿书快速扫,雷达坐标系都会出现漂移现象,所以建议利用传感器来获取位置信息,这是最稳妥的方法)。
将lslidar_c16/lslidar_c16_decoder/src/rawdata.cc 中的 数据类型修改为 PCL常用的点云处理数据类型 pcl::PointXYZI point 即可 ,修改后注释雷达输出的 ring 和 timestamp的两个话题.
pcl::PointXYZI point; //VPoint point;
<span class="token keyword">if</span> <span class="token punctuation">(</span><span class="token punctuation">(</span>azimuth_corrected_f <span class="token operator"><</span> scan_start_angle_<span class="token punctuation">)</span> <span class="token operator">||</span> <span class="token punctuation">(</span>azimuth_corrected_f <span class="token operator">></span> scan_end_angle_<span class="token punctuation">)</span><span class="token punctuation">)</span> <span class="token keyword">continue</span><span class="token punctuation">;</span> <span class="token keyword">if</span> <span class="token punctuation">(</span>distance2 <span class="token operator">></span> max_distance_ <span class="token operator">||</span> distance2 <span class="token operator"><</span> min_distance_<span class="token punctuation">)</span> <span class="token punctuation">{<!-- --></span> point<span class="token punctuation">.</span>x <span class="token operator">=</span> NAN<span class="token punctuation">;</span> point<span class="token punctuation">.</span>y <span class="token operator">=</span> NAN<span class="token punctuation">;</span> point<span class="token punctuation">.</span>z <span class="token operator">=</span> NAN<span class="token punctuation">;</span> point<span class="token punctuation">.</span>intensity <span class="token operator">=</span> <span class="token number">0</span><span class="token punctuation">;</span> <span class="token comment">//point.lines = dsr;</span> pointcloud<span class="token operator">-></span><span class="token function">at</span><span class="token punctuation">(</span><span class="token number">2</span> <span class="token operator">*</span> <span class="token keyword">this</span><span class="token operator">-></span>block_num <span class="token operator">+</span> firing<span class="token punctuation">,</span> dsr<span class="token punctuation">)</span> <span class="token operator">=</span> point<span class="token punctuation">;</span> <span class="token punctuation">}</span> <span class="token keyword">else</span> <span class="token punctuation">{<!-- --></span> <span class="token keyword">if</span> <span class="token punctuation">(</span>cbMethod_<span class="token punctuation">)</span> <span class="token punctuation">{<!-- --></span> point<span class="token punctuation">.</span>x <span class="token operator">=</span> distance2 <span class="token operator">*</span> cos_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span> <span class="token operator">*</span> cos_azimuth <span class="token operator">+</span> R1_ <span class="token operator">*</span> <span class="token function">cos</span><span class="token punctuation">(</span>arg_horiz_orginal<span class="token punctuation">)</span><span class="token punctuation">;</span> point<span class="token punctuation">.</span>y <span class="token operator">=</span> <span class="token operator">-</span>distance2 <span class="token operator">*</span> cos_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span> <span class="token operator">*</span> sin_azimuth <span class="token operator">+</span> R1_ <span class="token operator">*</span> <span class="token function">sin</span><span class="token punctuation">(</span>arg_horiz_orginal<span class="token punctuation">)</span><span class="token punctuation">;</span> point<span class="token punctuation">.</span>z <span class="token operator">=</span> distance2 <span class="token operator">*</span> sin_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span> <span class="token operator">+</span> <span class="token number">0.426</span> <span class="token operator">/</span> <span class="token number">100.f</span><span class="token punctuation">;</span> <span class="token punctuation">}</span> <span class="token keyword">else</span> <span class="token punctuation">{<!-- --></span> point<span class="token punctuation">.</span>x <span class="token operator">=</span> distance2 <span class="token operator">*</span> cos_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span> <span class="token operator">*</span> cos_azimuth<span class="token punctuation">;</span> point<span class="token punctuation">.</span>y <span class="token operator">=</span> <span class="token operator">-</span>distance2 <span class="token operator">*</span> cos_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span> <span class="token operator">*</span> sin_azimuth<span class="token punctuation">;</span> point<span class="token punctuation">.</span>z <span class="token operator">=</span> distance2 <span class="token operator">*</span> sin_scan_altitude_caliration<span class="token punctuation">[</span>dsr<span class="token punctuation">]</span><span class="token punctuation">;</span> <span class="token punctuation">}</span> point<span class="token punctuation">.</span>intensity <span class="token operator">=</span> intensity<span class="token punctuation">;</span> <span class="token comment">//point.lines = dsr;</span> pointcloud<span class="token operator">-></span><span class="token function">at</span><span class="token punctuation">(</span><span class="token number">2</span> <span class="token operator">*</span> <span class="token keyword">this</span><span class="token operator">-></span>block_num <span class="token operator">+</span> firing<span class="token punctuation">,</span> dsr<span class="token punctuation">)</span> <span class="token operator">=</span> point<span class="token punctuation">;</span>
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
- 18
- 19
- 20
- 21
- 22
- 23
- 24
- 25
- 26
- 27
- 28
四、SC-LeGO-LOAM的相关修改
(1)修改utility.h
extern const bool useCloudRing = false; // if true, ang_res_y and ang_bottom are not used
...
// leishen16
// lslidar_c16
extern const int N_SCAN = 16;
extern const int Horizon_SCAN = 2000;
extern const float ang_res_x = 0.18;
extern const float ang_res_y = 2.0;
extern const float ang_bottom = 15.0;
extern const int groundScanInd = 10;
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
(2)修改imageproject.cpp
void copyPointCloud(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){
cloudHeader <span class="token operator">=</span> laserCloudMsg<span class="token operator">-></span>header<span class="token punctuation">;</span> <span class="token comment">// cloudHeader.stamp = ros::Time::now(); // Ouster lidar users may need to uncomment this line</span> pcl<span class="token operator">::</span><span class="token function">fromROSMsg</span><span class="token punctuation">(</span><span class="token operator">*</span>laserCloudMsg<span class="token punctuation">,</span> <span class="token operator">*</span>laserCloudIn<span class="token punctuation">)</span><span class="token punctuation">;</span> <span class="token comment">// Remove Nan points</span> std<span class="token operator">::</span>vector<span class="token operator"><</span><span class="token keyword">int</span><span class="token operator">></span> indices<span class="token punctuation">;</span> pcl<span class="token operator">::</span><span class="token function">removeNaNFromPointCloud</span><span class="token punctuation">(</span><span class="token operator">*</span>laserCloudIn<span class="token punctuation">,</span> <span class="token operator">*</span>laserCloudIn<span class="token punctuation">,</span> indices<span class="token punctuation">)</span><span class="token punctuation">;</span> <span class="token comment">// have "ring" channel in the cloud</span> <span class="token keyword">if</span> <span class="token punctuation">(</span>useCloudRing <span class="token operator">==</span> <span class="token boolean">true</span><span class="token punctuation">)</span><span class="token punctuation">{<!-- --></span> pcl<span class="token operator">::</span><span class="token function">fromROSMsg</span><span class="token punctuation">(</span><span class="token operator">*</span>laserCloudMsg<span class="token punctuation">,</span> <span class="token operator">*</span>laserCloudInRing<span class="token punctuation">)</span><span class="token punctuation">;</span> <span class="token keyword">if</span> <span class="token punctuation">(</span>laserCloudInRing<span class="token operator">-></span>is_dense <span class="token operator">==</span> <span class="token boolean">false</span><span class="token punctuation">)</span> <span class="token punctuation">{<!-- --></span> <span class="token function">ROS_ERROR</span><span class="token punctuation">(</span><span class="token string">"Point cloud is not in dense format, please remove NaN points first!"</span><span class="token punctuation">)</span><span class="token punctuation">;</span> ros<span class="token operator">::</span><span class="token function">shutdown</span><span class="token punctuation">(</span><span class="token punctuation">)</span><span class="token punctuation">;</span> <span class="token punctuation">}</span> <span class="token punctuation">}</span>
}
- 1
- 2
- 3
- 4
- 5
- 6
- 7
- 8
- 9
- 10
- 11
- 12
- 13
- 14
- 15
- 16
- 17
注释掉cloudHeader.stamp = ros::Time::now()
五、离线建图
# 运行 lego-loam
roslaunch lego_loam run.launch
# 播放 指定的rosbag
rosbag play *.bag --clock --topic /velodyne_points /imu/data
rosbag play *.bag --clock /lslidar_point_cloud:=/velodyne_points
- 1
- 2
- 3
- 4
- 5
- 6
如果没有用到imu,就只订阅雷达话题。虽然 /imu/data 是可选的,但如果提供的话,它可以大大提高估计的准确性。
六、实时在线建图
<param name="/use_sim_time" value="false" />
- 1
参考链接:
[1] 镭神16线雷达适配Lego-Loam开源框架
[2] 32线镭神雷达跑LeGO-LOAM:3D 激光SLAM
[3] LeGO-LOAM初探:原理,安装和测试
[4] 搭建实验室3d slam 移动小车 4.1jackal小车+镭神32线激光雷达lego-loam建图