Go to the documentation of this file.
15 #ifndef BELUGA_RANDOM_MULTIVARIATE_NORMAL_DISTRIBUTION_HPP
16 #define BELUGA_RANDOM_MULTIVARIATE_NORMAL_DISTRIBUTION_HPP
31 template <
class Vector,
class Matrix>
34 static_assert(std::is_base_of_v<Eigen::EigenBase<Vector>,
Vector>,
"Vector should be an Eigen type");
36 Vector::ColsAtCompileTime == 1 || Vector::RowsAtCompileTime == 1,
37 "Vector should be a column or row vector");
94 template <
class Generator>
95 [[nodiscard]]
auto operator()(std::normal_distribution<scalar_type>& distribution, Generator& generator)
const {
96 const auto delta =
vector_type{}.unaryExpr([&distribution, &generator](
auto) {
return distribution(generator); });
97 if constexpr (vector_type::ColsAtCompileTime == 1) {
113 if (!covariance.isApprox(covariance.transpose())) {
114 throw std::runtime_error(
"Invalid covariance matrix, it is not symmetric.");
116 const auto solver = Eigen::SelfAdjointEigenSolver<matrix_type>{covariance};
117 if (solver.info() != Eigen::Success) {
118 throw std::runtime_error(
"Invalid covariance matrix, eigen solver failed.");
120 const auto& eigenvalues = solver.eigenvalues();
121 if ((eigenvalues.array() < 0.0).any()) {
122 throw std::runtime_error(
"Invalid covariance matrix, it has negative eigenvalues.");
124 return solver.eigenvectors() * eigenvalues.cwiseSqrt().asDiagonal();
221 params_ = std::move(other.params_);
247 template <
class Generator>
249 return (*
this)(generator,
params_);
260 template <
class Generator>
MultivariateNormalDistributionParam(vector_type mean, matrix_type covariance)
Constructs a parameter set instance.
MultivariateNormalDistribution(const param_type ¶ms)
Construct from distribution parameters.
MultivariateNormalDistribution(covariance_type covariance)
Construct with zero mean and the given covariance.
std::normal_distribution< scalar_type > distribution_
static matrix_type make_transform(matrix_type covariance)
MultivariateNormalDistributionParam()=default
Constructs a parameter set instance.
MultivariateNormalDistributionParam(matrix_type covariance)
Constructs a parameter set instance.
const param_type & param() const
Returns the associated parameter set.
void param(const param_type ¶ms)
Sets the associated parameter set to params.
MultivariateNormalDistribution(const MultivariateNormalDistribution< U > &other)
Copy construct from another compatible distribution.
bool operator!=(const MultivariateNormalDistributionParam &other) const
Compares this object with other parameter set object.
typename multivariate_distribution_traits< T >::vector_type vector_type
The Eigen vector type corresponding to T.
result_type operator()(Generator &generator, const param_type ¶ms)
Generates the next random object in the distribution.
bool operator!=(const MultivariateNormalDistribution< T > &other) const
Compares this object with other distribution object.
std::vector< T, std::allocator< T > > Vector
Shorthand for a vector with the default allocator.
typename multivariate_distribution_traits< T >::result_type result_type
The result type from T.
typename multivariate_distribution_traits< T >::scalar_type scalar_type
The scalar type.
MultivariateNormalDistribution(result_type mean, covariance_type covariance)
Construct with the given mean and covariance.
auto operator()(std::normal_distribution< scalar_type > &distribution, Generator &generator) const
Generates a new random object from the distribution.
typename multivariate_distribution_traits< T >::covariance_type covariance_type
The covariance matrix from T.
Eigen::Matrix< Scalar, M, N > Matrix
MultivariateNormalDistribution & operator=(const MultivariateNormalDistribution< U > &other)
Copy assign from another compatible distribution.
typename vector_type ::Scalar scalar_type
The scalar type.
vector_type vector_type
The vector type.
MultivariateNormalDistribution(const T &, const typename multivariate_distribution_traits< T >::covariance_type &) -> MultivariateNormalDistribution< typename multivariate_distribution_traits< T >::result_type >
Deduction guide to deduce the correct result type.
Implementation of multivariate distribution traits.
Multivariate normal distribution parameter set class.
MultivariateNormalDistribution(MultivariateNormalDistribution< U > &&other) noexcept
Move construct from another compatible distribution.
Multivariate normal distribution.
bool operator==(const MultivariateNormalDistributionParam &other) const
Compares this object with other parameter set object.
void reset()
Resets the internal state of the distribution.
result_type operator()(Generator &generator)
Generates the next random object in the distribution.
Forward declaration of the multivariate_distribution_traits class template.
bool operator==(const MultivariateNormalDistribution< T > &other) const
Compares this object with other distribution object.
MultivariateNormalDistribution & operator=(MultivariateNormalDistribution< U > &&other)
Move assign from another compatible distribution.
covariance_type matrix_type
The covariance matrix from Vector.
friend class MultivariateNormalDistribution
The main Beluga namespace.
beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53