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
00037 #ifndef STOMP_MOVEIT_MULTIVARIATE_GAUSSIAN_H_
00038 #define STOMP_MOVEIT_MULTIVARIATE_GAUSSIAN_H_
00039
00040 #include <Eigen/Core>
00041 #include <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 <boost/shared_ptr.hpp>
00046 #include <cstdlib>
00047
00048 namespace stomp_moveit
00049 {
00050
00051 namespace utils
00052 {
00053
00054 class MultivariateGaussian;
00055 typedef boost::shared_ptr<MultivariateGaussian> MultivariateGaussianPtr;
00056
00060 class MultivariateGaussian
00061 {
00062 public:
00063 template <typename Derived1, typename Derived2>
00064 MultivariateGaussian(const Eigen::MatrixBase<Derived1>& mean, const Eigen::MatrixBase<Derived2>& covariance);
00065
00071 template <typename Derived>
00072 void sample(Eigen::MatrixBase<Derived>& output,bool use_covariance = true);
00073
00074 private:
00075 Eigen::VectorXd mean_;
00076 Eigen::MatrixXd covariance_;
00077 Eigen::MatrixXd covariance_cholesky_;
00079 int size_;
00080 boost::mt19937 rng_;
00081 boost::normal_distribution<> normal_dist_;
00082 boost::shared_ptr<boost::variate_generator<boost::mt19937, boost::normal_distribution<> > > gaussian_;
00083 };
00084
00086
00087 template <typename Derived1, typename Derived2>
00088 MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase<Derived1>& mean, const Eigen::MatrixBase<Derived2>& covariance):
00089 mean_(mean),
00090 covariance_(covariance),
00091 covariance_cholesky_(covariance_.llt().matrixL()),
00092 normal_dist_(0.0,1.0)
00093 {
00094
00095 rng_.seed(rand());
00096 size_ = mean.rows();
00097 gaussian_.reset(new boost::variate_generator<boost::mt19937, boost::normal_distribution<> >(rng_, normal_dist_));
00098 }
00099
00100 template <typename Derived>
00101 void MultivariateGaussian::sample(Eigen::MatrixBase<Derived>& output,bool use_covariance)
00102 {
00103 for (int i=0; i<size_; ++i)
00104 output(i) = (*gaussian_)();
00105
00106 if(use_covariance)
00107 {
00108 output = mean_ + covariance_cholesky_*output;
00109 }
00110 else
00111 {
00112 output = mean_ + output;
00113 }
00114 }
00115
00116 }
00117
00118 }
00119
00120 #endif