自定义速腾激光雷达点云XYZIRT格式并调用PCL库进行滤波

6 篇文章 1 订阅


Windows 10 + Ubuntu 20.04 + VS Code
激光雷达速腾RS-LiDAR-32 + sdk v1.5.7

速腾激光雷达的ROS程序包可以输出XYZIRT格式,但是PCL库的点没有这种类型,需要进行自定义,并可以进行直通滤波和体素滤波等下采样处理。

一、试验程序源代码

1.1需要包含的头文件

#include <iostream>	
#include <cmath>

#include <pcl/common/transforms.h>
#include <pcl/io/pcd_io.h>	        
#include <pcl/point_types.h>	    

#include <pcl/filters/passthrough.h>
#include <pcl/filters/extract_indices.h>

1.2定义点云结构

struct MyPointType
{
  PCL_ADD_POINT4D;
  float intensity;
  uint16_t ring = 0;
  double timestamp = 0;
  EIGEN_MAKE_ALIGNED_OPERATOR_NEW
} EIGEN_ALIGN16;

POINT_CLOUD_REGISTER_POINT_STRUCT(MyPointType,    //注册点类型宏
    (float ,x,x)
    (float ,y,y)
    (float ,z,z)
    (float ,intensity,intensity)
    (uint16_t ,ring,ring)
    (double ,timestamp,timestamp)
)

1.3主函数

int main(int argc, char** argv)
{
	pcl::PCLPointCloud2::Ptr cloud_in(new pcl::PCLPointCloud2());
    pcl::PCLPointCloud2::Ptr cloud_filtered(new pcl::PCLPointCloud2());
    pcl::PointCloud<MyPointType>::Ptr cloud_voxel(new pcl::PointCloud<MyPointType>);
    pcl::PointCloud<MyPointType>::Ptr cloud_pass(new pcl::PointCloud<MyPointType>);

    pcl::PCDReader reader;
    reader.read("../111.pcd", *cloud_in); // Remember to download the file first!
 
    pcl::VoxelGrid<pcl::PCLPointCloud2> sor;
    sor.setInputCloud(cloud_in);
    sor.setLeafSize(0.1f, 0.1f, 0.1f);
    sor.filter(*cloud_filtered);
 
    pcl::fromPCLPointCloud2(*cloud_filtered, *cloud_voxel);
    pcl::io::savePCDFile("../voxel.pcd", *cloud_voxel);

    pcl::PassThrough <pcl::PCLPointCloud2> pass;
    pass.setInputCloud (cloud_in);
    pass.setFilterFieldName ("y");
    pass.setFilterLimits (5, 100);
    pass.setFilterLimitsNegative (false);
    pass.filter (*cloud_filtered);
    
    pcl::fromPCLPointCloud2(*cloud_filtered, *cloud_pass);
    pcl::io::savePCDFile("../pass.pcd", *cloud_pass);
}

1.4 CMake文件

cmake_minimum_required(VERSION 2.8 FATAL_ERROR)

project(ring_time)

find_package(PCL 1.2 REQUIRED)
SET(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++11 -pthread")
set(CMAKE_CXX_STANDARD 14)

find_package(Boost REQUIRED COMPONENTS thread)
include_directories(${Boost_INCLUDE_DIR})
link_directories(${Boost_LIBRARY_DIRS})
add_definitions(-DBOOST_ALL_DYN_LINK)

include_directories(${PCL_INCLUDE_DIRS})
link_directories(${PCL_LIBRARY_DIRS})
add_definitions(${PCL_DEFINITIONS})

aux_source_directory(. ALL_SRCS)

add_executable (ring_time ring_time.cpp ${ALL_SRCS})
target_link_libraries (ring_time ${PCL_LIBRARIES})

二、学习pcl::PCLPointCloud2::Ptr

直接用pcl::PointCloud<MyPointType>::Ptr 无法调用PCL的滤波函数。

2.1区别

pcl::PCLPointCloud2是为了与ROS更加兼容的PCL数据结构
pcl::PointCloud<T>是PCL数据标准结构
用pcl::PCLPointCloud2处理完后,转换成pcl::PointCloud<T>进行保存。

2.2转换

PCL中有两个函数直接解决了两者的转换关系:
1.pcl::fromPCLPointCloud2()
2.pcl::toPCLPointCloud2()
//cloud_filtered转换为cloud_pass,从pcl::PCLPointCloud2格式转换为模板点云pcl::PointCloud<pointT>
1、pcl::fromPCLPointCloud2(*cloud_filtered, *cloud_pass);
2、与1相反

  fromPCLPointCloud2 (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud)
  {
    MsgFieldMap field_map;
    createMapping<PointT> (msg.fields, field_map);    //创建一个field索引表
    fromPCLPointCloud2 (msg, cloud, field_map);       //转换点云
  }

2.3心得

1、处理带ring的点云需要自定义格式,而且要用到pcl::PCLPointCloud2::Ptr进行处理
2、直通滤波只能XYZI,不能滤除intensity和timestamp信息
3、发现一个VS Code里一个好用的pcd点云查看拓展vscode-3d-preview

参考资料:
链接: PCL自定义点和点云使用
链接: pcl::PCLPointCloud2 Struct Reference
链接: PCL点云类型之间相互转换
链接: PCL点云滤波

  • 2
    点赞
  • 4
    收藏
    觉得还不错? 一键收藏
  • 打赏
    打赏
  • 0
    评论
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包

打赏作者

可见一班

你的鼓励将是我创作的最大动力

¥1 ¥2 ¥4 ¥6 ¥10 ¥20
扫码支付:¥1
获取中
扫码支付

您的余额不足,请更换扫码支付或充值

打赏作者

实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值