Sampler.h
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 #pragma once
20 
22 
23 #include <random>
24 
25 namespace gtsam {
26 
31 class GTSAM_EXPORT Sampler {
32  protected:
35 
37  mutable std::mt19937_64 generator_;
38 
39  public:
40  typedef std::shared_ptr<Sampler> shared_ptr;
41 
44 
52  uint_fast64_t seed = 42u);
53 
60  explicit Sampler(const Vector& sigmas, uint_fast64_t seed = 42u);
61 
65 
66  size_t dim() const { return model_->dim(); }
67 
68  Vector sigmas() const { return model_->sigmas(); }
69 
70  const noiseModel::Diagonal::shared_ptr& model() const { return model_; }
71 
75 
77  Vector sample() const;
78 
80  static Vector sampleDiagonal(const Vector& sigmas, std::mt19937_64* rng);
82 
83  protected:
85  Vector sampleDiagonal(const Vector& sigmas) const;
86 };
87 
88 } // namespace gtsam
rng
static std::mt19937 rng
Definition: timeFactorOverhead.cpp:31
gtsam::Sampler::sigmas
Vector sigmas() const
Definition: Sampler.h:68
gtsam::Sampler::model
const noiseModel::Diagonal::shared_ptr & model() const
Definition: Sampler.h:70
gtsam::Sampler::shared_ptr
std::shared_ptr< Sampler > shared_ptr
Definition: Sampler.h:40
gtsam::Sampler::model_
noiseModel::Diagonal::shared_ptr model_
Definition: Sampler.h:34
gtsam::Sampler::dim
size_t dim() const
Definition: Sampler.h:66
uint_fast64_t
uint64_t uint_fast64_t
Definition: ms_stdint.h:116
gtsam::Sampler::generator_
std::mt19937_64 generator_
Definition: Sampler.h:37
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
exampleQR::sigmas
Vector sigmas
Definition: testNoiseModel.cpp:212
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
gtsam
traits
Definition: chartTesting.h:28
NoiseModel.h
gtsam::noiseModel::Diagonal::shared_ptr
std::shared_ptr< Diagonal > shared_ptr
Definition: NoiseModel.h:307
gtsam::Sampler
Definition: Sampler.h:31


gtsam
Author(s):
autogenerated on Tue Jun 25 2024 03:02:33