Skip to content

Commit d0aa578

Browse files
committed
*Changed boost namespace to std
*Need to compare function implementations *Find an equivalent implementation for variate_generator
1 parent e37b956 commit d0aa578

File tree

1 file changed

+8
-7
lines changed

1 file changed

+8
-7
lines changed

moveit_planners/stomp/include/stomp_moveit/math/multivariate_gaussian.hpp

Lines changed: 8 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -44,9 +44,8 @@
4444

4545
// TODO(#2166): Replace with std types
4646
#include <boost/random/variate_generator.hpp>
47-
#include <boost/random/normal_distribution.hpp>
48-
#include <boost/random/mersenne_twister.hpp>
49-
#include <boost/shared_ptr.hpp>
47+
48+
#include <random>
5049
#include <cstdlib>
5150

5251
namespace stomp_moveit
@@ -79,9 +78,11 @@ class MultivariateGaussian
7978
Eigen::MatrixXd covariance_cholesky_; /**< Cholesky decomposition (LL^T) of the covariance */
8079

8180
int size_;
82-
boost::mt19937 rng_;
83-
boost::normal_distribution<> normal_dist_;
84-
std::shared_ptr<boost::variate_generator<boost::mt19937, boost::normal_distribution<> > > gaussian_;
81+
std::mt19937 rng_;
82+
std::normal_distribution<double> normal_dist_;
83+
std::shared_ptr<boost::variate_generator<
84+
std::mt19937, STD_MSGS__MSG__DETAIL__COLOR_RGBA__TYPE_SUPPORT_HPP_::std::normal_distribution<>>>
85+
gaussian_;
8586
};
8687

8788
//////////////////////// template function definitions follow //////////////////////////////
@@ -93,7 +94,7 @@ MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase<Derived1>& me
9394
{
9495
rng_.seed(rand());
9596
size_ = mean.rows();
96-
gaussian_.reset(new boost::variate_generator<boost::mt19937, boost::normal_distribution<> >(rng_, normal_dist_));
97+
gaussian_.reset(new boost::variate_generator<std::mt19937, std::normal_distribution<double>>(rng_, normal_dist_));
9798
}
9899

99100
template <typename Derived>

0 commit comments

Comments
 (0)