multivariate_normal_distribution.hpp
Go to the documentation of this file.
1 // Copyright 2023-2024 Ekumen, Inc.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef BELUGA_RANDOM_MULTIVARIATE_NORMAL_DISTRIBUTION_HPP
16 #define BELUGA_RANDOM_MULTIVARIATE_NORMAL_DISTRIBUTION_HPP
17 
18 #include <random>
19 #include <utility>
20 
22 
28 namespace beluga {
29 
31 template <class Vector, class Matrix>
33  public:
34  static_assert(std::is_base_of_v<Eigen::EigenBase<Vector>, Vector>, "Vector should be an Eigen type");
35  static_assert(
36  Vector::ColsAtCompileTime == 1 || Vector::RowsAtCompileTime == 1,
37  "Vector should be a column or row vector");
38 
40  using scalar_type = typename Vector::Scalar;
41 
44 
47 
50 
52 
58  : transform_{make_transform(std::move(covariance))} {}
59 
61 
68  : mean_{std::move(mean)}, transform_{make_transform(std::move(covariance))} {}
69 
71 
75  [[nodiscard]] bool operator==(const MultivariateNormalDistributionParam& other) const {
76  return mean_ == other.mean_ && transform_ == other.transform_;
77  }
78 
80 
84  [[nodiscard]] bool operator!=(const MultivariateNormalDistributionParam& other) const { return !(*this == other); }
85 
87 
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) {
98  return mean_ + transform_ * delta;
99  } else {
100  return mean_ + delta * transform_;
101  }
102  }
103 
104  private:
105  vector_type mean_{vector_type::Zero()};
106  matrix_type transform_{make_transform(vector_type::Ones().asDiagonal())};
107 
108  [[nodiscard]] static matrix_type make_transform(matrix_type covariance) {
109  // For more information about the method used to generate correlated normal vectors
110  // from independent normal distributions, see:
111  // https://en.wikipedia.org/wiki/Multivariate_normal_distribution#Drawing_values_from_the_distribution
112  // \cite gentle2009computationalstatistics.
113  if (!covariance.isApprox(covariance.transpose())) {
114  throw std::runtime_error("Invalid covariance matrix, it is not symmetric.");
115  }
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.");
119  }
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.");
123  }
124  return solver.eigenvectors() * eigenvalues.cwiseSqrt().asDiagonal();
125  }
126 };
127 
129 
136 template <class T>
138  public:
139  template <class U>
141 
144 
147 
150 
153 
156 
158  MultivariateNormalDistribution() = default;
159 
161 
164  explicit MultivariateNormalDistribution(const param_type& params) : params_{params} {}
165 
167 
172  explicit MultivariateNormalDistribution(covariance_type covariance) : params_{std::move(covariance)} {}
173 
175 
182  : params_{multivariate_distribution_traits<T>::to_vector(std::move(mean)), std::move(covariance)} {}
183 
185 
189  template <class U>
191  : params_{other.params_}, distribution_{other.distribution_} {}
192 
194 
198  template <class U>
199  /* implicit */ MultivariateNormalDistribution(MultivariateNormalDistribution<U>&& other) noexcept // NOLINT
200  : params_(std::move(other.params_)), distribution_{std::move(other.distribution_)} {}
201 
203 
207  template <class U>
209  params_ = other.params_;
211  return *this;
212  }
213 
215 
219  template <class U>
221  params_ = std::move(other.params_);
222  distribution_ = std::move(other.distribution_);
223  return *this;
224  }
225 
227  void reset() { distribution_.reset(); }
228 
230  [[nodiscard]] const param_type& param() const { return params_; }
231 
233 
238  void param(const param_type& params) { params_ = params; }
239 
241 
247  template <class Generator>
248  [[nodiscard]] result_type operator()(Generator& generator) {
249  return (*this)(generator, params_);
250  }
251 
253 
260  template <class Generator>
261  [[nodiscard]] result_type operator()(Generator& generator, const param_type& params) {
263  }
264 
266 
273  [[nodiscard]] bool operator==(const MultivariateNormalDistribution<T>& other) const {
274  return params_ == other.params_ && distribution_ == other.distribution_;
275  }
276 
278 
285  [[nodiscard]] bool operator!=(const MultivariateNormalDistribution<T>& other) const { return !(*this == other); }
286 
287  private:
289  std::normal_distribution<scalar_type> distribution_;
290 };
291 
293 template <class T>
296 
297 } // namespace beluga
298 
299 #endif
beluga::MultivariateNormalDistributionParam::MultivariateNormalDistributionParam
MultivariateNormalDistributionParam(vector_type mean, matrix_type covariance)
Constructs a parameter set instance.
Definition: multivariate_normal_distribution.hpp:67
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
MultivariateNormalDistribution(const param_type &params)
Construct from distribution parameters.
Definition: multivariate_normal_distribution.hpp:164
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
MultivariateNormalDistribution(covariance_type covariance)
Construct with zero mean and the given covariance.
Definition: multivariate_normal_distribution.hpp:172
beluga::MultivariateNormalDistribution::distribution_
std::normal_distribution< scalar_type > distribution_
Definition: multivariate_normal_distribution.hpp:289
beluga::MultivariateNormalDistributionParam::make_transform
static matrix_type make_transform(matrix_type covariance)
Definition: multivariate_normal_distribution.hpp:108
beluga::MultivariateNormalDistributionParam::MultivariateNormalDistributionParam
MultivariateNormalDistributionParam()=default
Constructs a parameter set instance.
beluga::MultivariateNormalDistribution::params_
param_type params_
Definition: multivariate_normal_distribution.hpp:288
beluga::MultivariateNormalDistributionParam::MultivariateNormalDistributionParam
MultivariateNormalDistributionParam(matrix_type covariance)
Constructs a parameter set instance.
Definition: multivariate_normal_distribution.hpp:57
beluga::MultivariateNormalDistribution::param
const param_type & param() const
Returns the associated parameter set.
Definition: multivariate_normal_distribution.hpp:230
beluga::MultivariateNormalDistribution::param
void param(const param_type &params)
Sets the associated parameter set to params.
Definition: multivariate_normal_distribution.hpp:238
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
MultivariateNormalDistribution(const MultivariateNormalDistribution< U > &other)
Copy construct from another compatible distribution.
Definition: multivariate_normal_distribution.hpp:190
beluga::MultivariateNormalDistributionParam::operator!=
bool operator!=(const MultivariateNormalDistributionParam &other) const
Compares this object with other parameter set object.
Definition: multivariate_normal_distribution.hpp:84
beluga::MultivariateNormalDistribution::vector_type
typename multivariate_distribution_traits< T >::vector_type vector_type
The Eigen vector type corresponding to T.
Definition: multivariate_normal_distribution.hpp:146
beluga::MultivariateNormalDistribution::operator()
result_type operator()(Generator &generator, const param_type &params)
Generates the next random object in the distribution.
Definition: multivariate_normal_distribution.hpp:261
beluga::MultivariateNormalDistribution::operator!=
bool operator!=(const MultivariateNormalDistribution< T > &other) const
Compares this object with other distribution object.
Definition: multivariate_normal_distribution.hpp:285
beluga::Vector
std::vector< T, std::allocator< T > > Vector
Shorthand for a vector with the default allocator.
Definition: tuple_vector.hpp:216
beluga::MultivariateNormalDistribution::result_type
typename multivariate_distribution_traits< T >::result_type result_type
The result type from T.
Definition: multivariate_normal_distribution.hpp:152
beluga::MultivariateNormalDistribution::scalar_type
typename multivariate_distribution_traits< T >::scalar_type scalar_type
The scalar type.
Definition: multivariate_normal_distribution.hpp:143
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
MultivariateNormalDistribution(result_type mean, covariance_type covariance)
Construct with the given mean and covariance.
Definition: multivariate_normal_distribution.hpp:181
beluga::MultivariateNormalDistributionParam::operator()
auto operator()(std::normal_distribution< scalar_type > &distribution, Generator &generator) const
Generates a new random object from the distribution.
Definition: multivariate_normal_distribution.hpp:95
beluga::MultivariateNormalDistribution::covariance_type
typename multivariate_distribution_traits< T >::covariance_type covariance_type
The covariance matrix from T.
Definition: multivariate_normal_distribution.hpp:149
Matrix
Eigen::Matrix< Scalar, M, N > Matrix
beluga::MultivariateNormalDistribution::operator=
MultivariateNormalDistribution & operator=(const MultivariateNormalDistribution< U > &other)
Copy assign from another compatible distribution.
Definition: multivariate_normal_distribution.hpp:208
beluga::MultivariateNormalDistributionParam< vector_type, covariance_type >::scalar_type
typename vector_type ::Scalar scalar_type
The scalar type.
Definition: multivariate_normal_distribution.hpp:40
beluga::MultivariateNormalDistributionParam< vector_type, covariance_type >::vector_type
vector_type vector_type
The vector type.
Definition: multivariate_normal_distribution.hpp:43
beluga::MultivariateNormalDistribution
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.
multivariate_distribution_traits.hpp
Implementation of multivariate distribution traits.
beluga::MultivariateNormalDistributionParam::mean_
vector_type mean_
Definition: multivariate_normal_distribution.hpp:105
beluga::MultivariateNormalDistributionParam
Multivariate normal distribution parameter set class.
Definition: multivariate_normal_distribution.hpp:32
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
MultivariateNormalDistribution(MultivariateNormalDistribution< U > &&other) noexcept
Move construct from another compatible distribution.
Definition: multivariate_normal_distribution.hpp:199
beluga::MultivariateNormalDistribution
Multivariate normal distribution.
Definition: multivariate_normal_distribution.hpp:137
beluga::MultivariateNormalDistributionParam::operator==
bool operator==(const MultivariateNormalDistributionParam &other) const
Compares this object with other parameter set object.
Definition: multivariate_normal_distribution.hpp:75
beluga::MultivariateNormalDistribution::reset
void reset()
Resets the internal state of the distribution.
Definition: multivariate_normal_distribution.hpp:227
beluga::MultivariateNormalDistribution::operator()
result_type operator()(Generator &generator)
Generates the next random object in the distribution.
Definition: multivariate_normal_distribution.hpp:248
beluga::multivariate_distribution_traits
Forward declaration of the multivariate_distribution_traits class template.
Definition: multivariate_distribution_traits.hpp:32
beluga::MultivariateNormalDistributionParam::transform_
matrix_type transform_
Definition: multivariate_normal_distribution.hpp:106
beluga::MultivariateNormalDistribution::operator==
bool operator==(const MultivariateNormalDistribution< T > &other) const
Compares this object with other distribution object.
Definition: multivariate_normal_distribution.hpp:273
beluga::MultivariateNormalDistribution::operator=
MultivariateNormalDistribution & operator=(MultivariateNormalDistribution< U > &&other)
Move assign from another compatible distribution.
Definition: multivariate_normal_distribution.hpp:220
beluga::MultivariateNormalDistributionParam< vector_type, covariance_type >::matrix_type
covariance_type matrix_type
The covariance matrix from Vector.
Definition: multivariate_normal_distribution.hpp:46
beluga::MultivariateNormalDistribution::MultivariateNormalDistribution
friend class MultivariateNormalDistribution
Definition: multivariate_normal_distribution.hpp:140
beluga
The main Beluga namespace.
Definition: 3d_embedding.hpp:21


beluga
Author(s):
autogenerated on Tue Jul 16 2024 02:59:53