功能包介绍

功能包名称:
lidar_imu_calib

功能包简介:
在基于3D激光雷达开发slam时,我们经常使用imu为匹配算法(icp, ndt)提供先验,所以需要校准lidar和imu之间的变换。对于匹配算法,transfom中的姿态比transform中的位置更重要 , 并且位置通常设置为 0。所以这个功能包只校准激光雷达和 imu 之间转换中的姿态分量。

功能包地址:
https://github.com/chennuo0125-HIT/lidar_imu_calib

功能包下载与编译

安装步骤:

mkdir -p catkin_ws/src   
cd catkin_ws/src
git clone https://github.com/chennuo0125-HIT/lidar_imu_calib.git
cd ..
catkin_make -DCATKIN_WHITELIST_PACKAGES="ndt_omp;lidar_imu_calib"

此时会出现报错问题

报错内容:

/usr/include/pcl-1.10/pcl/common/impl/io.hpp: In function ‘void pcl::copyPointCloud(const pcl::PointCloud<PointT>&, const std::vector<pcl::PointIndices>&, pcl::PointCloud<PointOutT>&)’:
/usr/include/pcl-1.10/pcl/common/impl/io.hpp:272:16: error: use of ‘auto’ in lambda parameter declaration only available with ‘-std=c++14’ or ‘-std=gnu++14’
  272 |       [](const auto& acc, const auto& index) { return index.indices.size() + acc; });
      |                ^~~~
/usr/include/pcl-1.10/pcl/common/impl/io.hpp:272:33: error: use of ‘auto’ in lambda parameter declaration only available with ‘-std=c++14’ or ‘-std=gnu++14’
  272 |       [](const auto& acc, const auto& index) { return index.indices.size() + acc; });
      |                                 ^~~~
/usr/include/pcl-1.10/pcl/common/impl/io.hpp: In lambda function:
/usr/include/pcl-1.10/pcl/common/impl/io.hpp:272:61: error: request for member ‘indices’ in ‘index’, which is of non-class type ‘const int’
  272 |       [](const auto& acc, const auto& index) { return index.indices.size() + acc; });
      |                                                             ^~~~~~~
In file included from /usr/include/pcl-1.10/pcl/io/pcd_io.h:44,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/src/lib/calibExRLidar2Imu.cpp:5:
/usr/include/pcl-1.10/pcl/io/file_io.h: At global scope:
/usr/include/pcl-1.10/pcl/io/file_io.h:235:8: error: ‘enable_if_t’ in namespace ‘std’ does not name a template type; did you mean ‘enable_if’?
  235 |   std::enable_if_t<std::is_floating_point<Type>::value>
      |        ^~~~~~~~~~~
      |        enable_if
In file included from /usr/include/pcl-1.10/pcl/io/pcd_io.h:44,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/src/lib/calibExRLidar2Imu.cpp:5:
/usr/include/pcl-1.10/pcl/io/file_io.h:252:8: error: ‘enable_if_t’ in namespace ‘std’ does not name a template type; did you mean ‘enable_if’?
  252 |   std::enable_if_t<std::is_integral<Type>::value>
      |        ^~~~~~~~~~~
      |        enable_if
/usr/include/pcl-1.10/pcl/io/file_io.h:266:18: error: expected initializer before ‘<’ token
  266 |   copyValueString<std::int8_t> (const pcl::PCLPointCloud2 &cloud,
      |                  ^
/usr/include/pcl-1.10/pcl/io/file_io.h:280:18: error: expected initializer before ‘<’ token
  280 |   copyValueString<std::uint8_t> (const pcl::PCLPointCloud2 &cloud,
      |                  ^
/usr/include/pcl-1.10/pcl/io/file_io.h:304:8: error: ‘enable_if_t’ in namespace ‘std’ does not name a template type; did you mean ‘enable_if’?
  304 |   std::enable_if_t<std::is_floating_point<Type>::value, bool>
      |        ^~~~~~~~~~~
      |        enable_if
/usr/include/pcl-1.10/pcl/io/file_io.h:317:8: error: ‘enable_if_t’ in namespace ‘std’ does not name a template type; did you mean ‘enable_if’?
  317 |   std::enable_if_t<std::is_integral<Type>::value, bool>
      |        ^~~~~~~~~~~
      |        enable_if
^CIn file included from /usr/include/c++/9/algorithm:62,
                 from /usr/include/boost/smart_ptr/shared_ptr.hpp:39,
                 from /usr/include/pcl-1.10/pcl/pcl_macros.h:69,
                 from /usr/include/pcl-1.10/pcl/point_types.h:42,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/include/calibExRLidar2Imu.h:9,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/src/lib/calibExRLidar2Imu.cpp:1:
/usr/include/c++/9/bits/stl_algo.h: In instantiation of ‘_OIter std::transform(_IIter, _IIter, _OIter, _UnaryOperation) [with _IIter = __gnu_cxx::__normal_iterator<const pcl::Vertices*, std::vector<pcl::Vertices> >; _OIter = std::back_insert_iterator<std::vector<pcl::Vertices> >; _UnaryOperation = pcl::PolygonMesh::concatenate(pcl::PolygonMesh&, const pcl::PolygonMesh&)::<lambda(int)>]’:
/usr/include/pcl-1.10/pcl/PolygonMesh.h:55:24:   required from here
/usr/include/c++/9/bits/stl_algo.h:4343:24: error: no match for call to ‘(pcl::PolygonMesh::concatenate(pcl::PolygonMesh&, const pcl::PolygonMesh&)::<lambda(int)>) (const pcl::Vertices&)’
 4343 |  *__result = __unary_op(*__first);
      |              ~~~~~~~~~~^~~~~~~~~~
In file included from /usr/include/pcl-1.10/pcl/common/io.h:50,
                 from /usr/include/pcl-1.10/pcl/filters/filter.h:43,
                 from /usr/include/pcl-1.10/pcl/filters/voxel_grid.h:43,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/include/calibExRLidar2Imu.h:11,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/src/lib/calibExRLidar2Imu.cpp:1:
/usr/include/pcl-1.10/pcl/PolygonMesh.h:45:22: note: candidate: ‘pcl::PolygonMesh::concatenate(pcl::PolygonMesh&, const pcl::PolygonMesh&)::<lambda(int)>’
   45 |                      [point_offset](auto polygon)
      |                      ^
/usr/include/pcl-1.10/pcl/PolygonMesh.h:45:22: note:   no known conversion for argument 1 from ‘const pcl::Vertices’ to ‘int’
In file included from /usr/include/c++/9/numeric:62,
                 from /usr/include/boost/random/discrete_distribution.hpp:18,
                 from /usr/include/boost/random.hpp:63,
                 from /usr/include/pcl-1.10/pcl/filters/boost.h:48,
                 from /usr/include/pcl-1.10/pcl/filters/voxel_grid.h:42,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/include/calibExRLidar2Imu.h:11,
                 from /home/jone/jone_ws/src/lidar_imu_calib/lidar_imu_calib/src/lib/calibExRLidar2Imu.cpp:1:
/usr/include/c++/9/bits/stl_numeric.h: In instantiation of ‘_Tp std::accumulate(_InputIterator, _InputIterator, _Tp, _BinaryOperation) [with _InputIterator = __gnu_cxx::__normal_iterator<const pcl::PCLPointField*, std::vector<pcl::PCLPointField> >; _Tp = std::__cxx11::basic_string<char>; _BinaryOperation = pcl::getFieldsList(const pcl::PCLPointCloud2&)::<lambda(const int&, const int&)>]’:
/usr/include/pcl-1.10/pcl/common/io.h:144:82:   required from here
/usr/include/c++/9/bits/stl_numeric.h:166:22: error: no match for call to ‘(pcl::getFieldsList(const pcl::PCLPointCloud2&)::<lambda(const int&, const int&)>) (std::__cxx11::basic_string<char>&, const pcl::PCLPointField&)’
  166 |  __init = __binary_op(_GLIBCXX_MOVE_IF_20(__init), *__first);
      |           ~~~~~~~~~~~^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~

只截取了其中一段

报错原因:
ubuntu 20.04 的 ros版本是noetic 带的pcl是 pcl-1.10,这个版本和之前的有所不同

这么多错误就一个原因 : pcl-1.10需要用c++14及以上编译。

报错解决方法:
打开 lidar_imu_calib 文件夹下的 CMakeLists.txt
将第五行

add_compile_options(-std=c++11)

换成

add_compile_options(-std=c++14)

即可编译成功
在这里插入图片描述

使用功能包

接入雷达和imu

找个电源适配器,9-18v给雷达供电。雷达连接其连接器,网口接到ROS的工控机上即可
在这里插入图片描述
将工控机的网口配置为

ipv4,方式设置为手动
ip地址、掩码以及网关设置成下图
在这里插入图片描述
其中地址 不能为 192.168.1.201 ,这个是雷达的地址

运行雷达驱动程序

roslaunch velodyne_pointcloud VLP16_points.launch

imu模块的硬件连接很简单,usb给模块供电,并与pc通信,插上后

运行imu驱动程序

roslaunch fdilink_ahrs ahrs_data.launch

通过 rostopic list 指令,检查下消息是 否正确
在这里插入图片描述
图片中的/imu /velodyne_points就是两个传感器的消息名称

录制 rosbag 文件

通过

rosbag record /imu /velodyne_points

来录制两个传感器的消息
在这里插入图片描述

执行 lidar_imu_calib 功能包

上面的工作主要是给功能包准备数据,下面即可执行功能包了

首先需要 修改 配置文件
相关的参数没有config文件夹的yaml文件,是直接在其launch文件中设置的
在这里插入图片描述
将 /lidar_topic 和 /imu_topic 与/bag_file 修改成自己的

之后便可以运行功能包

roslaunch lidar_imu_calib calib_exR_lidar2imu.launch

功能包会显示添加 lidar 消息
在这里插入图片描述
在这里插入图片描述
最后会显示 lidar的消息数量和imu的数量 形成约束的数量

在这里插入图片描述
再等一下就会出现计算的结果

用上面标定结果进行lio-sam建图

LIO-SAM 在 ubuntu16.04 和 ubuntu18.04 编译都不麻烦。

但是最近配置的工控机是 ubuntu20.04 的 安装的ROS版本的是noetic,在编译LIO-SAM中遇到了很多问题,在此记录并发布出来。

eigen3的问题

在usr/local/include 中找不到 eigen3 ,因为它在 usr/include中,将其复制下
在这里插入图片描述

opencv 的问题

In file included from /home/jone/jone_ws/src/LIO-SAM/src/featureExtraction.cpp:1:
/home/jone/jone_ws/src/LIO-SAM/include/utility.h:18:10: fatal error: opencv/cv.h: 没有那个文件或目录
   18 | #include <opencv/cv.h>
      |          ^~~~~~~~~~~~~
In file included from /home/jone/jone_ws/src/LIO-SAM/src/mapOptmization.cpp:1:
/home/jone/jone_ws/src/LIO-SAM/include/utility.h:18:10: fatal error: opencv/cv.h: 没有那个文件或目录
   18 | #include <opencv/cv.h>
      |          ^~~~~~~~~~~~~
In file included from /home/jone/jone_ws/src/LIO-SAM/src/imuPreintegration.cpp:1:
/home/jone/jone_ws/src/LIO-SAM/include/utility.h:18:10: fatal error: opencv/cv.h: 没有那个文件或目录
   18 | #include <opencv/cv.h>
      |          ^~~~~~~~~~~~~
In file included from /home/jone/jone_ws/src/LIO-SAM/src/imageProjection.cpp:1:
/home/jone/jone_ws/src/LIO-SAM/include/utility.h:18:10: fatal error: opencv/cv.h: 没有那个文件或目录
   18 | #include <opencv/cv.h>
      |          ^~~~~~~~~~~~~
compilation terminated.
compilation terminated.
compilation terminated.
compilation terminated.

由于 20.04 自带的是OpenCV4,所以要对 LIO-SAM 代码做一点改动

在 utility.h 中的

#include<opencv/cv.h>

改为

#include<opencv2/imgproc.hpp>

在这里插入图片描述

pcl的问题

pcl的问题主要是需要 C++14的编译
在这里插入图片描述这里修改 lio-sam 的编译配置就行 ,打开 liosam的CMakeLists.txt:

将第5行的

set(CMAKE_CXX_FLAGS "-std=c++11")

改为

set(CMAKE_CXX_FLAGS "-std=c++14")

在这里插入图片描述

运行时的问题

process[lio_sam_mapOptmization-5]: started with pid [10295]
/home/jone/jone_ws/devel/lib/lio_sam/lio_sam_mapOptmization: error while loading shared libraries: libmetis.so: cannot open shared object file: No such file or directory
[lio_sam_imuPreintegration-2] process has died [pid 10294, exit code 127, cmd /home/jone/jone_ws/devel/lib/lio_sam/lio_sam_imuPreintegration __name:=lio_sam_imuPreintegration __log:=/home/jone/.ros/log/26ccf03a-2997-11ed-8e43-49590f7f8a53/lio_sam_imuPreintegration-2.log].
log file: /home/jone/.ros/log/26ccf03a-2997-11ed-8e43-49590f7f8a53/lio_sam_imuPreintegration-2*.log
[lio_sam_mapOptmization-5] process has died [pid 10295, exit code 127, cmd /home/jone/jone_ws/devel/lib/lio_sam/lio_sam_mapOptmization __name:=lio_sam_mapOptmization __log:=/home/jone/.ros/log/26ccf03a-2997-11ed-8e43-49590f7f8a53/lio_sam_mapOptmization-5.log].
log file: /home/jone/.ros/log/26ccf03a-2997-11ed-8e43-49590f7f8a53/lio_sam_mapOptmization-5*.log

报错找不到 libmetis.so 这个文件

这个和 gtsam 编译时候的 方法有关

实际问题是库文件libmetis.so 的位置。它是一个运行时库,但是当应用程序查找它时,它的位置不在预期的目录中。在通过运行命令sudo make install -j8安装库gtsam 时,文件libmetis.so安装在/usr/local/lib/的默认位置,但是当我们启动 ros 工作区时,运行时库查看位置/opt/ros/noetic/lib/

cd /usr/local/lib/
sudo cp libmetis.so /opt/ros/noetic/lib/

可以解决这个问题

再次运行

ERROR: cannot launch node of type [robot_localization/ekf_localization_node]: robot_localization
ROS path [0]=/opt/ros/noetic/share/ros
ROS path [1]=/home/jone/jone_ws/src
ROS path [2]=/opt/ros/noetic/share
ERROR: cannot launch node of type [robot_localization/navsat_transform_node]: robot_localization
ROS path [0]=/opt/ros/noetic/share/ros
ROS path [1]=/home/jone/jone_ws/src
ROS path [2]=/opt/ros/noetic/share

这个错位是少了 robot_localization 这个功能包

sudo apt-get install ros-noetic-fake-localization
sudo apt-get install ros-noetic-robot-localization

在这里插入图片描述
终于成功运行

将imu与雷达的外参进行配置

  #extrinsicRot: [-1, 0, 0,
  #                0, 1, 0,
  #                0, 0, -1]
  #extrinsicRPY: [0, -1, 0,
  #               1, 0, 0,
  #               0, 0, 1]
  extrinsicRot: [0.999014, -0.0354845, 0.0266871,
                 0.035815, 0.999286, -0.0120079,
                 -0.026242, 0.0129519, 0.999572]
  extrinsicRPY: [0.999014, -0.0354845, 0.0266871,
                 0.035815, 0.999286, -0.0120079,
                 -0.026242, 0.0129519, 0.999572]
  pointCloudTopic: "/velodyne_points"               # Point cloud data
  imuTopic: "/imu"                         # IMU data

result

在这里插入图片描述