Skip to content

Commit

Permalink
*Changed boost namespace to std
Browse files Browse the repository at this point in the history
*Need to compare function implementations
*Find an equivalent implementation for variate_generator
  • Loading branch information
Shobuj-Paul committed Sep 15, 2023
1 parent 6482350 commit 963511f
Showing 1 changed file with 8 additions and 7 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -44,9 +44,8 @@

// TODO(#2166): Replace with std types
#include <boost/random/variate_generator.hpp>
#include <boost/random/normal_distribution.hpp>
#include <boost/random/mersenne_twister.hpp>
#include <boost/shared_ptr.hpp>

#include <random>
#include <cstdlib>

namespace stomp_moveit
Expand Down Expand Up @@ -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<boost::variate_generator<boost::mt19937, boost::normal_distribution<> > > gaussian_;
std::mt19937 rng_;
std::normal_distribution<double> normal_dist_;
std::shared_ptr<boost::variate_generator<
std::mt19937, STD_MSGS__MSG__DETAIL__COLOR_RGBA__TYPE_SUPPORT_HPP_::std::normal_distribution<>>>
gaussian_;
};

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

template <typename Derived>
Expand Down

0 comments on commit 963511f

Please sign in to comment.