3D点云处理 PCL稀疏处理

实验平台:ubuntu20.04

实验目的:使用pcl订阅雷达数据实现数据的稀疏处理

实验数据:ros 激光雷达数据

PCL的VoxelGrid滤波器下采样

本次用到的主要的类是CloudViewer,是一个简单的点云可视化工具。

原理:

使用体素化网格方法实现下采样,即保存点云的形状特征的同时实现减少点的数量 减少点云数据,在提高配准,曲面重建,形状识别等算法速度中非常实用,PCL是实现的VoxelGrid类通过输入的点云数据创建一个三维体素栅格,容纳后每个体素内用体素中所有点的重心来近似显示体素中其他点,这样该体素内所有点都用一个重心点最终表示,对于所有体素处理后得到的过滤后的点云,这种方法比用体素中心逼近的方法更慢,但是对于采样点对应曲面的表示更为准确。

代码:

1.ROS数据订阅

修改CmakeLists.txt 在PCL基础上加载ROS功能包

cmake_minimum_required(VERSION 2.8 FATAL_ERROR)


project(test)


find_package(PCL 1.13 REQUIRED)
find_package(catkin REQUIRED COMPONENTS ${PACKAGE_DEPENDENCIES})


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


add_executable(test main.cpp)
target_link_libraries(test ${PCL_LIBRARIES} ${catkin_LIBRARIES})

2.写一个类pcl_me 实现ROS 数据的订阅和数据的回调

#include                          //标准输入输出头文件申明
#include 
#include 
#include 
#include 
#include  //类cloud_viewer头文件申明
#include  
#include 


class pcl_me
{
private:
  ros::NodeHandle n;
  ros::Subscriber subCloud;
  ros::Publisher pubCloud;
  sensor_msgs::PointCloud2 msg;  //接收到的点云消息
  sensor_msgs::PointCloud2 adjust_msg;  //等待发送的点云消息
  pcl::PointCloud adjust_pcl;   //建立了一个pcl的点云,作为中间过程


public:
  pcl_me():
    n("~"){
    subCloud = n.subscribe("/rslidar_points", 1, &pcl_me::getcloud, this); //接收点云数据,进入回调函数getcloud()
    pubCloud = n.advertise("/adjustd_cloud", 1000);  //建立了一个发布器,主题是/adjusted_cloud,方便之后发布调整后的点云
  }


  //回调函数
  void getcloud(const sensor_msgs::PointCloud2ConstPtr& laserCloudMsg){
    pcl::PointCloud::Ptr cloud (new pcl::PointCloud);   //放在这里是因为,每次都需要重新初始化
    pcl::PointCloud::Ptr cloud_filtered (new pcl::PointCloud);


    pcl::fromROSMsg(*laserCloudMsg, *cloud);  //把msg消息转化为点云 
/******************************************************************************
  创建一个voxel叶大小为1cm的pcl::VoxelGrid滤波器,
**********************************************************************************/
    pcl::VoxelGrid sor;  //创建滤波对象
    sor.setInputCloud (cloud);            //设置需要过滤的点云给滤波对象
    sor.setLeafSize (10.0f, 10.0f, 10.0f);  //设置滤波时创建的体素体积为1cm的立方体
    sor.filter (*cloud_filtered);           //执行滤波处理,存储输出


    sensor_msgs::PointCloud2 pub_pc;
    pcl::toROSMsg(*cloud_filtered, pub_pc);
    pub_pc.header = laserCloudMsg->header;
    pubCloud.publish(pub_pc); 


  }
  ~pcl_me(){}


};

主函数 初始化ROS节点 实例化类 开启ROS的循环 等待雷达数据实现回调函数的

int main(int argc, char** argv) {
  ros::init(argc, argv, "colored");  //初始化了一个节点,名字为colored
  pcl_me ps;
  ros::spin();
  return 0;
  }

3.编译 运行

mkdir bui;d
cd build
cmake ..
make

运行test可执行程序

4.稀疏的点云数据已经输出:

总结:

主要使用点云稀疏是降采样方法或者滤波算法,VoxelGrid滤波器下采样.

主要步骤:

创建滤波对象

pcl::VoxelGrid sor;

设置需要过滤的点云给滤波对象

sor.setInputCloud (cloud);

设置滤波时创建的体素体积为1cm的立方体

sor.setLeafSize (10.0f, 10.0f, 10.0f);

执行滤波处理,存储输出

sor.filter (*cloud_filtered);

展开阅读全文

页面更新:2024-05-14

标签:稀疏   立方体   曲面   滤波器   初始化   函数   对象   消息   方法   数据

1 2 3 4 5

上滑加载更多 ↓
推荐阅读:
友情链接:
更多:

本站资料均由网友自行发布提供,仅用于学习交流。如有版权问题,请与我联系,QQ:4156828  

© CopyRight 2020-2024 All Rights Reserved. Powered By 71396.com 闽ICP备11008920号-4
闽公网安备35020302034903号

Top