GaussianBayesNet.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 // \callgraph
20 
21 #pragma once
22 
26 #include <gtsam/global_includes.h>
27 
28 #include <utility>
29 namespace gtsam {
30 
35  class GTSAM_EXPORT GaussianBayesNet: public BayesNet<GaussianConditional>
36  {
37  public:
38 
42  typedef std::shared_ptr<This> shared_ptr;
43  typedef std::shared_ptr<ConditionalType> sharedConditional;
44 
47 
50 
52  template <typename ITERATOR>
53  GaussianBayesNet(ITERATOR firstConditional, ITERATOR lastConditional)
54  : Base(firstConditional, lastConditional) {}
55 
57  template <class CONTAINER>
58  explicit GaussianBayesNet(const CONTAINER& conditionals) {
59  push_back(conditionals);
60  }
61 
64  template <class DERIVEDCONDITIONAL>
66  : Base(graph) {}
67 
72  template <class DERIVEDCONDITIONAL>
74  std::initializer_list<std::shared_ptr<DERIVEDCONDITIONAL> > conditionals)
75  : Base(conditionals) {}
76 
78 
81 
83  bool equals(const This& bn, double tol = 1e-9) const;
84 
86  void print(
87  const std::string& s = "",
88  const KeyFormatter& formatter = DefaultKeyFormatter) const override {
90  }
91 
93 
96 
98  double error(const VectorValues& x) const;
99 
101  double logProbability(const VectorValues& x) const;
102 
108  double evaluate(const VectorValues& x) const;
109 
111  double operator()(const VectorValues& x) const {
112  return evaluate(x);
113  }
114 
117  VectorValues optimize() const;
118 
120  VectorValues optimize(const VectorValues& given) const;
121 
128  VectorValues sample(std::mt19937_64* rng) const;
129 
137  VectorValues sample(const VectorValues& given, std::mt19937_64* rng) const;
138 
140  VectorValues sample() const;
141 
143  VectorValues sample(const VectorValues& given) const;
144 
151  Ordering ordering() const;
152 
154 
157 
163  std::pair<Matrix, Vector> matrix(const Ordering& ordering) const;
164 
170  std::pair<Matrix, Vector> matrix() const;
171 
197  VectorValues optimizeGradientSearch() const;
198 
204  VectorValues gradient(const VectorValues& x0) const;
205 
212  VectorValues gradientAtZero() const;
213 
221  double determinant() const;
222 
229  double logDeterminant() const;
230 
235  VectorValues backSubstitute(const VectorValues& gx) const;
236 
243  VectorValues backSubstituteTranspose(const VectorValues& gx) const;
244 
248 
249  using Base::evaluate; // Expose evaluate(const HybridValues&) method..
250  using Base::logProbability; // Expose logProbability(const HybridValues&) method..
251  using Base::error; // Expose error(const HybridValues&) method..
252 
254 
255  private:
256 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
257 
258  friend class boost::serialization::access;
259  template<class ARCHIVE>
260  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
261  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
262  }
263 #endif
264  };
265 
267  template<>
268  struct traits<GaussianBayesNet> : public Testable<GaussianBayesNet> {
269  };
270 
271 } //\ namespace gtsam
BayesNet< GaussianConditional > Base
std::string serialize(const T &input)
serializes to a string
void determinant(const MatrixType &m)
Definition: determinant.cpp:14
double logDeterminant(const typename BAYESTREE::sharedClique &clique)
static std::mt19937 rng
GaussianConditional ConditionalType
GaussianBayesNet(const CONTAINER &conditionals)
EIGEN_STRONG_INLINE Packet4f print(const Packet4f &a)
NonlinearFactorGraph graph
Bayes network.
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
static enum @1107 ordering
const KeyFormatter & formatter
Included from all GTSAM files.
std::shared_ptr< ConditionalType > sharedConditional
std::shared_ptr< This > shared_ptr
GaussianBayesNet(ITERATOR firstConditional, ITERATOR lastConditional)
double operator()(const VectorValues &x) const
Evaluate probability density, sugar.
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
Conditional Gaussian Base class.
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print graph
traits
Definition: chartTesting.h:28
static Symbol x0('x', 0)
GaussianBayesNet(const FactorGraph< DERIVEDCONDITIONAL > &graph)
Factor Graph Base Class.
static double error
Definition: testRot3.cpp:37
const std::vector< GaussianConditional::shared_ptr > conditionals
const G double tol
Definition: Group.h:86
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
GaussianBayesNet(std::initializer_list< std::shared_ptr< DERIVEDCONDITIONAL > > conditionals)


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:15