Sampler.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #include <gtsam/linear/Sampler.h>
20 namespace gtsam {
21 
22 /* ************************************************************************* */
24  uint_fast64_t seed)
25  : model_(model), generator_(seed) {}
26 
27 /* ************************************************************************* */
29  : model_(noiseModel::Diagonal::Sigmas(sigmas, true)), generator_(seed) {}
30 
31 /* ************************************************************************* */
33  size_t d = sigmas.size();
34  Vector result(d);
35  for (size_t i = 0; i < d; i++) {
36  double sigma = sigmas(i);
37 
38  // handle constrained case separately
39  if (sigma == 0.0) {
40  result(i) = 0.0;
41  } else {
42  typedef std::normal_distribution<double> Normal;
43  Normal dist(0.0, sigma);
44  result(i) = dist(generator_);
45  }
46  }
47  return result;
48 }
49 
50 /* ************************************************************************* */
52  assert(model_.get());
53  const Vector& sigmas = model_->sigmas();
54  return sampleDiagonal(sigmas);
55 }
56 
57 /* ************************************************************************* */
58 
59 } // namespace gtsam
std::mt19937_64 generator_
Definition: Sampler.h:37
noiseModel::Diagonal::shared_ptr model_
Definition: Sampler.h:34
noiseModel::Diagonal::shared_ptr model
static const double sigma
Eigen::VectorXd Vector
Definition: Vector.h:38
Values result
sampling from a NoiseModel
boost::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:301
Vector sigmas() const
Definition: Sampler.h:71
traits
Definition: chartTesting.h:28
uint64_t uint_fast64_t
Definition: ms_stdint.h:116
static noiseModel::Diagonal::shared_ptr Diagonal(const Matrix &covariance)
Vector sampleDiagonal(const Vector &sigmas) const
Definition: Sampler.cpp:32
Sampler(const noiseModel::Diagonal::shared_ptr &model, uint_fast64_t seed=42u)
Definition: Sampler.cpp:23
Vector sample() const
sample from distribution
Definition: Sampler.cpp:51


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:53