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 f8b528568dc..dba83207abd 100644 --- a/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp +++ b/moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp @@ -76,6 +76,7 @@ class MultivariateGaussian int size_; std::mt19937 rng_; + std::random_device rd_{}; std::normal_distribution normal_dist_; }; @@ -86,7 +87,7 @@ MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase& me const Eigen::MatrixBase& covariance) : mean_(mean), covariance_(covariance), covariance_cholesky_(covariance_.llt().matrixL()), normal_dist_(0.0, 1.0) { - rng_.seed(rand()); + rng_.seed(rd_()); size_ = mean.rows(); }