diff --git a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp index 4011f3c647e..24316fd7721 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp @@ -44,9 +44,8 @@ // TODO(#2166): Replace with std types #include -#include -#include -#include + +#include #include namespace stomp_moveit @@ -79,9 +78,11 @@ class MultivariateGaussian Eigen::MatrixXd covariance_cholesky_; /**< Cholesky decomposition (LL^T) of the covariance */ int size_; - boost::mt19937 rng_; - boost::normal_distribution<> normal_dist_; - std::shared_ptr > > gaussian_; + std::mt19937 rng_; + std::normal_distribution normal_dist_; + std::shared_ptr>> + gaussian_; }; //////////////////////// template function definitions follow ////////////////////////////// @@ -93,7 +94,7 @@ MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase& me { rng_.seed(rand()); size_ = mean.rows(); - gaussian_.reset(new boost::variate_generator >(rng_, normal_dist_)); + gaussian_.reset(new boost::variate_generator>(rng_, normal_dist_)); } template