GaussianConditional.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 
18 // \callgraph
19 
20 #pragma once
21 
22 #include <boost/utility.hpp>
23 
24 #include <gtsam/global_includes.h>
28 
29 namespace gtsam {
30 
36  class GTSAM_EXPORT GaussianConditional :
37  public JacobianFactor,
38  public Conditional<JacobianFactor, GaussianConditional>
39  {
40  public:
42  typedef boost::shared_ptr<This> shared_ptr;
45 
48 
50  GaussianConditional(Key key, const Vector& d, const Matrix& R,
52 
54  GaussianConditional(Key key, const Vector& d, const Matrix& R,
55  Key name1, const Matrix& S, const SharedDiagonal& sigmas = SharedDiagonal());
56 
58  GaussianConditional(Key key, const Vector& d, const Matrix& R,
59  Key name1, const Matrix& S, Key name2, const Matrix& T,
61 
65  template<typename TERMS>
66  GaussianConditional(const TERMS& terms,
67  size_t nrFrontals, const Vector& d,
69 
74  template<typename KEYS>
76  const KEYS& keys, size_t nrFrontals, const VerticalBlockMatrix& augmentedMatrix,
78 
86  template<typename ITERATOR>
87  static shared_ptr Combine(ITERATOR firstConditional, ITERATOR lastConditional);
88 
90  void print(const std::string& = "GaussianConditional",
91  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
92 
94  bool equals(const GaussianFactor&cg, double tol = 1e-9) const override;
95 
97  constABlock R() const { return Ab_.range(0, nrFrontals()); }
98 
100  constABlock S() const { return Ab_.range(nrFrontals(), size()); }
101 
103  constABlock S(const_iterator it) const { return BaseFactor::getA(it); }
104 
106  const constBVector d() const { return BaseFactor::getb(); }
107 
121  VectorValues solve(const VectorValues& parents) const;
122 
123  VectorValues solveOtherRHS(const VectorValues& parents, const VectorValues& rhs) const;
124 
126  void solveTransposeInPlace(VectorValues& gy) const;
127 
130  void scaleFrontalsBySigma(VectorValues& gy) const;
131 
132  // FIXME: deprecated flag doesn't appear to exist?
133  // __declspec(deprecated) void scaleFrontalsBySigma(VectorValues& gy) const;
134 
135  private:
137  friend class boost::serialization::access;
138  template<class Archive>
139  void serialize(Archive & ar, const unsigned int /*version*/) {
140  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseFactor);
141  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(BaseConditional);
142  }
143  }; // GaussianConditional
144 
146 template<>
147 struct traits<GaussianConditional> : public Testable<GaussianConditional> {};
148 
149 } // \ namespace gtsam
150 
152 
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Base class for conditional densities.
Conditional< BaseFactor, This > BaseConditional
Typedef to our conditional base class.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Rot2 R(Rot2::fromAngle(0.1))
JacobianFactor BaseFactor
Typedef to our factor base class.
Conditional Gaussian Base class.
constABlock S(const_iterator it) const
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
const KeyFormatter & formatter
Included from all GTSAM files.
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
Factor Graph Values.
Eigen::VectorXd Vector
Definition: Vector.h:38
constABlock::ConstColXpr constBVector
Key S(std::uint64_t j)
GaussianConditional This
Typedef to this class.
void serialize(Archive &ar, const unsigned int)
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
Array< double, 1, 3 > e(1./3., 0.5, 2.)
const constBVector d() const
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
const G double tol
Definition: Group.h:83
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
const KeyVector keys
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:05