从一个点云中提取索引

附课本代码:

#include <iostream>
#include <pcl/ModelCoefficients.h>
#include <pcl/io/pcd_io.h>
#include <pcl/point_types.h>
#include <pcl/sample_consensus/method_types.h>
#include <pcl/sample_consensus/model_types.h>
#include <pcl/segmentation/sac_segmentation.h>
#include <pcl/filters/voxel_grid.h>
#include <pcl/filters/extract_indices.h>
int
main (int argc, char** argv)
{
  sensor_msgs::PointCloud2::Ptr cloud_blob (new sensor_msgs::PointCloud2), cloud_filtered_blob (new sensor_msgs::PointCloud2);
  pcl::PointCloud<pcl::PointXYZ>::Ptr cloud_filtered (new pcl::PointCloud<pcl::PointXYZ>), cloud_p (new pcl::PointCloud<pcl::PointXYZ>), cloud_f (new pcl::PointCloud<pcl::PointXYZ>);
  // 填入点云数据
  pcl::PCDReader reader;
  reader.read ("table_scene_lms400.pcd", *cloud_blob);
  std::cerr << "PointCloud before filtering: " << cloud_blob->width * cloud_blob->height << " data points." << std::endl;
  // 创建滤波器对象:使用叶大小为1cm的下采样
  pcl::VoxelGrid<sensor_msgs::PointCloud2> sor;
  sor.setInputCloud (cloud_blob);
  sor.setLeafSize (0.01f, 0.01f, 0.01f);
  sor.filter (*cloud_filtered_blob);
  // 转化为模板点云
  pcl::fromROSMsg (*cloud_filtered_blob, *cloud_filtered);
  std::cerr << "PointCloud after filtering: " << cloud_filtered->width * cloud_filtered->height << " data points." << std::endl;
  // 将下采样后的数据存入磁盘
  pcl::PCDWriter writer;
  writer.write<pcl::PointXYZ> ("table_scene_lms400_downsampled.pcd", *cloud_filtered, false);

  pcl::ModelCoefficients::Ptr coefficients (new pcl::ModelCoefficients ());
  pcl::PointIndices::Ptr inliers (new pcl::PointIndices ());
  // 创建分割对象
  pcl::SACSegmentation<pcl::PointXYZ> seg;
  // 可选
  seg.setOptimizeCoefficients (true);
  // 必选
  seg.setModelType (pcl::SACMODEL_PLANE);
  seg.setMethodType (pcl::SAC_RANSAC);
  seg.setMaxIterations (1000);
  seg.setDistanceThreshold (0.01);


  // 创建滤波器对象
  pcl::ExtractIndices<pcl::PointXYZ> extract;
  int i = 0, nr_points = (int) cloud_filtered->points.size ();
  // 当还有30%原始点云数据时
  while (cloud_filtered->points.size () > 0.3 * nr_points)
  {
    // 从余下的点云中分割最大平面组成部分
    seg.setInputCloud (cloud_filtered);
    seg.segment (*inliers, *coefficients);
    if (inliers->indices.size () == 0)
    {
      std::cerr << "Could not estimate a planar model for the given dataset." << std::endl;
      break;
    }
    // 分离内层
    extract.setInputCloud (cloud_filtered);
    extract.setIndices (inliers);
    extract.setNegative (false);
    extract.filter (*cloud_p);
    std::cerr << "PointCloud representing the planar component: " << cloud_p->width * cloud_p->height << " data points." << std::endl;
    std::stringstream ss;
    ss << "table_scene_lms400_plane_" << i << ".pcd";
    writer.write<pcl::PointXYZ> (ss.str (), *cloud_p, false);
    // 创建滤波器对象
    extract.setNegative (true);
    extract.filter (*cloud_f);
    cloud_filtered.swap (cloud_f);
    i++;
  }
  return (0);
}



相关对象函数说明:

1、pcl::PointIndices

This is the complete list of members for pcl::PointIndices, including all inherited members.

ConstPtr typedefpcl::PointIndices 
headerpcl::PointIndices 
indicespcl::PointIndices 
PointIndices()pcl::PointIndices 
Ptr typedefpcl::PointIndices

2、SACSegmentation对象

(1)

void pcl::SACSegmentation<PointT >::setOptimizeCoefficients(bool optimize)

Set to true if a coefficient refinement is required.//设置对估计的模型参数进行优化处理

Parameters:
[in]optimizetrue for enabling model coefficient refinement, false otherwise  
(2)
void pcl::SACSegmentation<PointT >::setModelType(int model)

The type of model to use (user given parameter).

Parameters:
[in]modelthe model type
(3)
void pcl::SACSegmentation<PointT >::setMethodType(int method)

The type of sample consensus method to use (user given parameter).

Parameters:
[in]methodthe method type 
    * SAC_RANSAC - RANdom SAmple Consensus
    * SAC_LMEDS - Least Median of Squares
    * SAC_MSAC - M-Estimator SAmple Consensus
    * SAC_RRANSAC - Randomized RANSAC
    * SAC_RMSAC - Randomized MSAC
    * SAC_MLESAC - Maximum LikeLihood Estimation SAmple Consensus
    * SAC_PROSAC - PROgressive SAmple Consensus

(4)
 
 
void pcl::SACSegmentation< PointT >::setMaxIterations(int max_iterations)

Set the maximum number of iterations before giving up. 

Parameters:
[in]max_iterationsthe maximum number of iterations the sample consensus method will run  
(5)
void pcl::SACSegmentation< PointT >::setDistanceThreshold(double threshold)

Distance to the model threshold (user given parameter). //设置判断是否为模型内点的距离阈值

Parameters:
[in]thresholdthe distance threshold to use 

(6)

virtual void pcl::PCLBase< PointT >::setInputCloud(const PointCloudConstPtrcloud)

Provide a pointer to the input dataset.

Parameters:
cloudthe const boost shared pointer to a PointCloud message  
(7)
void pcl::SACSegmentation< PointT >::segment(PointIndicesinliers,
  ModelCoefficientsmodel_coefficients 
 )

Base method for segmentation of a model in a PointCloud given by <setInputCloud (), setIndices ()>

Parameters:
[in]inliersthe resultant point indices that support the model found (inliers)
[out]model_coefficientsthe resultant model coefficients 
3、ExtractIndices滤波器对象 extracts a set of indices from a point cloud. (1)
void pcl::PCLBase< sensor_msgs::PointCloud2 >::setIndices(const PointIndicesConstPtrindices)

Provide a pointer to the vector of indices that represents the input data.

Parameters:
indicesa pointer to the vector of indices that represents the input data.  

(2)

void pcl::PCLBase< sensor_msgs::PointCloud2 >::setInputCloud(const PointCloud2ConstPtrcloud) 

Provide a pointer to the input dataset.

Parameters:

cloudthe const boost shared pointer to a PointCloud message  

(3)

void pcl::FilterIndices< sensor_msgs::PointCloud2 >::setNegative(bool negative)

Set whether the regular conditions for points filtering should apply, or the inverted conditions.

Parameters:
[in]negativefalse = normal filter behavior (default), true = inverted behavior.  
(4)

virtual void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter(PointCloud2output)

Calls the filtering method and returns the filtered dataset in output. 

void pcl::FilterIndices< sensor_msgs::PointCloud2 >::filter(std::vector< int > & indices) 

Calls the filtering method and returns the filtered point cloud indices. 

   

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

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值