Point Cloud Library (PCL)  1.9.1-dev
random_sample.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: extract_indices.hpp 1897 2011-07-26 20:35:49Z rusu $
35  *
36  */
37 
38 #ifndef PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_
39 #define PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_
40 
41 #include <pcl/filters/random_sample.h>
42 #include <pcl/common/io.h>
43 #include <pcl/point_traits.h>
44 
45 
46 ///////////////////////////////////////////////////////////////////////////////
47 template<typename PointT> void
49 {
50  std::vector<int> indices;
51  if (keep_organized_)
52  {
53  bool temp = extract_removed_indices_;
54  extract_removed_indices_ = true;
55  applyFilter (indices);
56  extract_removed_indices_ = temp;
57  copyPointCloud (*input_, output);
58  // Get X, Y, Z fields
59  const auto fields = pcl::getFields<PointT> ();
60  std::vector<std::size_t> offsets;
61  for (const auto &field : fields)
62  {
63  if (field.name == "x" ||
64  field.name == "y" ||
65  field.name == "z")
66  offsets.push_back (field.offset);
67  }
68  // For every "removed" point, set the x,y,z fields to user_filter_value_
69  const static float user_filter_value = user_filter_value_;
70  for (std::size_t rii = 0; rii < removed_indices_->size (); ++rii)
71  {
72  std::uint8_t* pt_data = reinterpret_cast<std::uint8_t*> (&output[(*removed_indices_)[rii]]);
73  for (const unsigned long &offset : offsets)
74  {
75  memcpy (pt_data + offset, &user_filter_value, sizeof (float));
76  }
77  if (!std::isfinite (user_filter_value_))
78  output.is_dense = false;
79  }
80  }
81  else
82  {
83  output.is_dense = true;
84  applyFilter (indices);
85  copyPointCloud (*input_, indices, output);
86  }
87 }
88 
89 ///////////////////////////////////////////////////////////////////////////////
90 template<typename PointT>
91 void
92 pcl::RandomSample<PointT>::applyFilter (std::vector<int> &indices)
93 {
94  std::size_t N = indices_->size ();
95  std::size_t sample_size = negative_ ? N - sample_ : sample_;
96  // If sample size is 0 or if the sample size is greater then input cloud size
97  // then return all indices
98  if (sample_size >= N)
99  {
100  indices = *indices_;
101  removed_indices_->clear ();
102  }
103  else
104  {
105  // Resize output indices to sample size
106  indices.resize (sample_size);
107  if (extract_removed_indices_)
108  removed_indices_->resize (N - sample_size);
109 
110  // Set random seed so derived indices are the same each time the filter runs
111  std::srand (seed_);
112 
113  // Algorithm S
114  std::size_t i = 0;
115  std::size_t index = 0;
116  std::vector<bool> added;
117  if (extract_removed_indices_)
118  added.resize (indices_->size (), false);
119  std::size_t n = sample_size;
120  while (n > 0)
121  {
122  // Step 1: [Generate U.] Generate a random variate U that is uniformly distributed between 0 and 1.
123  const float U = unifRand ();
124  // Step 2: [Test.] If N * U > n, go to Step 4.
125  if ((N * U) <= n)
126  {
127  // Step 3: [Select.] Select the next record in the file for the sample, and set n : = n - 1.
128  if (extract_removed_indices_)
129  added[index] = true;
130  indices[i++] = (*indices_)[index];
131  --n;
132  }
133  // Step 4: [Don't select.] Skip over the next record (do not include it in the sample).
134  // Set N : = N - 1.
135  --N;
136  ++index;
137  // If n > 0, then return to Step 1; otherwise, the sample is complete and the algorithm terminates.
138  }
139 
140  // Now populate removed_indices_ appropriately
141  if (extract_removed_indices_)
142  {
143  std::size_t ri = 0;
144  for (std::size_t i = 0; i < added.size (); i++)
145  {
146  if (!added[i])
147  {
148  (*removed_indices_)[ri++] = (*indices_)[i];
149  }
150  }
151  }
152  }
153 }
154 
155 #define PCL_INSTANTIATE_RandomSample(T) template class PCL_EXPORTS pcl::RandomSample<T>;
156 
157 #endif // PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_
PCL_EXPORTS void copyPointCloud(const pcl::PCLPointCloud2 &cloud_in, const std::vector< int > &indices, pcl::PCLPointCloud2 &cloud_out)
Extract the indices of a given point cloud as a new point cloud.
void applyFilter(PointCloud &output) override
Sample of point indices into a separate PointCloud.
PointCloud represents the base class in PCL for storing collections of 3D points. ...
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:402