LiDAR-based real-time 3D localization and mapping
github:https://github.com/erik-nelson/blam.git
官方视频:https://youtu.be/08GTGfNneCI
sudo apt-get install libboost-all-dev
sudo apt-get install cmake
git clone https://bitbucket.org/gtborg/gtsam.git
cd gtsam
mkdir build
cd build
cmake ..
sudo make install
git clone https://github.com/erik-nelson/blam.git
cd blam
./update
常见问题
1、fatal error: ros/ros.h: No such file or directory
cd blam/internal/src/geometry_utils
vim package.xml
#添加一下内容
<build_depend>roscpp</build_depend>
<run_depend>roscpp</run_depend>
vim CMakeList.txt
#修改find_package(catkin REQUIRED)为
find_package(catkin REQUIRED COMPONENTS roscpp)
#添加
include_directories(include ${catkin_INCLUDE_DIRS})
2、Invalid (NaN, Inf) point coordinates given to nearestKSearch!
pcl中NaN数据处理
在blam/src/point_cloud_filter/src/PointCloudFilter.cc的filter函数最后面添加如下内容
if (!points->is_dense)
{
points_filtered->is_dense = false;
std::vector<int> indices;
pcl::removeNaNFromPointCloud(*points_filtered,*points_filtered, indices);
}
以上nan问题主要是因为所使用的点云数据is_desne:false也就是说,点云里面可能含有nan所以在filter里面
统一做了去除无效值
3、按照以上方法修改后,在回环后还是出现Invalid (NaN, Inf) point coordinates given to nearestKSearch
修改”BlamSlam.cc”,修改以下几行(这几行不是连在一起的),即把使用原始msg的地方替换为msg_filtered
//1、change loop_closure_.AddKeyScanPair(0, msg); to
loop_closure_.AddKeyScanPair(0, msg_filtered);
//2、change if (HandleLoopClosures(msg, &new_keyframe)) to
if (HandleLoopClosures(msg_filtered, &new_keyframe))
//3、localization_.TransformPointsToFixedFrame(*msg, msg_fixed.get());
localization_.TransformPointsToFixedFrame(*msg_filtered, msg_fixed.get());
使用自己的数据集,修改test_online.launch文件
<remap from="~pcld" to="/rslidar_points"/> <!--/rslidar_points替换成自己的话题名-->
roslaunch rslidar rslidar_16.launch //运行激光雷达
source your_path/blam-master/internal/devel/setup.zsh//或./workon
roslaunch blam_example test_online.launch
1、效果不好
点云数量少就修改point_cloud_filter/config/parameters.yaml
#关闭voxel grid filter
grid_filter: false
2、按照1修改了,效果还不好,旋转特别大
修改point_cloud_localization/config/parameters.yaml
# Maximum acceptable incremental rotation and translation.
transform_thresholding: true #false
max_translation: 0.5 #0.05
max_rotation: 0.3 #0.1
3、不回环
观察你的pose相差多远,修改laser_loop_closure/config/parameters.yaml
#默认0.5米检测一次回环或记录关键帧,值越大效率越高,发现构图缓慢的时候可以放大这个值
translation_threshold: 1.0 #0.5
#默认是在1.5米范围内匹配,根据你自己的回环误差放大这个值
proximity_threshold: 10 #1.5
#ICP "fitness score" must be less than this number,就是越小越难回环
max_tolerable_fitness: 5 #0.15
#根据你自己的地图大小适当放宽跳过回环的点数,一般地图越大值越大
skip_recent_poses: 100 #40
poses_before_reclosing: 100 #40
4. rviz查看
rosrun rviz rviz -d blam_example/rviz/lidar_slam.rviz
参考博客