Skip to content

Commit a730723

Browse files
committed
calling Distribution(Engine) directly
1 parent d0aa578 commit a730723

File tree

1 file changed

+5
-5
lines changed

1 file changed

+5
-5
lines changed

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

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -80,9 +80,9 @@ class MultivariateGaussian
8080
int size_;
8181
std::mt19937 rng_;
8282
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_;
83+
// std::shared_ptr<boost::variate_generator<
84+
// std::mt19937, STD_MSGS__MSG__DETAIL__COLOR_RGBA__TYPE_SUPPORT_HPP_::std::normal_distribution<>>>
85+
// gaussian_;
8686
};
8787

8888
//////////////////////// template function definitions follow //////////////////////////////
@@ -94,14 +94,14 @@ MultivariateGaussian::MultivariateGaussian(const Eigen::MatrixBase<Derived1>& me
9494
{
9595
rng_.seed(rand());
9696
size_ = mean.rows();
97-
gaussian_.reset(new boost::variate_generator<std::mt19937, std::normal_distribution<double>>(rng_, normal_dist_));
97+
// gaussian_.reset(new boost::variate_generator<std::mt19937, std::normal_distribution<double>>(rng_, normal_dist_));
9898
}
9999

100100
template <typename Derived>
101101
void MultivariateGaussian::sample(Eigen::MatrixBase<Derived>& output, bool use_covariance)
102102
{
103103
for (int i = 0; i < size_; ++i)
104-
output(i) = (*gaussian_)();
104+
output(i) = normal_dist_(rng_);
105105

106106
if (use_covariance)
107107
{

0 commit comments

Comments
 (0)