Noise.cpp
Go to the documentation of this file.
00001 /******************************************************************************/
00002 /* randn()
00003  * 
00004  * Normally (Gaussian) distributed random numbers, using the Box-Muller 
00005  * transformation.  This transformation takes two uniformly distributed deviates
00006  * within the unit circle, and transforms them into two independently 
00007  * distributed normal deviates.  Utilizes the internal rand() function; this can
00008  * easily be changed to use a better and faster RNG.
00009  * 
00010  * The parameters passed to the function are the mean and standard deviation of 
00011  * the desired distribution.  The default values used, when no arguments are 
00012  * passed, are 0 and 1 - the standard normal distribution.
00013  * 
00014  * 
00015  * Two functions are provided:
00016  * 
00017  * The first uses the so-called polar version of the B-M transformation, using
00018  * multiple calls to a uniform RNG to ensure the initial deviates are within the
00019  * unit circle.  This avoids making any costly trigonometric function calls.
00020  * 
00021  * The second makes only a single set of calls to the RNG, and calculates a 
00022  * position within the unit circle with two trigonometric function calls.
00023  * 
00024  * The polar version is generally superior in terms of speed; however, on some
00025  * systems, the optimization of the math libraries may result in better 
00026  * performance of the second.  Try it out on the target system to see which
00027  * works best for you.  On my test machine (Athlon 3800+), the non-trig version
00028  * runs at about 3x10^6 calls/s; while the trig version runs at about
00029  * 1.8x10^6 calls/s (-O2 optimization).
00030  * 
00031  * 
00032  * Example calls:
00033  * randn_notrig();      //returns normal deviate with mean=0.0, std. deviation=1.0
00034  * randn_notrig(5.2,3.0);       //returns deviate with mean=5.2, std. deviation=3.0
00035  * 
00036  * 
00037  * Dependencies - requires <cmath> for the sqrt(), sin(), and cos() calls, and a
00038  * #defined value for PI.
00039  */
00040  
00041 
00042 #include <blort/Tracker/Noise.h>
00043 #include <blort/TomGine/tgMathlib.h>
00044  
00045 using namespace Tracking;
00046 
00047 /******************************************************************************/
00048 //      "Polar" version without trigonometric calls
00049 float Noise::randn_notrig(float mu, float sigma) {
00050         static bool deviateAvailable=false;     //      flag
00051         static float storedDeviate;                     //      deviate from previous calculation
00052         
00053         //      If no deviate has been stored, the polar Box-Muller transformation is 
00054         //      performed, producing two independent normally-distributed random
00055         //      deviates.  One is stored for the next round, and one is returned.
00056         if (!deviateAvailable) {
00057                 float polar, rsquared, var1, var2;
00058                 
00059                 //      choose pairs of uniformly distributed deviates, discarding those 
00060                 //      that don't fall within the unit circle
00061                 do {
00062                         var1=2.0f*( float(rand())/RAND_MAX ) - 1.0f;
00063                         var2=2.0f*( float(rand())/RAND_MAX ) - 1.0f;
00064                         rsquared=var1*var1+var2*var2;
00065                 } while ( rsquared>=1.0f || rsquared == 0.0f);
00066                 
00067                 //      calculate polar tranformation for each deviate
00068                 polar=sqrt(-2.0f*log(rsquared)/rsquared);
00069                 
00070                 //      store first deviate and set flag
00071                 storedDeviate=var1*polar;
00072                 deviateAvailable=true;
00073                 
00074                 //      return second deviate
00075                 return var2*polar*sigma + mu;
00076         }
00077         
00078         //      If a deviate is available from a previous call to this function, it is
00079         //      returned, and the flag is set to false.
00080         else {
00081                 deviateAvailable=false;
00082                 return storedDeviate*sigma + mu;
00083         }
00084 }
00085 
00086 
00087 /******************************************************************************/
00088 //      Standard version with trigonometric calls
00089 
00090 float Noise::randn_trig(float mu, float sigma) {
00091         static bool deviateAvailable=false;     //      flag
00092         static float storedDeviate;                     //      deviate from previous calculation
00093         
00094         //      If no deviate has been stored, the standard Box-Muller transformation is 
00095         //      performed, producing two independent normally-distributed random
00096         //      deviates.  One is stored for the next round, and one is returned.
00097         if (!deviateAvailable) {
00098                 float dist, angle;              
00099                 //      choose a pair of uniformly distributed deviates, one for the
00100                 //      distance and one for the angle, and perform transformations
00101                 dist=sqrt( -2.0f * log(float(rand()) / RAND_MAX) );
00102                 angle=2.0f * PI * (float(rand()) / RAND_MAX);
00103                 
00104                 //      calculate and store first deviate and set flag
00105                 storedDeviate=dist*cos(angle);
00106                 deviateAvailable=true;
00107                 
00108                 //      calcaulate return second deviate
00109                 return dist * sin(angle) * sigma + mu;
00110         }
00111         
00112         //      If a deviate is available from a previous call to this function, it is
00113         //      returned, and the flag is set to false.
00114         else {
00115                 deviateAvailable=false;
00116                 return storedDeviate*sigma + mu;
00117         }
00118 }
00119 
00120 /******************************************************************************/
00121 //      "Polar" version without trigonometric calls
00122 double Noise::randn_notrig(double mu, double sigma) {
00123         static bool deviateAvailable=false;     //      flag
00124         static double storedDeviate;                    //      deviate from previous calculation
00125         
00126         //      If no deviate has been stored, the polar Box-Muller transformation is 
00127         //      performed, producing two independent normally-distributed random
00128         //      deviates.  One is stored for the next round, and one is returned.
00129         if (!deviateAvailable) {
00130                 double polar, rsquared, var1, var2;     
00131                 //      choose pairs of uniformly distributed deviates, discarding those 
00132                 //      that don't fall within the unit circle
00133                 do {
00134                         var1=2.0*( double(rand())/RAND_MAX ) - 1.0;
00135                         var2=2.0*( double(rand())/RAND_MAX ) - 1.0;
00136                         rsquared=var1*var1+var2*var2;
00137                 } while ( rsquared>=1.0 || rsquared == 0.0);
00138                 
00139                 //      calculate polar tranformation for each deviate
00140                 polar=sqrt(-2.0*log(rsquared)/rsquared);
00141                 
00142                 //      store first deviate and set flag
00143                 storedDeviate=var1*polar;
00144                 deviateAvailable=true;
00145                 
00146                 //      return second deviate
00147                 return var2*polar*sigma + mu;
00148         }
00149         
00150         //      If a deviate is available from a previous call to this function, it is
00151         //      returned, and the flag is set to false.
00152         else {
00153                 deviateAvailable=false;
00154                 return storedDeviate*sigma + mu;
00155         }
00156 }
00157 
00158 
00159 /******************************************************************************/
00160 //      Standard version with trigonometric calls
00161 
00162 double Noise::randn_trig(double mu, double sigma) {
00163         static bool deviateAvailable=false;     //      flag
00164         static double storedDeviate;                    //      deviate from previous calculation
00165         
00166         //      If no deviate has been stored, the standard Box-Muller transformation is 
00167         //      performed, producing two independent normally-distributed random
00168         //      deviates.  One is stored for the next round, and one is returned.
00169         if (!deviateAvailable) {
00170                         double dist, angle;
00171                 //      choose a pair of uniformly distributed deviates, one for the
00172                 //      distance and one for the angle, and perform transformations
00173                 dist=sqrt( -2.0 * log(double(rand()) / RAND_MAX) );
00174                 angle=2.0 * PI * (double(rand()) / RAND_MAX);
00175                 
00176                 //      calculate and store first deviate and set flag
00177                 storedDeviate=dist*cos(angle);
00178                 deviateAvailable=true;
00179                 
00180                 //      calcaulate return second deviate
00181                 return dist * sin(angle) * sigma + mu;
00182         }
00183         
00184         //      If a deviate is available from a previous call to this function, it is
00185         //      returned, and the flag is set to false.
00186         else {
00187                 deviateAvailable=false;
00188                 return storedDeviate*sigma + mu;
00189         }
00190 }
00191 


blort
Author(s): Michael Zillich, Thomas Mörwald, Johann Prankl, Andreas Richtsfeld, Bence Magyar (ROS version)
autogenerated on Thu Jan 2 2014 11:38:25