Point Cloud Library (PCL)  1.8.1-dev
 All Classes Namespaces Functions Variables Typedefs Enumerations Enumerator Friends Groups Pages
filter.hpp
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2009, 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_FILTER_H_
39 #define PCL_FILTERS_IMPL_FILTER_H_
40 
41 #include <pcl/pcl_macros.h>
42 #include <pcl/filters/filter.h>
43 
44 //////////////////////////////////////////////////////////////////////////
45 template <typename PointT> void
47  pcl::PointCloud<PointT> &cloud_out,
48  std::vector<int> &index)
49 {
50  // If the clouds are not the same, prepare the output
51  if (&cloud_in != &cloud_out)
52  {
53  cloud_out.header = cloud_in.header;
54  cloud_out.points.resize (cloud_in.points.size ());
55  cloud_out.sensor_origin_ = cloud_in.sensor_origin_;
56  cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_;
57  }
58  // Reserve enough space for the indices
59  index.resize (cloud_in.points.size ());
60  size_t j = 0;
61 
62  // If the data is dense, we don't need to check for NaN
63  if (cloud_in.is_dense)
64  {
65  // Simply copy the data
66  cloud_out = cloud_in;
67  for (j = 0; j < cloud_out.points.size (); ++j)
68  index[j] = static_cast<int>(j);
69  }
70  else
71  {
72  for (size_t i = 0; i < cloud_in.points.size (); ++i)
73  {
74  if (!pcl_isfinite (cloud_in.points[i].x) ||
75  !pcl_isfinite (cloud_in.points[i].y) ||
76  !pcl_isfinite (cloud_in.points[i].z))
77  continue;
78  cloud_out.points[j] = cloud_in.points[i];
79  index[j] = static_cast<int>(i);
80  j++;
81  }
82  if (j != cloud_in.points.size ())
83  {
84  // Resize to the correct size
85  cloud_out.points.resize (j);
86  index.resize (j);
87  }
88 
89  cloud_out.height = 1;
90  cloud_out.width = static_cast<uint32_t>(j);
91 
92  // Removing bad points => dense (note: 'dense' doesn't mean 'organized')
93  cloud_out.is_dense = true;
94  }
95 }
96 
97 //////////////////////////////////////////////////////////////////////////
98 template <typename PointT> void
100  pcl::PointCloud<PointT> &cloud_out,
101  std::vector<int> &index)
102 {
103  // If the clouds are not the same, prepare the output
104  if (&cloud_in != &cloud_out)
105  {
106  cloud_out.header = cloud_in.header;
107  cloud_out.points.resize (cloud_in.points.size ());
108  cloud_out.sensor_origin_ = cloud_in.sensor_origin_;
109  cloud_out.sensor_orientation_ = cloud_in.sensor_orientation_;
110  }
111  // Reserve enough space for the indices
112  index.resize (cloud_in.points.size ());
113  size_t j = 0;
114 
115  for (size_t i = 0; i < cloud_in.points.size (); ++i)
116  {
117  if (!pcl_isfinite (cloud_in.points[i].normal_x) ||
118  !pcl_isfinite (cloud_in.points[i].normal_y) ||
119  !pcl_isfinite (cloud_in.points[i].normal_z))
120  continue;
121  cloud_out.points[j] = cloud_in.points[i];
122  index[j] = static_cast<int>(i);
123  j++;
124  }
125  if (j != cloud_in.points.size ())
126  {
127  // Resize to the correct size
128  cloud_out.points.resize (j);
129  index.resize (j);
130  }
131 
132  cloud_out.height = 1;
133  cloud_out.width = static_cast<uint32_t>(j);
134 }
135 
136 
137 #define PCL_INSTANTIATE_removeNaNFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNFromPointCloud<T>(const pcl::PointCloud<T>&, pcl::PointCloud<T>&, std::vector<int>&);
138 #define PCL_INSTANTIATE_removeNaNNormalsFromPointCloud(T) template PCL_EXPORTS void pcl::removeNaNNormalsFromPointCloud<T>(const pcl::PointCloud<T>&, pcl::PointCloud<T>&, std::vector<int>&);
139 
140 #endif // PCL_FILTERS_IMPL_FILTER_H_
141 
void removeNaNNormalsFromPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, std::vector< int > &index)
Removes points that have their normals invalid (i.e., equal to NaN)
Definition: filter.hpp:99
Eigen::Vector4f sensor_origin_
Sensor acquisition pose (origin/translation).
Definition: point_cloud.h:421
void removeNaNFromPointCloud(const pcl::PointCloud< PointT > &cloud_in, pcl::PointCloud< PointT > &cloud_out, std::vector< int > &index)
Removes points with x, y, or z equal to NaN.
Definition: filter.hpp:46
uint32_t width
The point cloud width (if organized as an image-structure).
Definition: point_cloud.h:413
pcl::PCLHeader header
The point cloud header.
Definition: point_cloud.h:407
Eigen::Quaternionf sensor_orientation_
Sensor acquisition pose (rotation).
Definition: point_cloud.h:423
std::vector< PointT, Eigen::aligned_allocator< PointT > > points
The point data.
Definition: point_cloud.h:410
bool is_dense
True if no points are invalid (e.g., have NaN or Inf values in any of their floating point fields)...
Definition: point_cloud.h:418
uint32_t height
The point cloud height (if organized as an image-structure).
Definition: point_cloud.h:415