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
00039
00040 #ifndef PCL_COMMON_RANDOM_H_
00041 #define PCL_COMMON_RANDOM_H_
00042
00043 #ifdef __GNUC__
00044 #pragma GCC system_header
00045 #endif
00046
00047 #include <boost/random/uniform_real.hpp>
00048 #include <boost/random/uniform_int.hpp>
00049 #include <boost/random/variate_generator.hpp>
00050 #include <boost/random/normal_distribution.hpp>
00051 #include <boost/random/mersenne_twister.hpp>
00052 #include <pcl/pcl_macros.h>
00053
00054 namespace pcl
00055 {
00056 namespace common
00057 {
00059 template <typename T> struct uniform_distribution;
00061 template<>
00062 struct uniform_distribution<int>
00063 {
00064 typedef boost::uniform_int<int> type;
00065 };
00067 template<>
00068 struct uniform_distribution<float>
00069 {
00070 typedef boost::uniform_real<float> type;
00071 };
00073 template<typename T>
00074 struct normal_distribution
00075 {
00076 typedef boost::normal_distribution<T> type;
00077 };
00078
00085 template<typename T>
00086 class UniformGenerator
00087 {
00088 public:
00089 struct Parameters
00090 {
00091 Parameters (T _min = 0, T _max = 1, pcl::uint32_t _seed = 1)
00092 : min (_min)
00093 , max (_max)
00094 , seed (_seed)
00095 {}
00096
00097 T min;
00098 T max;
00099 pcl::uint32_t seed;
00100 };
00101
00107 UniformGenerator(T min = 0, T max = 1, pcl::uint32_t seed = -1);
00108
00112 UniformGenerator(const Parameters& paramters);
00113
00117 void
00118 setSeed (pcl::uint32_t seed);
00119
00125 void
00126 setParameters (T min, T max, pcl::uint32_t seed = -1);
00127
00131 void
00132 setParameters (const Parameters& parameters);
00133
00135 const Parameters&
00136 getParameters () { return (parameters_); }
00137
00139 inline T
00140 run () { return (generator_ ()); }
00141
00142 private:
00143 typedef boost::mt19937 EngineType;
00144 typedef typename uniform_distribution<T>::type DistributionType;
00146 Parameters parameters_;
00148 DistributionType distribution_;
00150 EngineType rng_;
00152 boost::variate_generator<EngineType&, DistributionType> generator_;
00153 };
00154
00160 template<typename T>
00161 class NormalGenerator
00162 {
00163 public:
00164 struct Parameters
00165 {
00166 Parameters (T _mean = 0, T _sigma = 1, pcl::uint32_t _seed = 1)
00167 : mean (_mean)
00168 , sigma (_sigma)
00169 , seed (_seed)
00170 {}
00171
00172 T mean;
00173 T sigma;
00174 pcl::uint32_t seed;
00175 };
00176
00182 NormalGenerator(T mean = 0, T sigma = 1, pcl::uint32_t seed = -1);
00183
00187 NormalGenerator(const Parameters& parameters);
00188
00192 void
00193 setSeed (pcl::uint32_t seed);
00194
00200 void
00201 setParameters (T mean, T sigma, pcl::uint32_t seed = -1);
00202
00206 void
00207 setParameters (const Parameters& parameters);
00208
00210 const Parameters&
00211 getParameters () { return (parameters_); }
00212
00214 inline T
00215 run () { return (generator_ ()); }
00216
00217 typedef boost::mt19937 EngineType;
00218 typedef typename normal_distribution<T>::type DistributionType;
00220 Parameters parameters_;
00222 DistributionType distribution_;
00224 EngineType rng_;
00226 boost::variate_generator<EngineType&, DistributionType > generator_;
00227 };
00228 }
00229 }
00230
00231 #include <pcl/common/impl/random.hpp>
00232
00233 #endif