Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #ifndef MULTIVARIATE_GAUSSIAN_H_
00038 #define MULTIVARIATE_GAUSSIAN_H_
00039
00040 #include <eigen3/Eigen/Core>
00041 #include <eigen3/Eigen/Cholesky>
00042 #include <boost/random/variate_generator.hpp>
00043 #include <boost/random/normal_distribution.hpp>
00044 #include <boost/random/mersenne_twister.hpp>
00045 #include <cstdlib>
00046
00047 namespace chomp
00048 {
00052 class MultivariateGaussian
00053 {
00054 public:
00055 template <typename Derived1, typename Derived2>
00056 MultivariateGaussian(const Eigen::MatrixBase<Derived1>& mean, const Eigen::MatrixBase<Derived2>& covariance);
00057
00058 template <typename Derived>
00059 void sample(Eigen::MatrixBase<Derived>& output);
00060
00061 private:
00062 Eigen::VectorXd mean_;
00063 Eigen::MatrixXd covariance_;
00064 Eigen::MatrixXd covariance_cholesky_;
00066 int size_;
00067 boost::mt19937 rng_;
00068 boost::normal_distribution<> normal_dist_;
00069 boost::variate_generator<boost::mt19937, boost::normal_distribution<> > gaussian_;
00070 };
00071
00073
00074 template <typename Derived1, typename Derived2>
00075 MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase<Derived1>& mean,
00076 const Eigen::MatrixBase<Derived2>& covariance)
00077 : mean_(mean)
00078 , covariance_(covariance)
00079 , covariance_cholesky_(covariance_.llt().matrixL())
00080 , normal_dist_(0.0, 1.0)
00081 , gaussian_(rng_, normal_dist_)
00082 {
00083 rng_.seed(rand());
00084 size_ = mean.rows();
00085 }
00086
00087 template <typename Derived>
00088 void MultivariateGaussian::sample(Eigen::MatrixBase<Derived>& output)
00089 {
00090 for (int i = 0; i < size_; ++i)
00091 output(i) = gaussian_();
00092 output = mean_ + covariance_cholesky_ * output;
00093 }
00094 }
00095
00096 #endif