Main MRPT website > C++ reference
MRPT logo
utils.h
Go to the documentation of this file.
00001 /* +---------------------------------------------------------------------------+
00002    |          The Mobile Robot Programming Toolkit (MRPT) C++ library          |
00003    |                                                                           |
00004    |                       http://www.mrpt.org/                                |
00005    |                                                                           |
00006    |   Copyright (C) 2005-2011  University of Malaga                           |
00007    |                                                                           |
00008    |    This software was written by the Machine Perception and Intelligent    |
00009    |      Robotics Lab, University of Malaga (Spain).                          |
00010    |    Contact: Jose-Luis Blanco  <jlblanco@ctima.uma.es>                     |
00011    |                                                                           |
00012    |  This file is part of the MRPT project.                                   |
00013    |                                                                           |
00014    |     MRPT is free software: you can redistribute it and/or modify          |
00015    |     it under the terms of the GNU General Public License as published by  |
00016    |     the Free Software Foundation, either version 3 of the License, or     |
00017    |     (at your option) any later version.                                   |
00018    |                                                                           |
00019    |   MRPT is distributed in the hope that it will be useful,                 |
00020    |     but WITHOUT ANY WARRANTY; without even the implied warranty of        |
00021    |     MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the         |
00022    |     GNU General Public License for more details.                          |
00023    |                                                                           |
00024    |     You should have received a copy of the GNU General Public License     |
00025    |     along with MRPT.  If not, see <http://www.gnu.org/licenses/>.         |
00026    |                                                                           |
00027    +---------------------------------------------------------------------------+ */
00028 #ifndef  MRPT_MATH_H
00029 #define  MRPT_MATH_H
00030 
00031 #include <mrpt/utils/utils_defs.h>
00032 #include <mrpt/math/CMatrixTemplateNumeric.h>
00033 #include <mrpt/math/CMatrixFixedNumeric.h>
00034 #include <mrpt/math/CHistogram.h>
00035 
00036 #include <mrpt/math/ops_vectors.h>
00037 #include <mrpt/math/ops_matrices.h>
00038 
00039 #include <numeric>
00040 #include <cmath>
00041 
00042 /*---------------------------------------------------------------
00043                 Namespace
00044   ---------------------------------------------------------------*/
00045 namespace mrpt
00046 {
00047         /** This base provides a set of functions for maths stuff. \ingroup mrpt_base_grp
00048          */
00049         namespace math
00050         {
00051             using namespace mrpt::utils;
00052 
00053                 /** \addtogroup container_ops_grp
00054                   * @{ */
00055 
00056                 /** Loads one row of a text file as a numerical std::vector.
00057                   * \return false on EOF or invalid format.
00058                   * The body of the function is implemented in MATH.cpp
00059                         */
00060                 bool BASE_IMPEXP loadVector( utils::CFileStream &f, std::vector<int> &d);
00061 
00062                 /** Loads one row of a text file as a numerical std::vector.
00063                   * \return false on EOF or invalid format.
00064                   * The body of the function is implemented in MATH.cpp
00065                         */
00066                 bool BASE_IMPEXP loadVector( utils::CFileStream &f, std::vector<double> &d);
00067 
00068 
00069         /** Returns true if the number is NaN. */
00070         bool BASE_IMPEXP  isNaN(float  f) MRPT_NO_THROWS;
00071 
00072         /** Returns true if the number is NaN. */
00073         bool  BASE_IMPEXP isNaN(double f) MRPT_NO_THROWS;
00074 
00075         /** Returns true if the number is non infinity. */
00076         bool BASE_IMPEXP  isFinite(float f) MRPT_NO_THROWS;
00077 
00078         /** Returns true if the number is non infinity.  */
00079         bool  BASE_IMPEXP isFinite(double f) MRPT_NO_THROWS;
00080 
00081         void BASE_IMPEXP medianFilter( const std::vector<double> &inV, std::vector<double> &outV, const int &winSize, const int &numberOfSigmas = 2 );
00082 
00083 #ifdef HAVE_LONG_DOUBLE
00084                 /** Returns true if the number is NaN. */
00085         bool  BASE_IMPEXP isNaN(long double f) MRPT_NO_THROWS;
00086 
00087         /** Returns true if the number is non infinity. */
00088         bool BASE_IMPEXP  isFinite(long double f) MRPT_NO_THROWS;
00089 #endif
00090 
00091                 /** Generates an equidistant sequence of numbers given the first one, the last one and the desired number of points.
00092                   \sa sequence */
00093                 template<typename T,typename VECTOR>
00094                 void linspace(T first,T last, size_t count, VECTOR &out_vector)
00095                 {
00096                         if (count<2)
00097                         {
00098                                 out_vector.assign(count,last);
00099                                 return;
00100                         }
00101                         else
00102                         {
00103                                 out_vector.resize(count);
00104                                 const T incr = (last-first)/T(count-1);
00105                                 T c = first;
00106                                 for (size_t i=0;i<count;i++,c+=incr)
00107                                         out_vector[i] = static_cast<typename VECTOR::value_type>(c);
00108                         }
00109                 }
00110 
00111                 /** Generates an equidistant sequence of numbers given the first one, the last one and the desired number of points.
00112                   \sa sequence */
00113                 template<class T>
00114                 inline Eigen::Matrix<T,Eigen::Dynamic,1> linspace(T first,T last, size_t count)
00115                 {
00116                         Eigen::Matrix<T,Eigen::Dynamic,1> ret;
00117                         mrpt::math::linspace(first,last,count,ret);
00118                         return ret;
00119                 }
00120 
00121                 /** Generates a sequence of values [first,first+STEP,first+2*STEP,...]   \sa linspace, sequenceStdVec */
00122                 template<class T,T STEP>
00123                 inline Eigen::Matrix<T,Eigen::Dynamic,1> sequence(T first,size_t length)
00124                 {
00125                         Eigen::Matrix<T,Eigen::Dynamic,1> ret(length);
00126                         if (!length) return ret;
00127                         size_t i=0;
00128                         while (length--) { ret[i++]=first; first+=STEP; }
00129                         return ret;
00130                 }
00131 
00132                 /** Generates a sequence of values [first,first+STEP,first+2*STEP,...]   \sa linspace, sequence */
00133                 template<class T,T STEP>
00134                 inline std::vector<T> sequenceStdVec(T first,size_t length)
00135                 {
00136                         std::vector<T> ret(length);
00137                         if (!length) return ret;
00138                         size_t i=0;
00139                         while (length--) { ret[i++]=first; first+=STEP; }
00140                         return ret;
00141                 }
00142 
00143                 /** Generates a vector of all ones of the given length. */
00144                 template<class T> inline Eigen::Matrix<T,Eigen::Dynamic,1> ones(size_t count)
00145                 {
00146                         Eigen::Matrix<T,Eigen::Dynamic,1> v(count);
00147                         v.setOnes();
00148                         return v;
00149                 }
00150 
00151                 /** Generates a vector of all zeros of the given length. */
00152                 template<class T> inline Eigen::Matrix<T,Eigen::Dynamic,1> zeros(size_t count)
00153                 {
00154                         Eigen::Matrix<T,Eigen::Dynamic,1> v(count);
00155                         v.setZero();
00156                         return v;
00157                 }
00158 
00159 
00160                 /** Modifies the given angle to translate it into the [0,2pi[ range.
00161                   * \note Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
00162                   * \sa wrapToPi, wrapTo2Pi, unwrap2PiSequence
00163                   */
00164                 template <class T>
00165                 inline void wrapTo2PiInPlace(T &a)
00166                 {
00167                         bool was_neg = a<0;
00168                         a = fmod(a, static_cast<T>(M_2PI) );
00169                         if (was_neg) a+=static_cast<T>(M_2PI);
00170                 }
00171 
00172                 /** Modifies the given angle to translate it into the [0,2pi[ range.
00173                   * \note Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
00174                   * \sa wrapToPi, wrapTo2Pi, unwrap2PiSequence
00175                   */
00176                 template <class T>
00177                 inline T wrapTo2Pi(T a)
00178                 {
00179                         wrapTo2PiInPlace(a);
00180                         return a;
00181                 }
00182 
00183                 /** Modifies the given angle to translate it into the ]-pi,pi] range.
00184                   * \note Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
00185                   * \sa wrapTo2Pi, wrapToPiInPlace, unwrap2PiSequence
00186                   */
00187                 template <class T>
00188                 inline T wrapToPi(T a)
00189                 {
00190                         return wrapTo2Pi( a + static_cast<T>(M_PI) )-static_cast<T>(M_PI);
00191                 }
00192 
00193                 /** Modifies the given angle to translate it into the ]-pi,pi] range.
00194                   * \note Take care of not instancing this template for integer numbers, since it only works for float, double and long double.
00195                   * \sa wrapToPi,wrapTo2Pi, unwrap2PiSequence
00196                   */
00197                 template <class T>
00198                 inline void wrapToPiInPlace(T &a)
00199                 {
00200                         a = wrapToPi(a);
00201                 }
00202 
00203 
00204                 /** Normalize a vector, such as its norm is the unity.
00205                   *  If the vector has a null norm, the output is a null vector.
00206                   */
00207                 template<class VEC1,class VEC2>
00208                 void normalize(const VEC1 &v, VEC2 &out_v)
00209                 {
00210                         typename VEC1::value_type total=0;
00211                         const size_t N = v.size();
00212                         for (size_t i=0;i<N;i++)
00213                                 total += square(v[i]);
00214                         total = std::sqrt(total);
00215                         if (total)
00216                         {
00217                                 out_v = v * (1.0/total);
00218                         }
00219                         else out_v.assign(v.size(),0);
00220                 }
00221 
00222                 /** Computes covariances and mean of any vector of containers, given optional weights for the different samples.
00223                   * \param elements Any kind of vector of vectors/arrays, eg. std::vector<vector_double>, with all the input samples, each sample in a "row".
00224                   * \param covariances Output estimated covariance; it can be a fixed/dynamic matrix or a matrixview.
00225                   * \param means Output estimated mean; it can be vector_double/CArrayDouble, etc...
00226                   * \param weights_mean If !=NULL, it must point to a vector of size()==number of elements, with normalized weights to take into account for the mean.
00227                   * \param weights_cov If !=NULL, it must point to a vector of size()==number of elements, with normalized weights to take into account for the covariance.
00228                   * \param elem_do_wrap2pi If !=NULL; it must point to an array of "bool" of size()==dimension of each element, stating if it's needed to do a wrap to [-pi,pi] to each dimension.
00229                   * \sa This method is used in mrpt::math::unscented_transform_gaussian
00230                   * \ingroup stats_grp
00231                   */
00232                 template<class VECTOR_OF_VECTORS, class MATRIXLIKE,class VECTORLIKE,class VECTORLIKE2,class VECTORLIKE3>
00233                 inline void covariancesAndMeanWeighted(   // Done inline to speed-up the special case expanded in covariancesAndMean() below.
00234                         const VECTOR_OF_VECTORS &elements,
00235                         MATRIXLIKE &covariances,
00236                         VECTORLIKE &means,
00237                         const VECTORLIKE2 *weights_mean,
00238                         const VECTORLIKE3 *weights_cov,
00239                         const bool *elem_do_wrap2pi = NULL
00240                         )
00241                 {
00242                         ASSERTMSG_(elements.size()!=0,"No samples provided, so there is no way to deduce the output size.")
00243                         typedef typename VECTORLIKE::value_type T;
00244                         const size_t DIM = elements[0].size();
00245                         means.resize(DIM);
00246                         covariances.setSize(DIM,DIM);
00247                         const size_t nElms=elements.size();
00248                         const T NORM=1.0/nElms;
00249                         if (weights_mean) { ASSERTDEB_(size_t(weights_mean->size())==size_t(nElms)) }
00250                         // The mean goes first:
00251                         for (size_t i=0;i<DIM;i++)
00252                         {
00253                                 T  accum = 0;
00254                                 if (!elem_do_wrap2pi || !elem_do_wrap2pi[i])
00255                                 {       // i'th dimension is a "normal", real number:
00256                                         if (weights_mean)
00257                                         {
00258                                                 for (size_t j=0;j<nElms;j++)
00259                                                         accum+= (*weights_mean)[j] * elements[j][i];
00260                                         }
00261                                         else
00262                                         {
00263                                                 for (size_t j=0;j<nElms;j++) accum+=elements[j][i];
00264                                                 accum*=NORM;
00265                                         }
00266                                 }
00267                                 else
00268                                 {       // i'th dimension is a circle in [-pi,pi]: we need a little trick here:
00269                                         double accum_L=0,accum_R=0;
00270                                         double Waccum_L=0,Waccum_R=0;
00271                                         for (size_t j=0;j<nElms;j++)
00272                                         {
00273                                                 double ang = elements[j][i];
00274                                                 const double w   = weights_mean!=NULL ? (*weights_mean)[j] : NORM;
00275                                                 if (fabs( ang )>0.5*M_PI)
00276                                                 {       // LEFT HALF: 0,2pi
00277                                                         if (ang<0) ang = (M_2PI + ang);
00278                                                         accum_L  += ang * w;
00279                                                         Waccum_L += w;
00280                                                 }
00281                                                 else
00282                                                 {       // RIGHT HALF: -pi,pi
00283                                                         accum_R += ang * w;
00284                                                         Waccum_R += w;
00285                                                 }
00286                                         }
00287                                         if (Waccum_L>0) accum_L /= Waccum_L;  // [0,2pi]
00288                                         if (Waccum_R>0) accum_R /= Waccum_R;  // [-pi,pi]
00289                                         if (accum_L>M_PI) accum_L -= M_2PI;     // Left side to [-pi,pi] again:
00290                                         accum = (accum_L* Waccum_L + accum_R * Waccum_R );      // The overall result:
00291                                 }
00292                                 means[i]=accum;
00293                         }
00294                         // Now the covariance:
00295                         for (size_t i=0;i<DIM;i++)
00296                                 for (size_t j=0;j<=i;j++)       // Only 1/2 of the matrix
00297                                 {
00298                                         typename MATRIXLIKE::value_type elem=0;
00299                                         if (weights_cov)
00300                                         {
00301                                                 ASSERTDEB_(size_t(weights_cov->size())==size_t(nElms))
00302                                                 for (size_t k=0;k<nElms;k++)
00303                                                 {
00304                                                         const T Ai = (elements[k][i]-means[i]);
00305                                                         const T Aj = (elements[k][j]-means[j]);
00306                                                         if (!elem_do_wrap2pi || !elem_do_wrap2pi[i])
00307                                                                         elem+= (*weights_cov)[k] * Ai * Aj;
00308                                                         else    elem+= (*weights_cov)[k] * mrpt::math::wrapToPi(Ai) * mrpt::math::wrapToPi(Aj);
00309                                                 }
00310                                         }
00311                                         else
00312                                         {
00313                                                 for (size_t k=0;k<nElms;k++)
00314                                                 {
00315                                                         const T Ai = (elements[k][i]-means[i]);
00316                                                         const T Aj = (elements[k][j]-means[j]);
00317                                                         if (!elem_do_wrap2pi || !elem_do_wrap2pi[i])
00318                                                                         elem+= Ai * Aj;
00319                                                         else    elem+= mrpt::math::wrapToPi(Ai) * mrpt::math::wrapToPi(Aj);
00320                                                 }
00321                                                 elem*=NORM;
00322                                         }
00323                                         covariances.get_unsafe(i,j) = elem;
00324                                         if (i!=j) covariances.get_unsafe(j,i)=elem;
00325                                 }
00326                 }
00327 
00328                 /** Computes covariances and mean of any vector of containers.
00329                   * \param elements Any kind of vector of vectors/arrays, eg. std::vector<vector_double>, with all the input samples, each sample in a "row".
00330                   * \param covariances Output estimated covariance; it can be a fixed/dynamic matrix or a matrixview.
00331                   * \param means Output estimated mean; it can be vector_double/CArrayDouble, etc...
00332                   * \param elem_do_wrap2pi If !=NULL; it must point to an array of "bool" of size()==dimension of each element, stating if it's needed to do a wrap to [-pi,pi] to each dimension.
00333                   * \ingroup stats_grp
00334                   */
00335                 template<class VECTOR_OF_VECTORS, class MATRIXLIKE,class VECTORLIKE>
00336                 void covariancesAndMean(const VECTOR_OF_VECTORS &elements,MATRIXLIKE &covariances,VECTORLIKE &means, const bool *elem_do_wrap2pi = NULL)
00337                 {   // The function below is inline-expanded here:
00338                         covariancesAndMeanWeighted<VECTOR_OF_VECTORS,MATRIXLIKE,VECTORLIKE,vector_double,vector_double>(elements,covariances,means,NULL,NULL,elem_do_wrap2pi);
00339                 }
00340 
00341 
00342                 /** Computes the weighted histogram for a vector of values and their corresponding weights.
00343                   *  \param values [IN] The N values
00344                   *  \param weights [IN] The weights for the corresponding N values (don't need to be normalized)
00345                   *  \param binWidth [IN] The desired width of the bins
00346                   *  \param out_binCenters [OUT] The centers of the M bins generated to cover from the minimum to the maximum value of "values" with the given "binWidth"
00347                   *  \param out_binValues [OUT] The ratio of values at each given bin, such as the whole vector sums up the unity.
00348                   *  \sa weightedHistogramLog
00349                   */
00350                 template<class VECTORLIKE1,class VECTORLIKE2>
00351                         void  weightedHistogram(
00352                                 const VECTORLIKE1       &values,
00353                                 const VECTORLIKE1       &weights,
00354                                 float                           binWidth,
00355                                 VECTORLIKE2     &out_binCenters,
00356                                 VECTORLIKE2     &out_binValues )
00357                         {
00358                                 MRPT_START
00359                                 typedef typename VECTORLIKE1::value_type TNum;
00360 
00361                                 ASSERT_( values.size() == weights.size() );
00362                                 ASSERT_( binWidth > 0 );
00363                                 TNum    minBin = minimum( values );
00364                                 unsigned int    nBins = static_cast<unsigned>(ceil((maximum( values )-minBin) / binWidth));
00365 
00366                                 // Generate bin center and border values:
00367                                 out_binCenters.resize(nBins);
00368                                 out_binValues.clear(); out_binValues.resize(nBins,0);
00369                                 TNum halfBin = TNum(0.5)*binWidth;;
00370                                 VECTORLIKE2   binBorders(nBins+1,minBin-halfBin);
00371                                 for (unsigned int i=0;i<nBins;i++)
00372                                 {
00373                                         binBorders[i+1] = binBorders[i]+binWidth;
00374                                         out_binCenters[i] = binBorders[i]+halfBin;
00375                                 }
00376 
00377                                 // Compute the histogram:
00378                                 TNum totalSum = 0;
00379                                 typename VECTORLIKE1::const_iterator itVal, itW;
00380                                 for (itVal = values.begin(), itW = weights.begin(); itVal!=values.end(); ++itVal, ++itW )
00381                                 {
00382                                         int idx = round(((*itVal)-minBin)/binWidth);
00383                                         if (idx>=int(nBins)) idx=nBins-1;
00384                                         ASSERTDEB_(idx>=0);
00385                                         out_binValues[idx] += *itW;
00386                                         totalSum+= *itW;
00387                                 }
00388 
00389                                 if (totalSum)
00390                                         out_binValues /= totalSum;
00391 
00392 
00393                                 MRPT_END
00394                         }
00395 
00396                 /** Computes the weighted histogram for a vector of values and their corresponding log-weights.
00397                   *  \param values [IN] The N values
00398                   *  \param weights [IN] The log-weights for the corresponding N values (don't need to be normalized)
00399                   *  \param binWidth [IN] The desired width of the bins
00400                   *  \param out_binCenters [OUT] The centers of the M bins generated to cover from the minimum to the maximum value of "values" with the given "binWidth"
00401                   *  \param out_binValues [OUT] The ratio of values at each given bin, such as the whole vector sums up the unity.
00402                   *  \sa weightedHistogram
00403                   */
00404                 template<class VECTORLIKE1,class VECTORLIKE2>
00405                         void  weightedHistogramLog(
00406                                 const VECTORLIKE1       &values,
00407                                 const VECTORLIKE1       &log_weights,
00408                                 float                           binWidth,
00409                                 VECTORLIKE2     &out_binCenters,
00410                                 VECTORLIKE2     &out_binValues )
00411                         {
00412                                 MRPT_START
00413                                 typedef typename VECTORLIKE1::value_type TNum;
00414 
00415                                 ASSERT_( values.size() == log_weights.size() );
00416                                 ASSERT_( binWidth > 0 );
00417                                 TNum    minBin = minimum( values );
00418                                 unsigned int    nBins = static_cast<unsigned>(ceil((maximum( values )-minBin) / binWidth));
00419 
00420                                 // Generate bin center and border values:
00421                                 out_binCenters.resize(nBins);
00422                                 out_binValues.clear(); out_binValues.resize(nBins,0);
00423                                 TNum halfBin = TNum(0.5)*binWidth;;
00424                                 VECTORLIKE2   binBorders(nBins+1,minBin-halfBin);
00425                                 for (unsigned int i=0;i<nBins;i++)
00426                                 {
00427                                         binBorders[i+1] = binBorders[i]+binWidth;
00428                                         out_binCenters[i] = binBorders[i]+halfBin;
00429                                 }
00430 
00431                                 // Compute the histogram:
00432                                 const TNum max_log_weight = maximum(log_weights);
00433                                 TNum totalSum = 0;
00434                                 typename VECTORLIKE1::const_iterator itVal, itW;
00435                                 for (itVal = values.begin(), itW = log_weights.begin(); itVal!=values.end(); ++itVal, ++itW )
00436                                 {
00437                                         int idx = round(((*itVal)-minBin)/binWidth);
00438                                         if (idx>=int(nBins)) idx=nBins-1;
00439                                         ASSERTDEB_(idx>=0);
00440                                         const TNum w = exp(*itW-max_log_weight);
00441                                         out_binValues[idx] += w;
00442                                         totalSum+= w;
00443                                 }
00444 
00445                                 if (totalSum)
00446                                         out_binValues /= totalSum;
00447 
00448                                 MRPT_END
00449                         }
00450 
00451 
00452                         /** Extract a column from a vector of vectors, and store it in another vector.
00453                           *  - Input data can be: std::vector<vector_double>, std::deque<std::list<double> >, std::list<CArrayDouble<5> >, etc. etc.
00454                           *  - Output is the sequence:  data[0][idx],data[1][idx],data[2][idx], etc..
00455                           *
00456                           *  For the sake of generality, this function does NOT check the limits in the number of column, unless it's implemented in the [] operator of each of the "rows".
00457                           */
00458                         template <class VECTOR_OF_VECTORS, class VECTORLIKE>
00459                         inline void extractColumnFromVectorOfVectors(const size_t colIndex, const VECTOR_OF_VECTORS &data, VECTORLIKE &out_column)
00460                         {
00461                                 const size_t N = data.size();
00462                                 out_column.resize(N);
00463                                 for (size_t i=0;i<N;i++)
00464                                         out_column[i]=data[i][colIndex];
00465                         }
00466 
00467                 /** Computes the factorial of an integer number and returns it as a 64-bit integer number.
00468                   */
00469                 uint64_t BASE_IMPEXP  factorial64(unsigned int n);
00470 
00471                 /** Computes the factorial of an integer number and returns it as a double value (internally it uses logarithms for avoiding overflow).
00472                   */
00473                 double BASE_IMPEXP  factorial(unsigned int n);
00474 
00475                 /** Round up to the nearest power of two of a given number
00476                   */
00477                 template <class T>
00478                 T round2up(T val)
00479                 {
00480                         T n = 1;
00481                         while (n < val)
00482                         {
00483                                 n <<= 1;
00484                                 if (n<=1)
00485                                         THROW_EXCEPTION("Overflow!");
00486                         }
00487                         return n;
00488                 }
00489 
00490                 /** Round a decimal number up to the given 10'th power (eg, to 1000,100,10, and also fractions)
00491                   *  power10 means round up to: 1 -> 10, 2 -> 100, 3 -> 1000, ...  -1 -> 0.1, -2 -> 0.01, ...
00492                   */
00493                 template <class T>
00494                 T round_10power(T val, int power10)
00495                 {
00496                         long double F = ::pow((long double)10.0,-(long double)power10);
00497                         long int t = round_long( val * F );
00498                         return T(t/F);
00499                 }
00500 
00501                 /** Calculate the correlation between two matrices
00502                   *  (by AJOGD @ JAN-2007)
00503                   */
00504                 template<class T>
00505                 double  correlate_matrix(const CMatrixTemplateNumeric<T> &a1, const CMatrixTemplateNumeric<T> &a2)
00506                 {
00507                         if ((a1.getColCount()!=a2.getColCount())|(a1.getRowCount()!=a2.getRowCount()))
00508                                 THROW_EXCEPTION("Correlation Error!, images with no same size");
00509 
00510                         int i,j;
00511                         T x1,x2;
00512                         T syy=0, sxy=0, sxx=0, m1=0, m2=0 ,n=a1.getRowCount()*a2.getColCount();
00513 
00514                         //find the means
00515                         for (i=0;i<a1.getRowCount();i++)
00516                         {
00517                                 for (j=0;j<a1.getColCount();j++)
00518                                 {
00519                                         m1 += a1(i,j);
00520                                         m2 += a2(i,j);
00521                                 }
00522                         }
00523                         m1 /= n;
00524                         m2 /= n;
00525 
00526                         for (i=0;i<a1.getRowCount();i++)
00527                         {
00528                                 for (j=0;j<a1.getColCount();j++)
00529                                 {
00530                                         x1 = a1(i,j) - m1;
00531                                         x2 = a2(i,j) - m2;
00532                                         sxx += x1*x1;
00533                                         syy += x2*x2;
00534                                         sxy += x1*x2;
00535                                 }
00536                         }
00537 
00538                         return sxy / sqrt(sxx * syy);
00539                 }
00540 
00541                 /** A numerically-stable method to compute average likelihood values with strongly different ranges (unweighted likelihoods: compute the arithmetic mean).
00542                   *  This method implements this equation:
00543                   *
00544                   *  \f[ return = - \log N + \log  \sum_{i=1}^N e^{ll_i-ll_{max}} + ll_{max} \f]
00545                   *
00546                   * See also the <a href="http://www.mrpt.org/Averaging_Log-Likelihood_Values:Numerical_Stability">tutorial page</a>.
00547                   * \ingroup stats_grp
00548                   */
00549                 double BASE_IMPEXP averageLogLikelihood( const vector_double &logLikelihoods );
00550 
00551                 /** Computes the average of a sequence of angles in radians taking into account the correct wrapping in the range \f$ ]-\pi,\pi [ \f$, for example, the mean of (2,-2) is \f$ \pi \f$, not 0.
00552                   * \ingroup stats_grp
00553                   */
00554                 double BASE_IMPEXP averageWrap2Pi(const vector_double &angles );
00555 
00556                 /** A numerically-stable method to average likelihood values with strongly different ranges (weighted likelihoods).
00557                   *  This method implements this equation:
00558                   *
00559                   *  \f[ return = \log \left( \frac{1}{\sum_i e^{lw_i}} \sum_i  e^{lw_i} e^{ll_i}  \right) \f]
00560                   *
00561                   * See also the <a href="http://www.mrpt.org/Averaging_Log-Likelihood_Values:Numerical_Stability">tutorial page</a>.
00562                   * \ingroup stats_grp
00563                   */
00564                 double BASE_IMPEXP  averageLogLikelihood(
00565                         const vector_double &logWeights,
00566                         const vector_double &logLikelihoods );
00567 
00568                 /** Generates a string with the MATLAB commands required to plot an confidence interval (ellipse) for a 2D Gaussian ('float' version)..
00569                   *  \param cov22 The 2x2 covariance matrix
00570                   *  \param mean  The 2-length vector with the mean
00571                   *  \param stdCount How many "quantiles" to get into the area of the ellipse: 2: 95%, 3:99.97%,...
00572                   *  \param style A matlab style string, for colors, line styles,...
00573                   *  \param nEllipsePoints The number of points in the ellipse to generate
00574                   * \ingroup stats_grp
00575                   */
00576                 std::string BASE_IMPEXP  MATLAB_plotCovariance2D(
00577                         const CMatrixFloat  &cov22,
00578                         const vector_float  &mean,
00579                         const float         &stdCount,
00580                         const std::string   &style = std::string("b"),
00581                         const size_t        &nEllipsePoints = 30 );
00582 
00583                 /** Generates a string with the MATLAB commands required to plot an confidence interval (ellipse) for a 2D Gaussian ('double' version).
00584                   *  \param cov22 The 2x2 covariance matrix
00585                   *  \param mean  The 2-length vector with the mean
00586                   *  \param stdCount How many "quantiles" to get into the area of the ellipse: 2: 95%, 3:99.97%,...
00587                   *  \param style A matlab style string, for colors, line styles,...
00588                   *  \param nEllipsePoints The number of points in the ellipse to generate
00589                   * \ingroup stats_grp
00590                   */
00591                 std::string BASE_IMPEXP  MATLAB_plotCovariance2D(
00592                         const CMatrixDouble  &cov22,
00593                         const vector_double  &mean,
00594                         const float         &stdCount,
00595                         const std::string   &style = std::string("b"),
00596                         const size_t        &nEllipsePoints = 30 );
00597 
00598 
00599                 /** Efficiently compute the inverse of a 4x4 homogeneous matrix by only transposing the rotation 3x3 part and solving the translation with dot products.
00600                   *  This is a generic template which works with:
00601                   *    MATRIXLIKE: CMatrixTemplateNumeric, CMatrixFixedNumeric
00602                   */
00603                 template <class MATRIXLIKE1,class MATRIXLIKE2>
00604                 void homogeneousMatrixInverse(const MATRIXLIKE1 &M, MATRIXLIKE2 &out_inverse_M)
00605                 {
00606                         MRPT_START
00607                         ASSERT_( M.isSquare() && size(M,1)==4);
00608 
00609                         /* Instead of performing a generic 4x4 matrix inversion, we only need to
00610                           transpose the rotation part, then replace the translation part by
00611                           three dot products. See, for example:
00612                          https://graphics.stanford.edu/courses/cs248-98-fall/Final/q4.html
00613 
00614                                 [ux vx wx tx] -1   [ux uy uz -dot(u,t)]
00615                                 [uy vy wy ty]      [vx vy vz -dot(v,t)]
00616                                 [uz vz wz tz]    = [wx wy wz -dot(w,t)]
00617                                 [ 0  0  0  1]      [ 0  0  0     1    ]
00618                         */
00619 
00620                         out_inverse_M.setSize(4,4);
00621 
00622                         // 3x3 rotation part:
00623                         out_inverse_M.set_unsafe(0,0, M.get_unsafe(0,0));
00624                         out_inverse_M.set_unsafe(0,1, M.get_unsafe(1,0));
00625                         out_inverse_M.set_unsafe(0,2, M.get_unsafe(2,0));
00626 
00627                         out_inverse_M.set_unsafe(1,0, M.get_unsafe(0,1));
00628                         out_inverse_M.set_unsafe(1,1, M.get_unsafe(1,1));
00629                         out_inverse_M.set_unsafe(1,2, M.get_unsafe(2,1));
00630 
00631                         out_inverse_M.set_unsafe(2,0, M.get_unsafe(0,2));
00632                         out_inverse_M.set_unsafe(2,1, M.get_unsafe(1,2));
00633                         out_inverse_M.set_unsafe(2,2, M.get_unsafe(2,2));
00634 
00635                         const double tx = -M.get_unsafe(0,3);
00636                         const double ty = -M.get_unsafe(1,3);
00637                         const double tz = -M.get_unsafe(2,3);
00638 
00639                         const double tx_ = tx*M.get_unsafe(0,0)+ty*M.get_unsafe(1,0)+tz*M.get_unsafe(2,0);
00640                         const double ty_ = tx*M.get_unsafe(0,1)+ty*M.get_unsafe(1,1)+tz*M.get_unsafe(2,1);
00641                         const double tz_ = tx*M.get_unsafe(0,2)+ty*M.get_unsafe(1,2)+tz*M.get_unsafe(2,2);
00642 
00643                         out_inverse_M.set_unsafe(0,3, tx_ );
00644                         out_inverse_M.set_unsafe(1,3, ty_ );
00645                         out_inverse_M.set_unsafe(2,3, tz_ );
00646 
00647                         out_inverse_M.set_unsafe(3,0,  0);
00648                         out_inverse_M.set_unsafe(3,1,  0);
00649                         out_inverse_M.set_unsafe(3,2,  0);
00650                         out_inverse_M.set_unsafe(3,3,  1);
00651 
00652                         MRPT_END
00653                 }
00654                 //! \overload
00655                 template <class IN_ROTMATRIX,class IN_XYZ, class OUT_ROTMATRIX, class OUT_XYZ>
00656                 void homogeneousMatrixInverse(
00657                         const IN_ROTMATRIX  & in_R,
00658                         const IN_XYZ        & in_xyz,
00659                         OUT_ROTMATRIX & out_R,
00660                         OUT_XYZ       & out_xyz
00661                         )
00662                 {
00663                         MRPT_START
00664                         ASSERT_( in_R.isSquare() && size(in_R,1)==3 && in_xyz.size()==3)
00665                         out_R.setSize(3,3);
00666                         out_xyz.resize(3);
00667 
00668                         // translation part:
00669                         typedef typename IN_XYZ::value_type T;
00670                         const T tx = -in_xyz[0];
00671                         const T ty = -in_xyz[1];
00672                         const T tz = -in_xyz[2];
00673 
00674                         out_xyz[0] = tx*in_R.get_unsafe(0,0)+ty*in_R.get_unsafe(1,0)+tz*in_R.get_unsafe(2,0);
00675                         out_xyz[1] = tx*in_R.get_unsafe(0,1)+ty*in_R.get_unsafe(1,1)+tz*in_R.get_unsafe(2,1);
00676                         out_xyz[2] = tx*in_R.get_unsafe(0,2)+ty*in_R.get_unsafe(1,2)+tz*in_R.get_unsafe(2,2);
00677 
00678                         // 3x3 rotation part: transpose
00679                         out_R = in_R.adjoint();
00680 
00681                         MRPT_END
00682                 }
00683                 //! \overload
00684                 template <class MATRIXLIKE>
00685                 inline void homogeneousMatrixInverse(MATRIXLIKE &M)
00686                 {
00687                         ASSERTDEB_( M.isSquare() && size(M,1)==4);
00688                         // translation:
00689                         const double tx = -M(0,3);
00690                         const double ty = -M(1,3);
00691                         const double tz = -M(2,3);
00692                         M(0,3) = tx*M(0,0)+ty*M(1,0)+tz*M(2,0);
00693                         M(1,3) = tx*M(0,1)+ty*M(1,1)+tz*M(2,1);
00694                         M(2,3) = tx*M(0,2)+ty*M(1,2)+tz*M(2,2);
00695                         // 3x3 rotation part:
00696                         std::swap( M(1,0),M(0,1) );
00697                         std::swap( M(2,0),M(0,2) );
00698                         std::swap( M(1,2),M(2,1) );
00699                 }
00700 
00701 
00702                 /** Estimate the Jacobian of a multi-dimensional function around a point "x", using finite differences of a given size in each input dimension.
00703                   *  The template argument USERPARAM is for the data can be passed to the functor.
00704                   *   If it is not required, set to "int" or any other basic type.
00705                   *
00706                   *  This is a generic template which works with:
00707                   *    VECTORLIKE: vector_float, vector_double, CArrayNumeric<>, double [N], ...
00708                   *    MATRIXLIKE: CMatrixTemplateNumeric, CMatrixFixedNumeric
00709                   */
00710                 template <class VECTORLIKE,class VECTORLIKE2, class VECTORLIKE3, class MATRIXLIKE, class USERPARAM >
00711                 void estimateJacobian(
00712                         const VECTORLIKE        &x,
00713                         void                            (*functor) (const VECTORLIKE &x,const USERPARAM &y, VECTORLIKE3  &out),
00714                         const VECTORLIKE2       &increments,
00715                         const USERPARAM         &userParam,
00716                         MATRIXLIKE                      &out_Jacobian )
00717                 {
00718                         MRPT_START
00719                         ASSERT_(x.size()>0 && increments.size() == x.size());
00720 
00721                         size_t m = 0;           // will determine automatically on the first call to "f":
00722                         const size_t n = x.size();
00723 
00724                         for (size_t j=0;j<n;j++) { ASSERT_( increments[j]>0 ) }         // Who knows...
00725 
00726                         VECTORLIKE3     f_minus, f_plus;
00727                         VECTORLIKE      x_mod(x);
00728 
00729                         // Evaluate the function "i" with increments in the "j" input x variable:
00730                         for (size_t j=0;j<n;j++)
00731                         {
00732                                 // Create the modified "x" vector:
00733                                 x_mod[j]=x[j]+increments[j];
00734                                 functor(x_mod,userParam,   f_plus);
00735 
00736                                 x_mod[j]=x[j]-increments[j];
00737                                 functor(x_mod,userParam,   f_minus);
00738 
00739                                 x_mod[j]=x[j]; // Leave as original
00740                                 const double Ax_2_inv = 0.5/increments[j];
00741 
00742                                 // The first time?
00743                                 if (j==0)
00744                                 {
00745                                         m = f_plus.size();
00746                                         out_Jacobian.setSize(m,n);
00747                                 }
00748 
00749                                 for (size_t i=0;i<m;i++)
00750                                         out_Jacobian.get_unsafe(i,j) = Ax_2_inv* (f_plus[i]-f_minus[i]);
00751 
00752                         } // end for j
00753 
00754                         MRPT_END
00755                 }
00756 
00757                 /** Assignment operator for initializing a std::vector from a C array (The vector will be automatically set to the correct size).
00758                   * \code
00759                   *      vector_double  v;
00760                   *  const double numbers[] = { 1,2,3,5,6,7,8,9,10 };
00761                   *  loadVector( v, numbers );
00762                   * \endcode
00763                   * \note This operator performs the appropiate type castings, if required.
00764                   */
00765                 template <typename T, typename At, size_t N>
00766                 std::vector<T>& loadVector( std::vector<T> &v, At (&theArray)[N] )
00767                 {
00768                         MRPT_COMPILE_TIME_ASSERT(N!=0)
00769                         v.resize(N);
00770                         for (size_t i=0; i < N; i++)
00771                                 v[i] = static_cast<T>(theArray[i]);
00772                         return v;
00773                 }
00774                 //! \overload
00775                 template <typename Derived, typename At, size_t N>
00776                 Eigen::EigenBase<Derived>& loadVector( Eigen::EigenBase<Derived> &v, At (&theArray)[N] )
00777                 {
00778                         MRPT_COMPILE_TIME_ASSERT(N!=0)
00779                         v.derived().resize(N);
00780                         for (size_t i=0; i < N; i++)
00781                                 (v.derived())[i] = static_cast<typename Derived::Scalar>(theArray[i]);
00782                         return v;
00783                 }
00784 
00785                 /** Modify a sequence of angle values such as no consecutive values have a jump larger than PI in absolute value.
00786                   * \sa wrapToPi
00787                   */
00788                 void unwrap2PiSequence(vector_double &x);
00789 
00790                 /** A versatile template to build vectors on-the-fly in a style close to MATLAB's  v=[a b c d ...]
00791                   *  The first argument of the template is the vector length, and the second the type of the numbers.
00792                   *  Some examples:
00793                   *
00794                   *  \code
00795                   *    vector_double  = make_vector<4,double>(1.0,3.0,4.0,5.0);
00796                   *    vector_float   = make_vector<2,float>(-8.12, 3e4);
00797                   *  \endcode
00798                   */
00799                 template <size_t N, typename T>
00800                 std::vector<T> make_vector(const T val1, ...)
00801                 {
00802                         MRPT_COMPILE_TIME_ASSERT( N>0 )
00803                         std::vector<T>  ret;
00804                         ret.reserve(N);
00805 
00806                         ret.push_back(val1);
00807 
00808                         va_list args;
00809                         va_start(args,val1);
00810                         for (size_t i=0;i<N-1;i++)
00811                                 ret.push_back( va_arg(args,T) );
00812 
00813                         va_end(args);
00814                         return ret;
00815                 }
00816 
00817                 /**  @} */  // end of grouping container_ops_grp
00818 
00819                 /** \addtogroup stats_grp
00820                   * @{
00821                   */
00822 
00823                 /** @name Probability density distributions (pdf) distance metrics
00824                 @{ */
00825 
00826                 /** Computes the squared mahalanobis distance of a vector X given the mean MU and the covariance *inverse* COV_inv
00827                   *  \f[ d^2 =  (X-MU)^\top \Sigma^{-1} (X-MU)  \f]
00828                   */
00829                 template<class VECTORLIKE1,class VECTORLIKE2,class MAT>
00830                 typename VECTORLIKE1::value_type mahalanobisDistance2(
00831                         const VECTORLIKE1 &X,
00832                         const VECTORLIKE2 &MU,
00833                         const MAT &COV )
00834                 {
00835                         MRPT_START
00836                         #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG_MATRICES)
00837                                 ASSERT_( !X.empty() );
00838                                 ASSERT_( X.size()==MU.size() );
00839                                 ASSERT_( X.size()==size(COV,1) && COV.isSquare() );
00840                         #endif
00841                         const size_t N = X.size();
00842                         mrpt::dynamicsize_vector<typename VECTORLIKE1::value_type> X_MU(N);
00843                         for (size_t i=0;i<N;i++) X_MU[i]=X[i]-MU[i];
00844                         return multiply_HCHt_scalar(X_MU, COV.inv() );
00845                         MRPT_END
00846                 }
00847 
00848 
00849                 /** Computes the mahalanobis distance of a vector X given the mean MU and the covariance *inverse* COV_inv
00850                   *  \f[ d = \sqrt{ (X-MU)^\top \Sigma^{-1} (X-MU) }  \f]
00851                   */
00852                 template<class VECTORLIKE1,class VECTORLIKE2,class MAT>
00853                 inline typename VECTORLIKE1::value_type mahalanobisDistance(
00854                         const VECTORLIKE1 &X,
00855                         const VECTORLIKE2 &MU,
00856                         const MAT &COV )
00857                 {
00858                         return std::sqrt( mahalanobisDistance2(X,MU,COV) );
00859                 }
00860 
00861 
00862                 /** Computes the squared mahalanobis distance between two *non-independent* Gaussians, given the two covariance matrices and the vector with the difference of their means.
00863                   *  \f[ d^2 = \Delta_\mu^\top (\Sigma_1 + \Sigma_2 - 2 \Sigma_12 )^{-1} \Delta_\mu  \f]
00864                   */
00865                 template<class VECTORLIKE,class MAT1,class MAT2,class MAT3>
00866                 typename VECTORLIKE::value_type
00867                 mahalanobisDistance2(
00868                         const VECTORLIKE &mean_diffs,
00869                         const MAT1 &COV1,
00870                         const MAT2 &COV2,
00871                         const MAT3 &CROSS_COV12 )
00872                 {
00873                         MRPT_START
00874                         #if defined(_DEBUG) || (MRPT_ALWAYS_CHECKS_DEBUG_MATRICES)
00875                                 ASSERT_( !mean_diffs.empty() );
00876                                 ASSERT_( mean_diffs.size()==size(COV1,1));
00877                                 ASSERT_( COV1.isSquare() && COV2.isSquare() );
00878                                 ASSERT_( size(COV1,1)==size(COV2,1));
00879                         #endif
00880                         const size_t N = size(COV1,1);
00881                         MAT1 COV = COV1;
00882                         COV+=COV2;
00883                         COV.substract_An(CROSS_COV12,2);
00884                         MAT1 COV_inv;
00885                         COV.inv_fast(COV_inv);
00886                         return multiply_HCHt_scalar(mean_diffs,COV_inv);
00887                         MRPT_END
00888                 }
00889 
00890                 /** Computes the mahalanobis distance between two *non-independent* Gaussians (or independent if CROSS_COV12=NULL), given the two covariance matrices and the vector with the difference of their means.
00891                   *  \f[ d = \sqrt{ \Delta_\mu^\top (\Sigma_1 + \Sigma_2 - 2 \Sigma_12 )^{-1} \Delta_\mu } \f]
00892                   */
00893                 template<class VECTORLIKE,class MAT1,class MAT2,class MAT3> inline typename VECTORLIKE::value_type
00894                 mahalanobisDistance(
00895                         const VECTORLIKE &mean_diffs,
00896                         const MAT1 &COV1,
00897                         const MAT2 &COV2,
00898                         const MAT3 &CROSS_COV12 )
00899                 {
00900                         return std::sqrt( mahalanobisDistance( mean_diffs, COV1,COV2,CROSS_COV12 ));
00901                 }
00902 
00903                 /** Computes the squared mahalanobis distance between a point and a Gaussian, given the covariance matrix and the vector with the difference between the mean and the point.
00904                   *  \f[ d^2 = \Delta_\mu^\top \Sigma^{-1} \Delta_\mu  \f]
00905                   */
00906                 template<class VECTORLIKE,class MATRIXLIKE>
00907                 inline typename MATRIXLIKE::value_type
00908                 mahalanobisDistance2(const VECTORLIKE &delta_mu,const MATRIXLIKE &cov)
00909                 {
00910                         ASSERTDEB_(cov.isSquare())
00911                         ASSERTDEB_(cov.getColCount()==delta_mu.size())
00912                         return multiply_HCHt_scalar(delta_mu,cov.inverse());
00913                 }
00914 
00915                 /** Computes the mahalanobis distance between a point and a Gaussian, given the covariance matrix and the vector with the difference between the mean and the point.
00916                   *  \f[ d^2 = \sqrt( \Delta_\mu^\top \Sigma^{-1} \Delta_\mu ) \f]
00917                   */
00918                 template<class VECTORLIKE,class MATRIXLIKE>
00919                 inline typename MATRIXLIKE::value_type
00920                 mahalanobisDistance(const VECTORLIKE &delta_mu,const MATRIXLIKE &cov)
00921                 {
00922                         return std::sqrt(mahalanobisDistance2(delta_mu,cov));
00923                 }
00924 
00925                 /** Computes the integral of the product of two Gaussians, with means separated by "mean_diffs" and covariances "COV1" and "COV2".
00926                   *  \f[ D = \frac{1}{(2 \pi)^{0.5 N} \sqrt{}  }  \exp( \Delta_\mu^\top (\Sigma_1 + \Sigma_2 - 2 \Sigma_12)^{-1} \Delta_\mu)  \f]
00927                   */
00928                 template <typename T>
00929                 T productIntegralTwoGaussians(
00930                         const std::vector<T> &mean_diffs,
00931                         const CMatrixTemplateNumeric<T> &COV1,
00932                         const CMatrixTemplateNumeric<T> &COV2
00933                         )
00934                 {
00935                         const size_t vector_dim = mean_diffs.size();
00936                         ASSERT_(vector_dim>=1)
00937 
00938                         CMatrixTemplateNumeric<T> C = COV1;
00939                         C+= COV2;       // Sum of covs:
00940                         const T cov_det = C.det();
00941                         CMatrixTemplateNumeric<T> C_inv;
00942                         C.inv_fast(C_inv);
00943 
00944                         return std::pow( M_2PI, -0.5*vector_dim ) * (1.0/std::sqrt( cov_det ))
00945                                 * exp( -0.5 * mean_diffs.multiply_HCHt_scalar(C_inv) );
00946                 }
00947 
00948                 /** Computes the integral of the product of two Gaussians, with means separated by "mean_diffs" and covariances "COV1" and "COV2".
00949                   *  \f[ D = \frac{1}{(2 \pi)^{0.5 N} \sqrt{}  }  \exp( \Delta_\mu^\top (\Sigma_1 + \Sigma_2)^{-1} \Delta_\mu)  \f]
00950                   */
00951                 template <typename T, size_t DIM>
00952                 T productIntegralTwoGaussians(
00953                         const std::vector<T> &mean_diffs,
00954                         const CMatrixFixedNumeric<T,DIM,DIM> &COV1,
00955                         const CMatrixFixedNumeric<T,DIM,DIM> &COV2
00956                         )
00957                 {
00958                         ASSERT_(mean_diffs.size()==DIM);
00959 
00960                         CMatrixFixedNumeric<T,DIM,DIM> C = COV1;
00961                         C+= COV2;       // Sum of covs:
00962                         const T cov_det = C.det();
00963                         CMatrixFixedNumeric<T,DIM,DIM> C_inv(UNINITIALIZED_MATRIX);
00964                         C.inv_fast(C_inv);
00965 
00966                         return std::pow( M_2PI, -0.5*DIM ) * (1.0/std::sqrt( cov_det ))
00967                                 * exp( -0.5 * mean_diffs.multiply_HCHt_scalar(C_inv) );
00968                 }
00969 
00970                 /** Computes both, the integral of the product of two Gaussians and their square Mahalanobis distance.
00971                   * \sa productIntegralTwoGaussians, mahalanobisDistance2
00972                   */
00973                 template <typename T, class VECLIKE,class MATLIKE1, class MATLIKE2>
00974                 void productIntegralAndMahalanobisTwoGaussians(
00975                         const VECLIKE   &mean_diffs,
00976                         const MATLIKE1  &COV1,
00977                         const MATLIKE2  &COV2,
00978                         T                               &maha2_out,
00979                         T                               &intprod_out,
00980                         const MATLIKE1  *CROSS_COV12=NULL
00981                         )
00982                 {
00983                         const size_t vector_dim = mean_diffs.size();
00984                         ASSERT_(vector_dim>=1)
00985 
00986                         MATLIKE1 C = COV1;
00987                         C+= COV2;       // Sum of covs:
00988                         if (CROSS_COV12) { C-=*CROSS_COV12; C-=*CROSS_COV12; }
00989                         const T cov_det = C.det();
00990                         MATLIKE1 C_inv;
00991                         C.inv_fast(C_inv);
00992 
00993                         maha2_out = mean_diffs.multiply_HCHt_scalar(C_inv);
00994                         intprod_out = std::pow( M_2PI, -0.5*vector_dim ) * (1.0/std::sqrt( cov_det ))*exp(-0.5*maha2_out);
00995                 }
00996 
00997                 /** Computes both, the logarithm of the PDF and the square Mahalanobis distance between a point (given by its difference wrt the mean) and a Gaussian.
00998                   * \sa productIntegralTwoGaussians, mahalanobisDistance2, normalPDF, mahalanobisDistance2AndPDF
00999                   */
01000                 template <typename T, class VECLIKE,class MATRIXLIKE>
01001                 void mahalanobisDistance2AndLogPDF(
01002                         const VECLIKE           &diff_mean,
01003                         const MATRIXLIKE        &cov,
01004                         T                                       &maha2_out,
01005                         T                                       &log_pdf_out)
01006                 {
01007                         MRPT_START
01008                         ASSERTDEB_(cov.isSquare())
01009                         ASSERTDEB_(size_t(cov.getColCount())==size_t(diff_mean.size()))
01010                         MATRIXLIKE C_inv;
01011                         cov.inv(C_inv);
01012                         maha2_out = multiply_HCHt_scalar(diff_mean,C_inv);
01013                         log_pdf_out = static_cast<typename MATRIXLIKE::value_type>(-0.5)* (
01014                                 maha2_out+
01015                                 static_cast<typename MATRIXLIKE::value_type>(cov.getColCount())*::log(static_cast<typename MATRIXLIKE::value_type>(M_2PI))+
01016                                 ::log(cov.det())
01017                                 );
01018                         MRPT_END
01019                 }
01020 
01021                 /** Computes both, the PDF and the square Mahalanobis distance between a point (given by its difference wrt the mean) and a Gaussian.
01022                   * \sa productIntegralTwoGaussians, mahalanobisDistance2, normalPDF
01023                   */
01024                 template <typename T, class VECLIKE,class MATRIXLIKE>
01025                 inline void mahalanobisDistance2AndPDF(
01026                         const VECLIKE           &diff_mean,
01027                         const MATRIXLIKE        &cov,
01028                         T                                       &maha2_out,
01029                         T                                       &pdf_out)
01030                 {
01031                         mahalanobisDistance2AndLogPDF(diff_mean,cov,maha2_out,pdf_out);
01032                         pdf_out = std::exp(pdf_out); // log to linear
01033                 }
01034 
01035                 /** @} */
01036                 /** @} */  // end of grouping statistics
01037 
01038                 /** @addtogroup interpolation_grp Interpolation, least-squares fit, splines
01039                   * \ingroup mrpt_base_grp
01040                   *  @{ */
01041 
01042                 /** Interpolate a data sequence "ys" ranging from "x0" to "x1" (equally spaced), to obtain the approximation of the sequence at the point "x".
01043                   *  If the point "x" is out of the range [x0,x1], the closest extreme "ys" value is returned.
01044                   * \sa spline, interpolate2points
01045                   */
01046                 template <class T,class VECTOR>
01047                 T interpolate(
01048                         const T                 &x,
01049                         const VECTOR    &ys,
01050                         const T                 &x0,
01051                         const T                 &x1 )
01052                 {
01053                         MRPT_START
01054                         ASSERT_(x1>x0); ASSERT_(!ys.empty());
01055                         const size_t N = ys.size();
01056                         if (x<=x0)      return ys[0];
01057                         if (x>=x1)      return ys[N-1];
01058                         const T Ax = (x1-x0)/T(N);
01059                         const size_t i = int( (x-x0)/Ax );
01060                         if (i>=N-1) return ys[N-1];
01061                         const T Ay = ys[i+1]-ys[i];
01062                         return ys[i] + (x-(x0+i*Ax))*Ay/Ax;
01063                         MRPT_END
01064                 }
01065 
01066                 /** Linear interpolation/extrapolation: evaluates at "x" the line (x0,y0)-(x1,y1).
01067                   *  If wrap2pi is true, output is wrapped to ]-pi,pi] (It is assumed that input "y" values already are in the correct range).
01068                   * \sa spline, interpolate, leastSquareLinearFit
01069                   */
01070                 double BASE_IMPEXP interpolate2points(const double x, const double x0, const double y0, const double x1, const double y1, bool wrap2pi = false);
01071 
01072                 /** Interpolates the value of a function in a point "t" given 4 SORTED points where "t" is between the two middle points
01073                   *  If wrap2pi is true, output "y" values are wrapped to ]-pi,pi] (It is assumed that input "y" values already are in the correct range).
01074                   * \sa leastSquareLinearFit
01075                   */
01076                 double BASE_IMPEXP  spline(const double t, const vector_double &x, const vector_double &y, bool wrap2pi = false);
01077 
01078                 /** Interpolates or extrapolates using a least-square linear fit of the set of values "x" and "y", evaluated at a single point "t".
01079                   *  The vectors x and y must have size >=2, and all values of "x" must be different.
01080                   *  If wrap2pi is true, output "y" values are wrapped to ]-pi,pi] (It is assumed that input "y" values already are in the correct range).
01081                   * \sa spline
01082                   * \sa getRegressionLine, getRegressionPlane
01083                   */
01084                 template <typename NUMTYPE,class VECTORLIKE>
01085                 NUMTYPE leastSquareLinearFit(const NUMTYPE t, const VECTORLIKE &x, const VECTORLIKE &y, bool wrap2pi = false)
01086                 {
01087                         MRPT_START
01088 
01089                         // http://en.wikipedia.org/wiki/Linear_least_squares
01090                         ASSERT_(x.size()==y.size());
01091                         ASSERT_(x.size()>1);
01092 
01093                         const size_t N = x.size();
01094 
01095                         typedef typename VECTORLIKE::value_type NUM;
01096 
01097                         // X= [1 columns of ones, x' ]
01098                         const NUM x_min = x.minimum();
01099                         CMatrixTemplateNumeric<NUM> Xt(2,N);
01100                         for (size_t i=0;i<N;i++)
01101                         {
01102                                 Xt.set_unsafe(0,i, 1);
01103                                 Xt.set_unsafe(1,i, x[i]-x_min);
01104                         }
01105 
01106                         CMatrixTemplateNumeric<NUM> XtX;
01107                         XtX.multiply_AAt(Xt);
01108 
01109                         CMatrixTemplateNumeric<NUM> XtXinv;
01110                         XtX.inv_fast(XtXinv);
01111 
01112                         CMatrixTemplateNumeric<NUM> XtXinvXt;   // B = inv(X' * X)*X'  (pseudoinverse)
01113                         XtXinvXt.multiply(XtXinv,Xt);
01114 
01115                         VECTORLIKE B;
01116                         XtXinvXt.multiply_Ab(y,B);
01117 
01118                         ASSERT_(B.size()==2)
01119 
01120                         NUM ret = B[0] + B[1]*(t-x_min);
01121 
01122                         // wrap?
01123                         if (!wrap2pi)
01124                                         return ret;
01125                         else    return mrpt::math::wrapToPi(ret);
01126 
01127                         MRPT_END
01128                 }
01129 
01130                 /** Interpolates or extrapolates using a least-square linear fit of the set of values "x" and "y", evaluated at a sequence of points "ts" and returned at "outs".
01131                   *  If wrap2pi is true, output "y" values are wrapped to ]-pi,pi] (It is assumed that input "y" values already are in the correct range).
01132                   * \sa spline, getRegressionLine, getRegressionPlane
01133                   */
01134                 template <class VECTORLIKE1,class VECTORLIKE2,class VECTORLIKE3>
01135                 void leastSquareLinearFit(
01136                         const VECTORLIKE1 &ts,
01137                         VECTORLIKE2 &outs,
01138                         const VECTORLIKE3 &x,
01139                         const VECTORLIKE3 &y,
01140                         bool wrap2pi = false)
01141                 {
01142                         MRPT_START
01143 
01144                         // http://en.wikipedia.org/wiki/Linear_least_squares
01145                         ASSERT_(x.size()==y.size());
01146                         ASSERT_(x.size()>1);
01147 
01148                         const size_t N = x.size();
01149 
01150                         // X= [1 columns of ones, x' ]
01151                         typedef typename VECTORLIKE3::value_type NUM;
01152                         const NUM x_min = x.minimum();
01153                         CMatrixTemplateNumeric<NUM> Xt(2,N);
01154                         for (size_t i=0;i<N;i++)
01155                         {
01156                                 Xt.set_unsafe(0,i, 1);
01157                                 Xt.set_unsafe(1,i, x[i]-x_min);
01158                         }
01159 
01160                         CMatrixTemplateNumeric<NUM> XtX;
01161                         XtX.multiply_AAt(Xt);
01162 
01163                         CMatrixTemplateNumeric<NUM> XtXinv;
01164                         XtX.inv_fast(XtXinv);
01165 
01166                         CMatrixTemplateNumeric<NUM> XtXinvXt;   // B = inv(X' * X)*X' (pseudoinverse)
01167                         XtXinvXt.multiply(XtXinv,Xt);
01168 
01169                         VECTORLIKE3 B;
01170                         XtXinvXt.multiply_Ab(y,B);
01171 
01172                         ASSERT_(B.size()==2)
01173 
01174                         const size_t tsN = size_t(ts.size());
01175                         outs.resize(tsN);
01176                         if (!wrap2pi)
01177                                 for (size_t k=0;k<tsN;k++)
01178                                         outs[k] = B[0] + B[1]*(ts[k]-x_min);
01179                         else
01180                                 for (size_t k=0;k<tsN;k++)
01181                                         outs[k] = mrpt::math::wrapToPi( B[0] + B[1]*(ts[k]-x_min) );
01182                         MRPT_END
01183                 }
01184 
01185                 /** @} */  // end grouping interpolation_grp
01186 
01187         } // End of MATH namespace
01188 
01189 } // End of namespace
01190 
01191 #endif



Page generated by Doxygen 1.7.4 for MRPT 0.9.5 SVN:2717 at Sun Oct 16 16:08:03 PDT 2011 Hosted on:
SourceForge.net Logo