37 #ifndef STOMP_MOVEIT_MULTIVARIATE_GAUSSIAN_H_ 38 #define STOMP_MOVEIT_MULTIVARIATE_GAUSSIAN_H_ 41 #include <Eigen/Cholesky> 42 #include <boost/random/variate_generator.hpp> 43 #include <boost/random/normal_distribution.hpp> 44 #include <boost/random/mersenne_twister.hpp> 45 #include <boost/shared_ptr.hpp> 54 class MultivariateGaussian;
55 typedef std::shared_ptr<MultivariateGaussian> MultivariateGaussianPtr;
63 template <
typename Derived1,
typename Derived2>
64 MultivariateGaussian(
const Eigen::MatrixBase<Derived1>& mean,
const Eigen::MatrixBase<Derived2>& covariance);
71 template <
typename Derived>
72 void sample(Eigen::MatrixBase<Derived>& output,
bool use_covariance =
true);
81 boost::normal_distribution<> normal_dist_;
82 std::shared_ptr<boost::variate_generator<boost::mt19937, boost::normal_distribution<> > > gaussian_;
87 template <
typename Derived1,
typename Derived2>
88 MultivariateGaussian::MultivariateGaussian(
const Eigen::MatrixBase<Derived1>& mean,
const Eigen::MatrixBase<Derived2>& covariance):
97 gaussian_.reset(
new boost::variate_generator<boost::mt19937, boost::normal_distribution<> >(rng_, normal_dist_));
100 template <
typename Derived>
103 for (
int i=0; i<size_; ++i)
104 output(i) = (*gaussian_)();
112 output =
mean_ + output;
Eigen::MatrixXd covariance_cholesky_
Eigen::MatrixXd covariance_
void sample(Eigen::MatrixBase< Derived > &output, bool use_covariance=true)
generates random values using a normal distribution.
Generates samples from a multivariate gaussian distribution.