rtcPCA.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (C) 2008
00003  * Robert Bosch LLC
00004  * Research and Technology Center North America
00005  * Palo Alto, California
00006  *
00007  * All rights reserved.
00008  *
00009  *------------------------------------------------------------------------------
00010  * project ....: PUMA: Probablistic Unsupervised Model Acquisition
00011  * file .......: pca.h
00012  * authors ....: Benjamin Pitzer
00013  * organization: Robert Bosch LLC
00014  * creation ...: 08/16/2006
00015  * modified ...: $Date: 2009-01-10 22:38:24 -0800 (Sat, 10 Jan 2009) $
00016  * changed by .: $Author: benjaminpitzer $
00017  * revision ...: $Revision: 695 $
00018  */
00019 #ifndef PCA_H
00020 #define PCA_H
00021 
00022 #include "rtc/rtcMath.h"
00023 #include "rtc/rtcSMat.h"
00024 #include "rtc/rtcVec.h"
00025 #include "rtc/rtcVarMat.h"
00026 #include "rtc/rtcVarVec.h"
00027 #include "rtc/rtcEigenSystem.h"
00028 
00029 namespace rtc {
00030 
00036   template <class T, int N>
00037   class PrincipalComponentAnalysis {
00038   public:
00039     // data vector type
00040     typedef std::vector< Vec<T,N> > VecData;
00041 
00043     PrincipalComponentAnalysis();
00045     ~PrincipalComponentAnalysis();
00046 
00048     SMat<T,N>& computeTransformMatrix(const VecData& data);
00050     SMat<T,N>& computeTransformMatrix(const VarMat<T>& data);
00051 
00053     Vec<T,N>& transform(const Vec<T,N>& src, Vec<T,N>& dest) const;
00055     Vec<T,N>& transform(Vec<T,N>& srcdest) const;
00057     VarMat<T>& transform(VarMat<T>& data) const;
00059     VecData& transform(VecData& data) const;
00060   protected:
00061     // calculates mean of all rows
00062     SMat<T,N>& covarianceMatrixOfRows(const VecData& src, SMat<T,N>& covariance) const;
00063     // calculates mean of all rows
00064     Vec<T,N>& meanOfRows(const VecData& src, Vec<T,N>& mean) const;
00065 
00066     // Data
00067     bool transform_matrix_computed;
00068 
00069   public:
00070     Vec<T,N> offset;
00071     SMat<T,N> correlation_coefficient;
00072     SMat<T,N> eigen_vectors;
00073     SMat<T,N> transform_matrix;
00074     Vec<T,N> eigen_values;
00075   };
00076 
00077 
00080   template <class T, int N>
00081   inline PrincipalComponentAnalysis<T,N>::PrincipalComponentAnalysis() {
00082     transform_matrix_computed = false;
00083   }
00084 
00087   template <class T, int N>
00088   inline PrincipalComponentAnalysis<T,N>::~PrincipalComponentAnalysis() {
00089 
00090   }
00091 
00092   template <class T, int N>
00093   inline SMat<T,N>& PrincipalComponentAnalysis<T,N>::computeTransformMatrix(const VecData& data)
00094   {
00095     // determine the center of the data point distribution
00096     meanOfRows(data,offset);
00097 
00098     // correlation coefficient matrix
00099     covarianceMatrixOfRows(data,correlation_coefficient);
00100 
00101     // now compute eigenvectors of correlation coefficient matrix
00102     EigenSystem<T,N> eig(correlation_coefficient);
00103     eig.jacobi(eigen_values, eigen_vectors);
00104 
00105     // sort eigenvalues (and corresponding eigenvectors) into descending order
00106     eig.eigenSort(eigen_values, eigen_vectors);
00107 
00108     // the transformation matrix is simply the first columns of
00109     // the ordered eigenvectors
00110     transform_matrix.set(eigen_vectors);
00111 
00112     transform_matrix_computed = true;
00113     return transform_matrix;
00114   }
00115 
00116   template <class T, int N>
00117   inline SMat<T,N>& PrincipalComponentAnalysis<T,N>::computeTransformMatrix(const VarMat<T>& data)
00118   {
00119     if(data.columns()!=N)
00120       throw Exception("The input matrix has the wrong number of columns.");
00121 
00122     // determine the center of the data point distribution
00123     VarVec<T> var_offset = data.meanOfRows();
00124     for(int i=0;i<N;++i) offset(i)=var_offset(i);
00125 
00126     // correlation coefficient matrix
00127     VarSMat<T> var_correlation_coefficient = data.covarianceMatrixOfRows();
00128     for(int i=0;i<N;++i) for(int j=0;j<N;++j) correlation_coefficient(i,j)=var_correlation_coefficient(i,j);
00129 
00130     // now compute eigenvectors of correlation coefficient matrix
00131     EigenSystem<T,N> eig(correlation_coefficient);
00132     eig.jacobi(eigen_values, eigen_vectors);
00133 
00134     // sort eigenvalues (and corresponding eigenvectors) into descending order
00135     eig.eigenSort(eigen_values, eigen_vectors);
00136 
00137     // the transformation matrix is simply the first columns of
00138     // the ordered eigenvectors
00139     transform_matrix.set(eigen_vectors);
00140 
00141     transform_matrix_computed = true;
00142     return transform_matrix;
00143   }
00144 
00145   /*
00146    * Transforms a single vector according to a previously computed
00147    * transformation matrix.
00148    */
00149   template <class T, int N>
00150   inline Vec<T,N>& PrincipalComponentAnalysis<T,N>::transform(const Vec<T,N>& src, Vec<T,N>& dest) const {
00151     // check if transform matrix was computed
00152     if(!transform_matrix_computed)
00153       throw Exception("The transform matrix has to be computed before calling this function.");
00154     // subtract offset
00155     Vec<T,N> tmp = src-offset;
00156     // apply transform
00157     dest = transform_matrix*tmp;
00158     return dest;
00159   }
00160 
00161   /*
00162    * Transforms a single vector according to a previously computed
00163    * transformation matrix.
00164    */
00165   template <class T, int N>
00166   inline Vec<T,N>& PrincipalComponentAnalysis<T,N>::transform(Vec<T,N>& srcdest) const {
00167     // check if transform matrix was computed
00168     if(!transform_matrix_computed)
00169       throw Exception("The transform matrix has to be computed before calling this function.");
00170     // subtract offset
00171     Vec<T,N> tmp = srcdest-offset;
00172     // apply transform
00173     srcdest = transform_matrix*tmp;
00174     return srcdest;
00175   }
00176 
00177   /*
00178    * Transforms the data vector according to a previously computed
00179    * transformation matrix.
00180    */
00181   template <class T, int N>
00182   inline VarMat<T>& PrincipalComponentAnalysis<T,N>::transform(VarMat<T>& data) const {
00183     // check if transform matrix was computed
00184     if(!transform_matrix_computed)
00185       throw Exception("The transform matrix has to be computed before calling this function.");
00186 
00187     for (unsigned int i=0;i<data.rows();i++) {
00188       Vec<T,N> tmp = data.getRow(i);
00189       transform(tmp);
00190       data.setRow(i,tmp);
00191     }
00192 
00193     return data;
00194   }
00195 
00196   /*
00197    * Transforms the data vector according to a previously computed
00198    * transformation matrix.
00199    */
00200   template <class T, int N>
00201   inline std::vector< Vec<T,N> >& PrincipalComponentAnalysis<T,N>::transform(VecData& data) const {
00202     // check if transform matrix was computed
00203     if(!transform_matrix_computed)
00204       throw Exception("The transform matrix has to be computed before calling this function.");
00205 
00206     for (unsigned int i=0;i<data.size();i++)
00207       transform(data[i]);
00208 
00209     return data;
00210   }
00211 
00216   template <class T, int N>
00217   inline Vec<T,N>& PrincipalComponentAnalysis<T,N>::meanOfRows(const VecData& src, Vec<T,N>& mean) const {
00218     mean.set(T(0));
00219     int len = src.size();
00220     for (int j=0;j<N;j++)
00221       for (int i=0;i<len;i++) mean.x[j] += src[i][j];
00222     mean/=static_cast<T>(len);
00223     return mean;
00224   }
00225 
00226   // covariance of rows
00227   template <class T, int N>
00228   inline SMat<T,N>& PrincipalComponentAnalysis<T,N>::covarianceMatrixOfRows(const VecData& src, SMat<T,N>& covariance) const {
00229 
00230     int len = src.size();
00231     covariance.set(T(0));
00232 
00233     //Implementation for the sum of Matrix[X];
00234     if (len<2) { //just one row
00235       throw Exception("The input data has to have more than one row.");
00236     }
00237 
00238     // mean vector
00239     Vec<T,N> mu(T(0));
00240 
00241     /*
00242      * the loop gets out the result of the Matrix[X];
00243      * Matrix[X]=sum(Matrix[X(i)]);-- i from 0 to n-1--
00244      */
00245     for (int i=0; i<len; i++) {
00246       const Vec<T,N>& tmpV = src.at(i);
00247       mu.add(tmpV);
00248       SMat<T,N> tmp = tmpV.outer(tmpV);
00249       covariance.add(tmp); //add the Matrix[X(i)] to Matrix[sumMatrix];
00250     }
00251     //End of the Implementation for the sum of Matrix[X];
00252 
00253     //Implementation for the Matrix[meanOf];
00254     mu/=static_cast<T>(len);
00255 
00256     SMat<T,N> tmp = mu.outer(mu);
00257     tmp *= static_cast<T>(len);
00258 
00259     //get the result of the difference from Matrix[X] and Matrix[meanOf];
00260     covariance.subtract(tmp);
00261     covariance/=static_cast<T>(len-1);
00262     return covariance;
00263   }
00264 
00265 }; // end namspace puma
00266 
00267 #endif


rtc
Author(s): Benjamin Pitzer
autogenerated on Mon Oct 6 2014 10:07:35