Go to the documentation of this file.00001 #ifndef _GPREGRESSION_HPP_
00002 #define _GPREGRESSION_HPP_
00003
00004 #define NDEBUG
00005
00006
00007 #include "cholesky.hpp"
00008 #include "types.hpp"
00009 #include "linAlgTools.hpp"
00010 #include <assert.h>
00011 #include <vector>
00012 #include <gsl/gsl_vector.h>
00013
00014 #include "covarianceFunction.hpp"
00015
00016
00017 template <class TInput>
00018 class GPReg
00019 {
00020
00021 public:
00022
00023 GPReg( CovFunc<TInput> *covFunc, double sigmaNoise, GPReg<TInput> *noiseGP = NULL);
00024 GPReg( CovFunc<TInput> *covFunc, double *sigmaNoise, GPReg<TInput> *noiseGP = NULL);
00025 GPReg(GPReg<TInput> *copyFromGP);
00026 ~GPReg();
00027
00028 void setSigmaNoise( double sigma );
00029 void setDataPoints( TVector<TInput> &dataPoints, TVector<double> &dataTargets );
00030 void buildGP(bool useTargets=true);
00031 void buildTargets();
00032 void evalGP( const TInput &x, double &mean, double &var );
00033 void evalGP( const TInput &x, double &mean );
00034 double getDataLikelihood();
00035 double getAvgVariance();
00036
00037 void getParameters(std::vector<double> *r );
00038 void setParameters(std::vector<double> *r );
00039 void getDerivative(std::vector<double> *r);
00040
00041
00042
00043 double getDataFit();
00044 double getComplexity();
00045 double getMarginalDataLikelihood();
00046
00047
00048
00049
00050
00051 public:
00052 GPReg<TInput> *m_copyFromGP;
00053
00054 int m_numDataPoints;
00055
00056 TVector<TInput> *m_dataPoints;
00057 TVector<double> *m_t;
00058 TMatrix<double> *m_C;
00059
00060 TMatrix<double> *m_iC;
00061 TVector<double> *m_iCt;
00062 CovFunc<TInput> *m_covFunc;
00063 double *m_sigmaNoise;
00064 double m_ownSigmaNoise;
00065
00066 GPReg<TInput> *m_noiseGP;
00067
00068 static double gsl_my_f(const gsl_vector *v, void *params);
00069 static void gsl_my_df (const gsl_vector *v, void *params, gsl_vector *df);
00070 static void gsl_my_fdf (const gsl_vector *v, void *params, double *f, gsl_vector *df);
00071 bool minimizeGSL(unsigned maxIt);
00072 };
00073 #endif //_GPREGRESSION_HPP_