禾赛激光雷达点云格式转换适配lio-sam、fast-lio2算法
禾赛、速腾三维雷达适配lio-sam、fast-lio2建图算法
lio-sam与fast-lio2算法,对于机械雷达而言,均只适配了Veloyne雷达,而对国内的雷达均不适配。国内速腾、禾赛等雷达需要将点云数据结构转化为Veloyne结构,进而运行lio-sam、fast-lio等建图算法,本文主要讲解速腾、禾赛雷达数据格式与Velodyne数据格式之间的转换。
1.速腾雷达数据格式转换适配lio-sam算法
网上已开源速腾雷达转Veloyne数据结构算法,下面给出下载链接:https://gitee.com/duanyuanchao123/rs_to_velodyne.git
2.禾赛雷达数据格式转换适配lio-sam算法
禾赛雷达数据转换具体参考rs_to_velodyne,下载链接:https://gitee.com/duanyuanchao123/hesai_to_velodyne.git
2.1 禾赛雷达与Veloyne数据结构
禾赛雷达数据结构为:
// hesai lidar的点云格式
struct HesaiPointXYZIRT
{
PCL_ADD_POINT4D;
// uint8_t intensity;
PCL_ADD_INTENSITY;
double timestamp = 0;
uint16_t ring = 0;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
POINT_CLOUD_REGISTER_POINT_STRUCT(HesaiPointXYZIRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(double, timestamp, timestamp)(uint16_t, ring, ring))
Veloyne数据结构为:
// velodyne的点云格式
struct VelodynePointXYZIRT
{
PCL_ADD_POINT4D
PCL_ADD_INTENSITY;
uint16_t ring;
float time;
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;
POINT_CLOUD_REGISTER_POINT_STRUCT(VelodynePointXYZIRT,
(float, x, x)(float, y, y)(float, z, z)(float, intensity, intensity)(uint16_t, ring, ring)(float, time, time))
2.2 安装hesai_to_velodyne转换节点
- 安装完成禾赛雷达驱动之后,下载hesai_to_velodyne功能包并编译。
git clone https://gitee.com/duanyuanchao123/hesai_to_velodyne.git
cd ..
catkin_make
- 新建launch文件夹,在launch文件夹内新建hesai_to_velodyne.launch启动节点
<launch>
<param name="lidar_topic" value="/hesai_2/pandar"/>
<param name="publish_lidar_topic" value="/velodyne_back_points"/>
<node pkg="hesai_to_velodyne" type="hesai_to_velodyne" name="hesai_to_velodyne_node" args="XYZIRT XYZIRT"/>
</launch>
- 修改订阅的雷达话题lidar_topic和发布转换后发布的雷达话题,注意args参数,采集XYZIRT格式的点输入XYZIRT,采集XYZIRT格式的点输入XYZIRT
<param name="lidar_topic" value="/hesai_2/pandar"/>
<param name="publish_lidar_topic" value="/velodyne_points"/>
- 编译并启动launch文件
catkin_make
source devel/setup.bash
roslaunch hesai_to_velodyne hesai_to_velodyne.launch
rostopic list
查看发布后的话题消息,同过rostopic echo /velodyne_points -p
打印查看/veloyne_points话题数据
- .在雷达驱动的launch文件中添加以下语句,将激光雷达与数据转换一起启动
<!--- hesai_ros -->
<include file="$(find hesai_to_velodyne)/launch/hesai_to_velodyne.launch" />