extract_indices_patch.h
Go to the documentation of this file.
1 /*
2  * Software License Agreement (BSD License)
3  *
4  * Point Cloud Library (PCL) - www.pointclouds.org
5  * Copyright (c) 2010-2012, Willow Garage, Inc.
6  * Copyright (c) 2012-, Open Perception, Inc.
7  *
8  * All rights reserved.
9  *
10  * Redistribution and use in source and binary forms, with or without
11  * modification, are permitted provided that the following conditions
12  * are met:
13  *
14  * * Redistributions of source code must retain the above copyright
15  * notice, this list of conditions and the following disclaimer.
16  * * Redistributions in binary form must reproduce the above
17  * copyright notice, this list of conditions and the following
18  * disclaimer in the documentation and/or other materials provided
19  * with the distribution.
20  * * Neither the name of the copyright holder(s) nor the names of its
21  * contributors may be used to endorse or promote products derived
22  * from this software without specific prior written permission.
23  *
24  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
25  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
26  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
27  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
28  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
29  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
30  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
31  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
32  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
33  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
34  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35  * POSSIBILITY OF SUCH DAMAGE.
36  *
37  * $Id$
38  *
39  */
40 
41 #include <pcl/filters/impl/extract_indices.hpp>
42 
44 void
45 pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (PCLPointCloud2 &output)
46 {
47  if (keep_organized_)
48  {
49  output = *input_;
50  if (negative_)
51  {
52  // Prepare the output and copy the data
53  for (size_t i = 0; i < indices_->size (); ++i)
54  for (size_t j = 0; j < output.fields.size(); ++j)
55  memcpy (&output.data[(*indices_)[i] * output.point_step + output.fields[j].offset],
56  &user_filter_value_, sizeof(float));
57  }
58  else
59  {
60  // Prepare a vector holding all indices
61  std::vector<int> all_indices (input_->width * input_->height);
62  for (int i = 0; i < static_cast<int>(all_indices.size ()); ++i)
63  all_indices[i] = i;
64 
65  std::vector<int> indices = *indices_;
66  std::sort (indices.begin (), indices.end ());
67 
68  // Get the diference
69  std::vector<int> remaining_indices;
70  set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (),
71  inserter (remaining_indices, remaining_indices.begin ()));
72 
73  // Prepare the output and copy the data
74  for (size_t i = 0; i < remaining_indices.size (); ++i)
75  for (size_t j = 0; j < output.fields.size(); ++j)
76  memcpy (&output.data[remaining_indices[i] * output.point_step + output.fields[j].offset],
77  &user_filter_value_, sizeof(float));
78  }
79  if (!pcl_isfinite (user_filter_value_))
80  output.is_dense = false;
81  return;
82  }
83  if (indices_->empty () || (input_->width * input_->height == 0))
84  {
85  output.width = output.height = 0;
86  output.data.clear ();
87  // If negative, copy all the data
88  if (negative_)
89  output = *input_;
90  return;
91  }
92  if (indices_->size () == (input_->width * input_->height))
93  {
94  // If negative, then return an empty cloud
95  if (negative_)
96  {
97  output.width = output.height = 0;
98  output.data.clear ();
99  }
100  // else, we need to return all points
101  else
102  output = *input_;
103  return;
104  }
105 
106  // Copy the common fields (header and fields should have already been copied)
107  output.is_bigendian = input_->is_bigendian;
108  output.point_step = input_->point_step;
109  output.height = 1;
110  // TODO: check the output cloud and assign is_dense based on whether the points are valid or not
111  output.is_dense = false;
112 
113  if (negative_)
114  {
115  // Prepare a vector holding all indices
116  std::vector<int> all_indices (input_->width * input_->height);
117  for (int i = 0; i < static_cast<int>(all_indices.size ()); ++i)
118  all_indices[i] = i;
119 
120  std::vector<int> indices = *indices_;
121  std::sort (indices.begin (), indices.end ());
122 
123  // Get the diference
124  std::vector<int> remaining_indices;
125  set_difference (all_indices.begin (), all_indices.end (), indices.begin (), indices.end (),
126  inserter (remaining_indices, remaining_indices.begin ()));
127 
128  // Prepare the output and copy the data
129  output.width = static_cast<uint32_t> (remaining_indices.size ());
130  output.data.resize (remaining_indices.size () * output.point_step);
131  for (size_t i = 0; i < remaining_indices.size (); ++i)
132  memcpy (&output.data[i * output.point_step], &input_->data[remaining_indices[i] * output.point_step], output.point_step);
133  }
134  else
135  {
136  // Prepare the output and copy the data
137  output.width = static_cast<uint32_t> (indices_->size ());
138  output.data.resize (indices_->size () * output.point_step);
139  for (size_t i = 0; i < indices_->size (); ++i)
140  memcpy (&output.data[i * output.point_step], &input_->data[(*indices_)[i] * output.point_step], output.point_step);
141  }
142  output.row_step = output.point_step * output.width;
143 }
144 
146 void
147 pcl::ExtractIndices<pcl::PCLPointCloud2>::applyFilter (std::vector<int> &indices)
148 {
149  if (negative_)
150  {
151  // If the subset is the full set
152  if (indices_->size () == (input_->width * input_->height))
153  {
154  // Empty set copy
155  indices.clear ();
156  return;
157  }
158 
159  // Set up the full indices set
160  std::vector<int> indices_fullset (input_->width * input_->height);
161  for (int p_it = 0; p_it < static_cast<int> (indices_fullset.size ()); ++p_it)
162  indices_fullset[p_it] = p_it;
163 
164  // If the subset is the empty set
165  if (indices_->empty () || (input_->width * input_->height == 0))
166  {
167  // Full set copy
168  indices = indices_fullset;
169  return;
170  }
171 
172  // If the subset is a proper subset
173  // Set up the subset input indices
174  std::vector<int> indices_subset = *indices_;
175  std::sort (indices_subset.begin (), indices_subset.end ());
176 
177  // Get the difference
178  set_difference (indices_fullset.begin (), indices_fullset.end (), indices_subset.begin (), indices_subset.end (), inserter (indices, indices.begin ()));
179  }
180  else
181  indices = *indices_;
182 }
183 
184 #ifndef PCL_NO_PRECOMPILE
185 #include <pcl/impl/instantiate.hpp>
186 #include <pcl/point_types.h>
187 
188 #ifdef PCL_ONLY_CORE_POINT_TYPES
189  PCL_INSTANTIATE(ExtractIndices, (pcl::PointXYZ)(pcl::PointXYZI)(pcl::PointXYZRGB)(pcl::PointXYZRGBA)(pcl::Normal)(pcl::PointXYZRGBNormal))
190 #else
191  PCL_INSTANTIATE(ExtractIndices, PCL_POINT_TYPES)
192 #endif
193 
194 #endif // PCL_NO_PRECOMPILE
float


jsk_pcl_ros
Author(s): Yohei Kakiuchi
autogenerated on Mon May 3 2021 03:03:46