Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #ifndef PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_
00039 #define PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_
00040
00041 #include <pcl/filters/normal_space.h>
00042
00043 #include <vector>
00044 #include <list>
00045
00047 template<typename PointT, typename NormalT> void
00048 pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (PointCloud &output)
00049 {
00050
00051
00052 if (sample_ >= input_->size ())
00053 {
00054 output = *input_;
00055 return;
00056 }
00057
00058
00059 output.points.resize (sample_);
00060 output.width = sample_;
00061 output.height = 1;
00062
00063
00064 unsigned int n_bins = binsx_ * binsy_ * binsz_;
00065
00066
00067 std::vector< std::list <int> > normals_hg;
00068 normals_hg.reserve (n_bins);
00069 for (unsigned int i = 0; i < n_bins; i++)
00070 normals_hg.push_back (std::list<int> ());
00071
00072 for (unsigned int i = 0; i < input_normals_->points.size (); i++)
00073 {
00074 unsigned int bin_number = findBin (input_normals_->points[i].normal, n_bins);
00075 normals_hg[bin_number].push_back (i);
00076 }
00077
00078
00079
00080 std::vector< std::vector <std::list<int>::iterator> > random_access (normals_hg.size ());
00081 for (unsigned int i = 0; i < normals_hg.size (); i++)
00082 {
00083 random_access.push_back (std::vector< std::list<int>::iterator> ());
00084 random_access[i].resize (normals_hg[i].size ());
00085
00086 unsigned int j=0;
00087 for (std::list<int>::iterator itr = normals_hg[i].begin (); itr != normals_hg[i].end (); itr++, j++)
00088 {
00089 random_access[i][j] = itr;
00090 }
00091 }
00092 unsigned int* start_index = new unsigned int[normals_hg.size ()];
00093 start_index[0] = 0;
00094 unsigned int prev_index = start_index[0];
00095 for (unsigned int i = 1; i < normals_hg.size (); i++)
00096 {
00097 start_index[i] = prev_index + static_cast<unsigned int> (normals_hg[i-1].size ());
00098 prev_index = start_index[i];
00099 }
00100
00101
00102 boost::dynamic_bitset<> is_sampled_flag (input_normals_->points.size ());
00103
00104 boost::dynamic_bitset<> bin_empty_flag (normals_hg.size ());
00105 unsigned int i = 0;
00106 while (i < sample_)
00107 {
00108
00109 for (unsigned int j = 0; j < normals_hg.size (); j++)
00110 {
00111 unsigned int M = static_cast<unsigned int> (normals_hg[j].size ());
00112 if (M == 0 || bin_empty_flag.test (j))
00113 {
00114 continue;
00115 }
00116
00117 unsigned int pos = 0;
00118 unsigned int random_index = 0;
00119
00120 do
00121 {
00122 random_index = std::rand () % M;
00123 pos = start_index[j] + random_index;
00124 } while (is_sampled_flag.test (pos));
00125
00126 is_sampled_flag.flip (start_index[j] + random_index);
00127
00128
00129 if (isEntireBinSampled (is_sampled_flag, start_index[j], static_cast<unsigned int> (normals_hg[j].size ())))
00130 {
00131 bin_empty_flag.flip (j);
00132 }
00133
00134 unsigned int index = *(random_access[j][random_index]);
00135 output.points[i] = input_->points[index];
00136 i++;
00137 if (i == sample_)
00138 {
00139 break;
00140 }
00141 }
00142 }
00143 delete[] start_index;
00144 }
00145
00147 template<typename PointT, typename NormalT> bool
00148 pcl::NormalSpaceSampling<PointT, NormalT>::isEntireBinSampled (boost::dynamic_bitset<> &array, unsigned int start_index, unsigned int length)
00149 {
00150 bool status = true;
00151 for (unsigned int i = start_index; i < start_index + length; i++)
00152 {
00153 status = status & array.test (i);
00154 }
00155 return status;
00156 }
00157
00159 template<typename PointT, typename NormalT> unsigned int
00160 pcl::NormalSpaceSampling<PointT, NormalT>::findBin (float *normal, unsigned int)
00161 {
00162 unsigned int bin_number = 0;
00163
00164 unsigned int t[3] = {0,0,0};
00165
00166
00167 float dcos = 0.0;
00168 float bin_size = 0.0;
00169
00170 float max_cos = 1.0;
00171 float min_cos = -1.0;
00172
00173 dcos = cosf (normal[0]);
00174 bin_size = (max_cos - min_cos) / static_cast<float> (binsx_);
00175
00176
00177 unsigned int k = 0;
00178 for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++)
00179 {
00180 if (dcos >= i && dcos <= (i+bin_size))
00181 {
00182 break;
00183 }
00184 }
00185 t[0] = k;
00186
00187 dcos = cosf (normal[1]);
00188 bin_size = (max_cos - min_cos) / static_cast<float> (binsy_);
00189
00190
00191 k = 0;
00192 for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++)
00193 {
00194 if (dcos >= i && dcos <= (i+bin_size))
00195 {
00196 break;
00197 }
00198 }
00199 t[1] = k;
00200
00201 dcos = cosf (normal[2]);
00202 bin_size = (max_cos - min_cos) / static_cast<float> (binsz_);
00203
00204
00205 k = 0;
00206 for (float i = min_cos; (i + bin_size) < (max_cos - bin_size); i += bin_size , k++)
00207 {
00208 if (dcos >= i && dcos <= (i+bin_size))
00209 {
00210 break;
00211 }
00212 }
00213 t[2] = k;
00214
00215 bin_number = t[0] * (binsy_*binsz_) + t[1] * binsz_ + t[2];
00216 return bin_number;
00217 }
00218
00220 template<typename PointT, typename NormalT>
00221 void
00222 pcl::NormalSpaceSampling<PointT, NormalT>::applyFilter (std::vector<int> &indices)
00223 {
00224
00225
00226 if (sample_ >= input_->width * input_->height)
00227 {
00228 indices = *indices_;
00229 return;
00230 }
00231
00232
00233 indices.resize (sample_);
00234
00235
00236 unsigned int n_bins = binsx_ * binsy_ * binsz_;
00237
00238
00239 std::vector< std::list <int> > normals_hg;
00240 normals_hg.reserve (n_bins);
00241 for (unsigned int i = 0; i < n_bins; i++)
00242 normals_hg.push_back (std::list<int> ());
00243
00244 for (unsigned int i=0; i < input_normals_->points.size (); i++)
00245 {
00246 unsigned int bin_number = findBin (input_normals_->points[i].normal, n_bins);
00247 normals_hg[bin_number].push_back (i);
00248 }
00249
00250
00251
00252 std::vector< std::vector <std::list<int>::iterator> > random_access (normals_hg.size ());
00253 for (unsigned int i = 0; i < normals_hg.size (); i++)
00254 {
00255 random_access.push_back (std::vector<std::list<int>::iterator> ());
00256 random_access[i].resize (normals_hg[i].size ());
00257
00258 unsigned int j = 0;
00259 for (std::list<int>::iterator itr = normals_hg[i].begin (); itr != normals_hg[i].end (); itr++, j++)
00260 {
00261 random_access[i][j] = itr;
00262 }
00263 }
00264 unsigned int* start_index = new unsigned int[normals_hg.size ()];
00265 start_index[0] = 0;
00266 unsigned int prev_index = start_index[0];
00267 for (unsigned int i = 1; i < normals_hg.size (); i++)
00268 {
00269 start_index[i] = prev_index + static_cast<unsigned int> (normals_hg[i-1].size ());
00270 prev_index = start_index[i];
00271 }
00272
00273
00274 boost::dynamic_bitset<> is_sampled_flag (input_normals_->points.size ());
00275
00276 boost::dynamic_bitset<> bin_empty_flag (normals_hg.size ());
00277 unsigned int i=0;
00278 while (i < sample_)
00279 {
00280
00281 for (unsigned int j = 0; j < normals_hg.size (); j++)
00282 {
00283 unsigned int M = static_cast<unsigned int> (normals_hg[j].size ());
00284 if (M==0 || bin_empty_flag.test (j))
00285 {
00286 continue;
00287 }
00288
00289 unsigned int pos = 0;
00290 unsigned int random_index = 0;
00291
00292
00293 do
00294 {
00295 random_index = std::rand () % M;
00296 pos = start_index[j] + random_index;
00297 } while (is_sampled_flag.test (pos));
00298
00299 is_sampled_flag.flip (start_index[j] + random_index);
00300
00301
00302 if (isEntireBinSampled (is_sampled_flag, start_index[j], static_cast<unsigned int> (normals_hg[j].size ())))
00303 {
00304 bin_empty_flag.flip (j);
00305 }
00306
00307 unsigned int index = *(random_access[j][random_index]);
00308 indices[i] = index;
00309 i++;
00310 if (i == sample_)
00311 {
00312 break;
00313 }
00314 }
00315 }
00316 delete[] start_index;
00317 }
00318
00319 #define PCL_INSTANTIATE_NormalSpaceSampling(T,NT) template class PCL_EXPORTS pcl::NormalSpaceSampling<T,NT>;
00320
00321 #endif // PCL_FILTERS_IMPL_NORMAL_SPACE_SAMPLE_H_