random_sample.hpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage, Inc. nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *
00034  * $Id: random_sample.hpp 5026 2012-03-12 02:51:44Z rusu $
00035  *
00036  */
00037 
00038 #ifndef PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_
00039 #define PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_
00040 
00041 #include <pcl/filters/random_sample.h>
00042 
00043 
00045 template<typename PointT> void
00046 pcl::RandomSample<PointT>::applyFilter (PointCloud &output)
00047 {
00048   unsigned N = static_cast<unsigned> (input_->size ());
00049   float one_over_N = 1.0f / float (N);
00050 
00051   // If sample size is 0 or if the sample size is greater then input cloud size
00052   //   then return entire copy of cloud
00053   if (sample_ >= N)
00054   {
00055     output = *input_;
00056   }
00057   else
00058   {
00059     // Resize output cloud to sample size
00060     output.points.resize (sample_);
00061     output.width = sample_;
00062     output.height = 1;
00063 
00064     // Set random seed so derived indices are the same each time the filter runs
00065     std::srand (seed_);
00066 
00067     unsigned top = N - sample_;
00068     unsigned i = 0;
00069     unsigned index = 0;
00070 
00071     // Algorithm A
00072     for (size_t n = sample_; n >= 2; n--)
00073     {
00074       unsigned int V = unifRand ();
00075       unsigned S = 0;
00076       float quot = float (top) * one_over_N;
00077       while (quot > V)
00078       {
00079         S++;
00080         top--;
00081         N--;
00082         quot = quot * float (top) * one_over_N;
00083       }
00084       index += S;
00085       output.points[i++] = input_->points[index++];
00086       N--;
00087     }
00088 
00089     index += N * static_cast<unsigned> (unifRand ());
00090     output.points[i++] = input_->points[index++];
00091   }
00092 }
00093 
00095 template<typename PointT>
00096 void
00097 pcl::RandomSample<PointT>::applyFilter (std::vector<int> &indices)
00098 {
00099   unsigned N = static_cast<unsigned> (input_->size ());
00100   float one_over_N = 1.0f / float (N);
00101 
00102   // If sample size is 0 or if the sample size is greater then input cloud size
00103   //   then return all indices
00104   if (sample_ >= N)
00105   {
00106     indices = *indices_;
00107   }
00108   else
00109   {
00110     // Resize output indices to sample size
00111     indices.resize (sample_);
00112 
00113     // Set random seed so derived indices are the same each time the filter runs
00114     std::srand (seed_);
00115 
00116     // Algorithm A
00117     unsigned top = N - sample_;
00118     unsigned i = 0;
00119     unsigned index = 0;
00120 
00121     for (size_t n = sample_; n >= 2; n--)
00122     {
00123       unsigned int V = unifRand ();
00124       unsigned S = 0;
00125       float quot = float (top) * one_over_N;
00126       while (quot > V)
00127       {
00128         S++;
00129         top--;
00130         N--;
00131         quot = quot * float (top) * one_over_N;
00132       }
00133       index += S;
00134       indices[i++] = (*indices_)[index++];
00135       N--;
00136     }
00137 
00138     index += N * static_cast<unsigned> (unifRand ());
00139     indices[i++] = (*indices_)[index++];
00140   }
00141 }
00142 
00143 #define PCL_INSTANTIATE_RandomSample(T) template class PCL_EXPORTS pcl::RandomSample<T>;
00144 
00145 #endif    // PCL_FILTERS_IMPL_RANDOM_SAMPLE_H_


pcl
Author(s): Open Perception
autogenerated on Mon Oct 6 2014 03:17:36