RandomSample applies a random sampling with uniform probability. More...
#include <random_sample.h>
Public Member Functions | |
unsigned int | getSample () |
Get the value of the internal sample parameter. | |
unsigned int | getSeed () |
Get the value of the internal seed parameter. | |
RandomSample () | |
Empty constructor. | |
void | setSample (unsigned int sample) |
Set number of indices to be sampled. | |
void | setSeed (unsigned int seed) |
Set seed of random function. | |
Protected Member Functions | |
void | applyFilter (PointCloud2 &output) |
Sample of point indices into a separate PointCloud. | |
void | applyFilter (std::vector< int > &indices) |
Sample of point indices. | |
float | unifRand () |
Return a random number fast using a LCG (Linear Congruential Generator) algorithm. See http://software.intel.com/en-us/articles/fast-random-number-generator-on-the-intel-pentiumr-4-processor/ for more information. | |
Protected Attributes | |
unsigned int | sample_ |
Number of indices that will be returned. | |
unsigned int | seed_ |
Random number seed. | |
Private Types | |
typedef sensor_msgs::PointCloud2 | PointCloud2 |
typedef PointCloud2::ConstPtr | PointCloud2ConstPtr |
typedef PointCloud2::Ptr | PointCloud2Ptr |
RandomSample applies a random sampling with uniform probability.
Definition at line 143 of file random_sample.h.
typedef sensor_msgs::PointCloud2 pcl::RandomSample< sensor_msgs::PointCloud2 >::PointCloud2 [private] |
Reimplemented from pcl::FilterIndices< sensor_msgs::PointCloud2 >.
Definition at line 148 of file random_sample.h.
typedef PointCloud2::ConstPtr pcl::RandomSample< sensor_msgs::PointCloud2 >::PointCloud2ConstPtr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 150 of file random_sample.h.
typedef PointCloud2::Ptr pcl::RandomSample< sensor_msgs::PointCloud2 >::PointCloud2Ptr [private] |
Reimplemented from pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 149 of file random_sample.h.
pcl::RandomSample< sensor_msgs::PointCloud2 >::RandomSample | ( | ) | [inline] |
Empty constructor.
Definition at line 154 of file random_sample.h.
void pcl::RandomSample< sensor_msgs::PointCloud2 >::applyFilter | ( | PointCloud2 & | output | ) | [protected, virtual] |
Sample of point indices into a separate PointCloud.
output | the resultant point cloud |
Implements pcl::Filter< sensor_msgs::PointCloud2 >.
Definition at line 45 of file random_sample.cpp.
void pcl::RandomSample< sensor_msgs::PointCloud2 >::applyFilter | ( | std::vector< int > & | indices | ) | [protected, virtual] |
Sample of point indices.
indices | the resultant point cloud indices |
Implements pcl::FilterIndices< sensor_msgs::PointCloud2 >.
Definition at line 101 of file random_sample.cpp.
unsigned int pcl::RandomSample< sensor_msgs::PointCloud2 >::getSample | ( | ) | [inline] |
Get the value of the internal sample parameter.
Definition at line 171 of file random_sample.h.
unsigned int pcl::RandomSample< sensor_msgs::PointCloud2 >::getSeed | ( | ) | [inline] |
Get the value of the internal seed parameter.
Definition at line 188 of file random_sample.h.
void pcl::RandomSample< sensor_msgs::PointCloud2 >::setSample | ( | unsigned int | sample | ) | [inline] |
Set number of indices to be sampled.
sample |
Definition at line 163 of file random_sample.h.
void pcl::RandomSample< sensor_msgs::PointCloud2 >::setSeed | ( | unsigned int | seed | ) | [inline] |
float pcl::RandomSample< sensor_msgs::PointCloud2 >::unifRand | ( | ) | [inline, protected] |
Return a random number fast using a LCG (Linear Congruential Generator) algorithm. See http://software.intel.com/en-us/articles/fast-random-number-generator-on-the-intel-pentiumr-4-processor/ for more information.
Definition at line 216 of file random_sample.h.
unsigned int pcl::RandomSample< sensor_msgs::PointCloud2 >::sample_ [protected] |
Number of indices that will be returned.
Definition at line 196 of file random_sample.h.
unsigned int pcl::RandomSample< sensor_msgs::PointCloud2 >::seed_ [protected] |
Random number seed.
Definition at line 198 of file random_sample.h.