diff --git a/docs/source/index.rst b/docs/source/index.rst index d49d415952255f700647d66e5565c7b50a11de39..0ef490503edfe9e0a62d2550f1ff2bc0bf37f0bd 100644 --- a/docs/source/index.rst +++ b/docs/source/index.rst @@ -54,6 +54,7 @@ openEuler ROS sig成立于2020年6月,主要目标是将ROS1/ROS2移植到open slam-nav/slam_gmapping.md slam-nav/slam_gmapping_test_report.md slam-nav/slam_hector_test_report.md + slam-nav/lidarslam_slam_installation.md slam-nav/stage_ros.md slam-nav/cartographer.md slam-nav/orb_slam3_porting.md diff --git a/docs/source/slam-nav/image/lidarslam_1.png b/docs/source/slam-nav/image/lidarslam_1.png new file mode 100644 index 0000000000000000000000000000000000000000..591d285078d6ba2bbabc3210092b11dcdfef4d77 Binary files /dev/null and b/docs/source/slam-nav/image/lidarslam_1.png differ diff --git a/docs/source/slam-nav/image/lidarslam_2.png b/docs/source/slam-nav/image/lidarslam_2.png new file mode 100644 index 0000000000000000000000000000000000000000..c49c115d5dc215aa48ea4e95a95a3f6c01daec6e Binary files /dev/null and b/docs/source/slam-nav/image/lidarslam_2.png differ diff --git a/docs/source/slam-nav/lidarslam_slam_installation.md b/docs/source/slam-nav/lidarslam_slam_installation.md new file mode 100755 index 0000000000000000000000000000000000000000..605305955e1fb98c0c54190026aca627b31348ed --- /dev/null +++ b/docs/source/slam-nav/lidarslam_slam_installation.md @@ -0,0 +1,181 @@ +# 从源码编译lidarslam_ros2 + +LidarSLAM 是一个基于 ROS2 的 3D 激光雷达 SLAM 软件包,前端采用OpenMP 加速的 GICP/NDT 扫描匹配,后端使用基于图优化的 SLAM 方法。该工具适用于移动机器人在室内外环境中的定位与建图,尤其在自动驾驶和机器人导航领域表现出色。 + +## 系统环境 + +操作系统: openEuler 24.03 + +ROS版本: ROS 2 Humble + +架构: x86 + +源代码: + +## 算法介绍 + +### frontend(scan-matcher) + +- input + /input_cloud (sensor_msgs/PointCloud2) + /tf(from "base_link" to LiDAR's frame) + /initial_pose (geometry_msgs/PoseStamed)(optional) + /imu (sensor_msgs/Imu)(optional) + /tf(from "odom" to "base_link")(Odometry)(optional) +- output + /current_pose (geometry_msgs/PoseStamped) + /map (sensor_msgs/PointCloud2) + /path (nav_msgs/Path) + /tf(from "map" to "base_link") + /map_array(lidarslam_msgs/MapArray) + +### backend(graph-based-slam) + +- input + /map_array(lidarslam_msgs/MapArray) +- output + /modified_path (nav_msgs/Path) + /modified_map (sensor_msgs/PointCloud2) +- srv + /map_save (std_srvs/Empty) + +- frontend(scan-matcher) + +| Name | Type | Default value | Description | +| ------------------------ | ------ | ------------- | ------------------------------------------------------------ | +| registration_method | string | "NDT" | 配准方法,可选 "NDT" 或 "GICP" | +| ndt_resolution | double | 5.0 | NDT 体素网格的分辨率大小[m] | +| ndt_num_threads | int | 0 | NDT 使用的线程数(若设为 0,则使用最大可用线程数)。(线程数越多越好,但如果CPU处理负载过大导致位姿估计失败,则应减少此值。) | +| gicp_corr_dist_threshold | double | 5.0 | 源点云与目标点云中对应点之间的最大距离阈值[m] | +| trans_for_mapupdate | double | 1.5 | 更新地图所需的最小移动距离[m] | +| vg_size_for_input | double | 0.2 | 输入点云的体素网格下采样尺寸[m] | +| vg_size_for_map | double | 0.05 | 地图点云的体素网格下采样尺寸[m] | +| use_min_max_filter | bool | false | 是否使用最小/最大距离滤波器 | +| scan_max_range | double | 100.0 | 输入点云的最大有效距离[m] | +| scan_min_range | double | 1.0 | 输入点云的最小有效距离[m] | +| scan_period | double | 0.1 | 输入点云的扫描周期[sec] | +| map_publish_period | double | 15.0 | 地图发布周期[sec] | +| num_targeted_cloud | int | 10 | 配准时使用的目标点云数量(此数值越大,点云失真越小。) | +| debug_flag | bool | false | 是否显示配准过程的调试信息 | +| set_initial_pose | bool | false | 是否在参数文件中设置默认的初始位姿 | +| initial_pose_x | double | 0.0 | 初始位姿的 X 坐标[m] | +| initial_pose_y | double | 0.0 | 初始位姿的 Y 坐标[m] | +| initial_pose_z | double | 0.0 | 初始位姿的 Z 坐标[m] | +| initial_pose_qx | double | 0.0 | 初始位姿的四元数 X 分量 | +| initial_pose_qy | double | 0.0 | 初始位姿的四元数 Y 分量 | +| initial_pose_qz | double | 0.0 | 初始位姿的四元数 Z 分量 | +| initial_pose_qw | double | 1.0 | 初始位姿的四元数 W 分量 | +| publish_tf | bool | true | 是否发布从全局坐标系到机器人坐标系的变换(tf) | +| use_odom | bool | false | 是否使用里程计数据作为点云配准的初始姿态估计 | +| use_imu | bool | false | 是否使用9轴IMU(必须包含角速度、加速度和方向数据)进行点云运动畸变校正。(注意:必须同时设置 scan_period 参数。) | +| debug_flag | bool | false | 是否显示配准过程的调试信息 | + +- backend(graph-based-slam) + +| Name | Type | Default value | Description | +| ------------------------------- | ------ | ------------- | ------------------------------------------------------------ | +| registration_method | string | "NDT" | 回环检测时使用的配准方法,可选 "NDT" 或 "GICP" | +| ndt_resolution | double | 5.0 | 回环检测中 NDT 的体素网格分辨率大小[m] | +| ndt_num_threads | int | 0 | 回环检测中 NDT 使用的线程数(若设为 0,则使用最大可用线程数。) | +| voxel_leaf_size | double | 0.2 | 输入点云的体素网格下采样尺寸[m] | +| loop_detection_period | int | 1000 | 搜索回环检测的周期[ms] | +| threshold_loop_closure_score | double | 1.0 | 用于判断回环闭合的 NDT 匹配得分阈值 | +| distance_loop_closure | double | 20.0 | 回环闭合候选点与当前位置的最小距离[m] | +| range_of_searching_loop_closure | double | 20.0 | 以当前位置为中心,搜索回环闭合候选点的半径[m] | +| search_submap_num | int | 2 | 用于回环配准的子地图数量(使用重访点前后各多少个子地图) | +| num_adjacent_pose_cnstraints | int | 5 | 位姿图中随时间连续的节点之间约束的数量 | +| use_save_map_in_loop | bool | true | 是否在检测到回环时保存地图(如果在回环闭合时的地图保存过程过于繁重,导致自定位估计失败,则将此参数设为 false。) | + +## 如何安装 + +在openeuler24.03的官方库中,缺少VKT包,PCL包是精简包,缺少部分依赖包,同时还需要一个ndt-omp-ros2的ros包。如若直接编译便会出现以下错误。 + +``` +/home/openeuler/ros2_ws/src/ndt_omp_ros2-humble/apps/align.cpp:10:10: 致命错误:pcl/visualization/pcl_visualizer.h:没有那个文件或目录 + 10 | #include + | ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~ +编译中断。 +``` + +首先下载以下依赖 + +``` +sudo dnf install flann-static -y +sudo dnf install ros-humble-pcl-conversions ros-humble-pcl-msgs +sudo dnf install ros-humble-libg2o +``` + +安装VTK + +``` +mkdir ~/src +cd ~/src +wget https://www.vtk.org/files/release/9.2/VTK-9.2.6.tar.gz +tar -xzf VTK-9.2.6.tar.gz +cd VTK-9.2.6 +mkdir build +cd build + +cmake .. \ + -DVTK_SMP_IMPLEMENTATION_TYPE=OpenMP \ + -DVTK_USE_SYSTEM_TBB=OFF + +make -j$(nproc) +sudo make install +sudo ldconfig +``` + +安装PCL + +``` +cd ~/src +git clone https://github.com/PointCloudLibrary/pcl.git +cd pcl +git checkout pcl-1.12.1 + +mkdir build && cd build +cmake .. \ + -DCMAKE_BUILD_TYPE=Release \ + -DCMAKE_INSTALL_PREFIX=/usr/local \ + -DWITH_VTK=ON \ + -DBUILD_visualization=ON + +make -j$(nproc) +sudo make install +sudo ldconfig + +vim ~/.bashrc +#添加以下(注意,添加把 PCL_DIR 或 CMAKE_PREFIX_PATH 指向包含 PCLConfig.cmake 的目录) +export PCL_DIR=/usr/local/share/pcl-1.12 +export CMAKE_PREFIX_PATH=/usr/local:$CMAKE_PREFIX_PATH +export LD_LIBRARY_PATH=/usr/local/lib:$LD_LIBRARY_PATH +``` + +编译lidarslam_ros2,请下载https://github.com/rsasaki0109/lidarslam_ros2.git和https://github.com/rsasaki0109/ndt_omp_ros2.git并放入ros2工作空间的src中 + +``` +colcon build --symlink-install --cmake-args -DCMAKE_BUILD_TYPE=Release +``` + +如果编译出错请检查系统里同时存在两个 PCL 的 CMake 配置,且编译时用到了系统的 PCL!! + +## 实机测试 + +``` +ros2 launch robot_description robot_display_launch.py +ros2 bag play hdl_400 +``` + +‍ + +![image](./image/lidarslam_1.png) + +保存地图 + +``` +ros2 service call /map_save std_srvs/Empty +``` + +![image](./image/lidarslam_2.png) + +‍