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 #include <pcl/impl/instantiate.hpp>
00039 #include <pcl/point_types.h>
00040 #include <pcl/filters/random_sample.h>
00041 #include <pcl/filters/impl/random_sample.hpp>
00042
00044 void
00045 pcl::RandomSample<sensor_msgs::PointCloud2>::applyFilter (PointCloud2 &output)
00046 {
00047 unsigned N = input_->width * input_->height;
00048
00049
00050 if (sample_ >= N)
00051 {
00052 output = *input_;
00053 }
00054 else
00055 {
00056
00057 output.data.resize (sample_ * input_->point_step);
00058
00059
00060 output.fields = input_->fields;
00061 output.is_bigendian = input_->is_bigendian;
00062 output.row_step = input_->row_step;
00063 output.point_step = input_->point_step;
00064 output.height = 1;
00065
00066
00067 std::srand (seed_);
00068
00069 unsigned top = N - sample_;
00070 unsigned i = 0;
00071 unsigned index = 0;
00072
00073
00074 for (size_t n = sample_; n >= 2; n--)
00075 {
00076 float V = unifRand ();
00077 unsigned S = 0;
00078 float quot = float (top) / float (N);
00079 while (quot > V)
00080 {
00081 S++;
00082 top--;
00083 N--;
00084 quot = quot * float (top) / float (N);
00085 }
00086 index += S;
00087 memcpy (&output.data[i++ * output.point_step], &input_->data[index++ * output.point_step], output.point_step);
00088 N--;
00089 }
00090
00091 index += N * static_cast<unsigned> (unifRand ());
00092 memcpy (&output.data[i++ * output.point_step], &input_->data[index++ * output.point_step], output.point_step);
00093
00094 output.width = sample_;
00095 output.row_step = output.point_step * output.width;
00096 }
00097 }
00098
00100 void
00101 pcl::RandomSample<sensor_msgs::PointCloud2>::applyFilter (std::vector<int> &indices)
00102 {
00103 unsigned N = input_->width * input_->height;
00104
00105
00106 if (sample_ >= N)
00107 {
00108 indices = *indices_;
00109 }
00110 else
00111 {
00112
00113 indices.resize (sample_);
00114
00115
00116 std::srand (seed_);
00117
00118 unsigned top = N - sample_;
00119 unsigned i = 0;
00120 unsigned index = 0;
00121
00122
00123 for (size_t n = sample_; n >= 2; n--)
00124 {
00125 float V = unifRand ();
00126 unsigned S = 0;
00127 float quot = float (top) / float (N);
00128 while (quot > V)
00129 {
00130 S++;
00131 top--;
00132 N--;
00133 quot = quot * float (top) / float (N);
00134 }
00135 index += S;
00136 indices[i++] = (*indices_)[index++];
00137 N--;
00138 }
00139
00140 index += N * static_cast<unsigned> (unifRand ());
00141 indices[i++] = (*indices_)[index++];
00142 }
00143 }
00144
00145 PCL_INSTANTIATE(RandomSample, PCL_POINT_TYPES)