PCL点云滤波

pcl --- Module filters

https://pointclouds.org/documentation/group__filters.html

点云数据类型

sensor_msgs::LaserScan

sensor_msgs::PointCloud — ROS message (deprecated)

sensor_msgs::PointCloud2 — ROS message

pcl::PCLPointCloud2 — PCL data structure mostly for compatibility with ROS

pcl::PointCloud<T> — standard PCL data structure 

sensor_msgs::LaserScan

std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
float32 angle_min
float32 angle_max
float32 angle_increment
float32 time_increment
float32 scan_time
float32 range_min
float32 range_max
float32[] ranges
float32[] intensities

sensor_msgs::PointCloud2

std_msgs/Header header
  uint32 seq
  time stamp
  string frame_id
uint32 height  //点云的高度,如果是无序点云,则为1
uint32 width  //每行点云的宽度
sensor_msgs/PointField[] fields
  uint8 INT8=1
  uint8 UINT8=2
  uint8 INT16=3
  uint8 UINT16=4
  uint8 INT32=5
  uint8 UINT32=6
  uint8 FLOAT32=7
  uint8 FLOAT64=8
  string name
  uint32 offset
  uint8 datatype
  uint32 count
bool is_bigendian
uint32 point_step  //每个点占用的比特数,1个字节对应8个比特数
uint32 row_step  //每一行占用的比特数
uint8[] data  //为序列化后的数据,直接获得不了信息,序列化是为了方便信息传输和交换,使用时需要反序列化
bool is_dense  //是否有非法数据点,true表示没有

pcl::PCLPointCloud2

namespace pcl
{
    struct PCLPointCloud2
    {
        PCLPointCloud2 () : header (), height (0), width (0), fields (),
        is_bigendian (false), point_step (0), row_step (0),
        data (), is_dense (false)
        {
            #if defined(BOOST_BIG_ENDIAN)
            is_bigendian = true;
            #elif defined(BOOST_LITTLE_ENDIAN)
            is_bigendian = false;
            #else
            #error "unable to determine system endianness"
            #endif
        }
        ::pcl::PCLHeader header;
        pcl::uint32_t height;
        pcl::uint32_t width;
        std::vector< ::pcl::PCLPointField>  fields;
        pcl::uint8_t is_bigendian;
        pcl::uint32_t point_step;
        pcl::uint32_t row_step;
        std::vector<pcl::uint8_t> data;
        pcl::uint8_t is_dense;

        public:
        typedef boost::shared_ptr< ::pcl::PCLPointCloud2> Ptr;
        typedef boost::shared_ptr< ::pcl::PCLPointCloud2  const> ConstPtr;
    }; // struct PCLPointCloud2

    typedef boost::shared_ptr< ::pcl::PCLPointCloud2> PCLPointCloud2Ptr;
    typedef boost::shared_ptr< ::pcl::PCLPointCloud2 const> PCLPointCloud2ConstPtr;
}

pcl::PCLPointCloud2 是 ROS(机器人操作系统)消息类型,取代旧的 sensors_msgs::PointCloud2。因此,它只能在与 ROS 进行交互时使用。

PCLPointCloud2 --- PointCloud转化

// 从 PCLPointCloud2 转化为 PointCloud
void fromPCLPointCloud2(const pcl::PCLPointCloud2& msg, cl::PointCloud<PointT>& cloud); 
// 内部调用 fromPCLPointCloud2 函数
void fromROSMsg (const pcl::PCLPointCloud2& msg, pcl::PointCloud<PointT>& cloud);
      
// 从 PointCloud 转化为 PCLPointCloud2
void toPCLPointCloud2(const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg); 
// 内部调用 toPCLPointCloud2 函数
void toROSMsg (const pcl::PointCloud<PointT>& cloud, pcl::PCLPointCloud2& msg);

1.体素网格滤波

pcl::VoxelGrid< pcl::PCLPointCloud2 > Class Reference

https://pointclouds.org/documentation/classpcl_1_1_voxel_grid_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html#details

Definition at line 513 of file voxel_grid.h.

https://pointclouds.org/documentation/filters_2include_2pcl_2filters_2voxel__grid_8h_source.html#l00513

构造函数

       VoxelGrid () :
         leaf_size_ (Eigen::Vector4f::Zero ()),
         inverse_leaf_size_ (Eigen::Array4f::Zero ()),
         downsample_all_data_ (true),
         save_leaf_layout_ (false),
         min_b_ (Eigen::Vector4i::Zero ()),
         max_b_ (Eigen::Vector4i::Zero ()),
         div_b_ (Eigen::Vector4i::Zero ()),
         divb_mul_ (Eigen::Vector4i::Zero ()),
         filter_field_name_ (""),
         filter_limit_min_ (std::numeric_limits<float>::lowest()),
         filter_limit_max_ (std::numeric_limits<float>::max()),
         filter_limit_negative_ (false),
         min_points_per_voxel_ (0)
       {
         filter_name_ = "VoxelGrid";
       }

setLeafSize()

/** \brief Set the voxel grid leaf size.
* \param[in] leaf_size the voxel grid leaf size
*/
       inline void
       setLeafSize (const Eigen::Vector4f &leaf_size)
       {
         leaf_size_ = leaf_size;
         // Avoid division errors
         if (leaf_size_[3] == 0)
           leaf_size_[3] = 1;
         // Use multiplications instead of divisions
         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
       }
/** \brief Set the voxel grid leaf size.
* \param[in] lx the leaf size for X
 * \param[in] ly the leaf size for Y
 * \param[in] lz the leaf size for Z
*/
       inline void
       setLeafSize (float lx, float ly, float lz)
       {
         leaf_size_[0] = lx; leaf_size_[1] = ly; leaf_size_[2] = lz;
         // Avoid division errors
         if (leaf_size_[3] == 0)
           leaf_size_[3] = 1;
         // Use multiplications instead of divisions
         inverse_leaf_size_ = Eigen::Array4f::Ones () / leaf_size_.array ();
       }

setInputCloud()

template <typename PointT> void
pcl::PCLBase<PointT>::setInputCloud (const PointCloudConstPtr &cloud)
{ 
  input_ = cloud; 
}

filter()

void pcl::Filter< PointT >::filter 	( 	PointCloud &  	output	) 	
Calls the filtering method and returns the filtered dataset in output. 
Parameters
    [out]	output	the resultant filtered point cloud dataset 

测试

    pcl::VoxelGrid<pcl::PCLPointCloud2> downsample_filter;
    downsample_filter.setLeafSize(0.1, 0.1, 0.1);
    downsample_filter.setDownsampleAllData(true); 
    downsample_filter.setInputCloud(cloudPtr);
    downsample_filter.filter(cloud_filtered); 

 原始点云

 2.直通滤波

https://pointclouds.org/documentation/classpcl_1_1_pass_through_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html

 setFilterFieldName ()

void 	setFilterFieldName (const std::string &field_name)
Provide the name of the field to be used for filtering data.

In conjunction with setFilterLimits, points having values outside this interval will be discarded. 
Parameters
    [in]	field_name	the name of the field that contains values used for filtering 

测试

pcl::PassThrough<pcl::PCLPointCloud2> pass;     //创建滤波器对象
  pass.setInputCloud(cloud_in);            //设置待滤波的点云
  pass.setFilterFieldName ("x");           //设置在x轴方向上进行滤波
//   pass.setNegative(false);                 //false:保留当前范围内数据;true:取反;
  pass.setFilterLimits (3., 10.);         //设置滤波范围为min~max,在范围之外的点会被剪除
  pass.filter (cloud_out);                //存储

 

 3.半径滤波

https://pointclouds.org/documentation/classpcl_1_1_radius_outlier_removal_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html

 void setRadiusSearch(double radius)

Set the sphere radius that is to be used for determining the k-nearest neighbors for filtering. 
Parameters
    radius	the sphere radius that is to contain all k-nearest neighbors 

setMinNeighborsInRadius(int min_pts)

Set the minimum number of neighbors that a point needs to have in the given search radius in order to be considered an inlier (i.e., valid).

Parameters
    min_pts	the minimum number of neighbors 

测试

  pcl::RadiusOutlierRemoval<pcl::PCLPointCloud2> outrem;  // 创建滤波器    
  outrem.setInputCloud(cloud_in);                 //设置输入点云
  /****搜索半径设为radius,在此半径内点必须要有至少num个邻居时,此点才会被保留***/
  outrem.setRadiusSearch(0.5);              //设置在radius半径的范围内找邻近点
  outrem.setMinNeighborsInRadius(100);        //设置查询点的邻近点集数小于num的删除
  outrem.filter(cloud_out);           //执行条件滤波,存储结果到cloud_filter

 4.统计滤波器

https://pointclouds.org/documentation/classpcl_1_1_statistical_outlier_removal_3_01pcl_1_1_p_c_l_point_cloud2_01_4.html

 void setMeanK(int nr_k)

Set the number of points (k) to use for mean distance estimation.

Parameters
    nr_k	the number of points to use for mean distance estimation 

setStddevMulThresh(0.5)

 测试

 pcl::StatisticalOutlierRemoval<pcl::PCLPointCloud2> Static;   //创建滤波器对象
  Static.setInputCloud(cloud_in);                      //设置待滤波的点云
  Static.setMeanK(50);                          //设置在进行统计时考虑查询点临近点数
  Static.setStddevMulThresh(0.5);          //设置判断是否为离群点的阈值
  Static.filter(cloud_out);                //存储

  • 0
    点赞
  • 2
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

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

余额充值