Point Cloud Library (PCL)  1.9.1-dev
project_inliers.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2010, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the copyright holder(s) nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *
34  * $Id$
35  *
36  */
37 
38 #ifndef PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
39 #define PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
40 
41 #include <pcl/filters/project_inliers.h>
42 
43 //////////////////////////////////////////////////////////////////////////////////////////////
44 template <typename PointT> void
46 {
47  if (indices_->empty ())
48  {
49  PCL_WARN ("[pcl::%s::applyFilter] No indices given or empty indices!\n", getClassName ().c_str ());
50  output.width = output.height = 0;
51  output.points.clear ();
52  return;
53  }
54 
55  //Eigen::Map<Eigen::VectorXf, Eigen::Aligned> model_coefficients (&model_->values[0], model_->values.size ());
56  // More expensive than a map but safer (32bit architectures seem to complain)
57  Eigen::VectorXf model_coefficients (model_->values.size ());
58  for (size_t i = 0; i < model_->values.size (); ++i)
59  model_coefficients[i] = model_->values[i];
60 
61  // Initialize the Sample Consensus model and set its parameters
62  if (!initSACModel (model_type_))
63  {
64  PCL_ERROR ("[pcl::%s::applyFilter] Error initializing the SAC model!\n", getClassName ().c_str ());
65  output.width = output.height = 0;
66  output.points.clear ();
67  return;
68  }
69  if (copy_all_data_)
70  sacmodel_->projectPoints (*indices_, model_coefficients, output, true);
71  else
72  sacmodel_->projectPoints (*indices_, model_coefficients, output, false);
73 }
74 
75 //////////////////////////////////////////////////////////////////////////////////////////////
76 template <typename PointT> bool
78 {
79  // Build the model
80  switch (model_type)
81  {
82  case SACMODEL_PLANE:
83  {
84  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PLANE\n", getClassName ().c_str ());
85  sacmodel_.reset (new SampleConsensusModelPlane<PointT> (input_));
86  break;
87  }
88  case SACMODEL_LINE:
89  {
90  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_LINE\n", getClassName ().c_str ());
91  sacmodel_.reset (new SampleConsensusModelLine<PointT> (input_));
92  break;
93  }
94  case SACMODEL_CIRCLE2D:
95  {
96  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_CIRCLE2D\n", getClassName ().c_str ());
97  sacmodel_.reset (new SampleConsensusModelCircle2D<PointT> (input_));
98  break;
99  }
100  case SACMODEL_SPHERE:
101  {
102  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_SPHERE\n", getClassName ().c_str ());
103  sacmodel_.reset (new SampleConsensusModelSphere<PointT> (input_));
104  break;
105  }
107  {
108  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PARALLEL_LINE\n", getClassName ().c_str ());
109  sacmodel_.reset (new SampleConsensusModelParallelLine<PointT> (input_));
110  break;
111  }
113  {
114  //PCL_DEBUG ("[pcl::%s::initSACModel] Using a model of type: SACMODEL_PERPENDICULAR_PLANE\n", getClassName ().c_str ());
115  sacmodel_.reset (new SampleConsensusModelPerpendicularPlane<PointT> (input_));
116  break;
117  }
118  case SACMODEL_CYLINDER:
119  {
120  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CYLINDER\n", getClassName ().c_str ());
121  sacmodel_.reset (new SampleConsensusModelCylinder<PointT, pcl::Normal> (input_));
122  break;
123  }
125  {
126  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PLANE\n", getClassName ().c_str ());
127  sacmodel_.reset (new SampleConsensusModelNormalPlane<PointT, pcl::Normal> (input_));
128  break;
129  }
130  case SACMODEL_CONE:
131  {
132  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_CONE\n", getClassName ().c_str ());
133  sacmodel_.reset (new SampleConsensusModelCone<PointT, pcl::Normal> (input_));
134  break;
135  }
137  {
138  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_SPHERE\n", getClassName ().c_str ());
139  sacmodel_.reset (new SampleConsensusModelNormalSphere<PointT, pcl::Normal> (input_));
140  break;
141  }
143  {
144  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_NORMAL_PARALLEL_PLANE\n", getClassName ().c_str ());
146  break;
147  }
149  {
150  //PCL_DEBUG ("[pcl::%s::segment] Using a model of type: SACMODEL_PARALLEL_PLANE\n", getClassName ().c_str ());
151  sacmodel_.reset (new SampleConsensusModelParallelPlane<PointT> (input_));
152  break;
153  }
154  default:
155  {
156  PCL_ERROR ("[pcl::%s::initSACModel] No valid model given!\n", getClassName ().c_str ());
157  return (false);
158  }
159  }
160  return (true);
161 }
162 
163 #define PCL_INSTANTIATE_ProjectInliers(T) template class PCL_EXPORTS pcl::ProjectInliers<T>;
164 
165 #endif // PCL_FILTERS_IMPL_PROJECT_INLIERS_H_
166 
SampleConsensusModelCylinder defines a model for 3D cylinder segmentation.
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:423
SampleConsensusModelLine defines a model for 3D line segmentation.
SampleConsensusModelParallelPlane defines a model for 3D plane segmentation using additional angular ...
ProjectInliers uses a model and a set of inlier indices from a PointCloud to project them into a sepa...
SampleConsensusModelNormalSphere defines a model for 3D sphere segmentation using additional surface ...
uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:428
SampleConsensusModelCircle2D defines a model for 2D circle segmentation on the X-Y plane...
uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:426
SampleConsensusModelParallelLine defines a model for 3D line segmentation using additional angular co...
SampleConsensusModelCone defines a model for 3D cone segmentation.
SampleConsensusModelNormalPlane defines a model for 3D plane segmentation using additional surface no...
PointCloud represents the base class in PCL for storing collections of 3D points. ...
void applyFilter(PointCloud &output) override
Project point indices into a separate PointCloud.
SampleConsensusModelPlane defines a model for 3D plane segmentation.
SampleConsensusModelSphere defines a model for 3D sphere segmentation.
SampleConsensusModelNormalParallelPlane defines a model for 3D plane segmentation using additional su...
SampleConsensusModelPerpendicularPlane defines a model for 3D plane segmentation using additional ang...