GaussianFactor.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 
23 #include <gtsam/inference/Factor.h>
24 #include <gtsam/base/Matrix.h>
25 #include <gtsam/base/Testable.h>
26 
27 namespace gtsam {
28 
29  // Forward declarations
30  class VectorValues;
31  class Scatter;
32  class SymmetricBlockMatrix;
33 
38  class GTSAM_EXPORT GaussianFactor : public Factor
39  {
40  public:
41  typedef GaussianFactor This;
42  typedef std::shared_ptr<This> shared_ptr;
43  typedef Factor Base;
44 
47 
50 
53  template<typename CONTAINER>
54  GaussianFactor(const CONTAINER& keys) : Base(keys) {}
55 
59 
61  void print(
62  const std::string& s = "",
63  const KeyFormatter& formatter = DefaultKeyFormatter) const override = 0;
64 
66  virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const = 0;
67 
71 
79  virtual double error(const VectorValues& c) const;
80 
85  double error(const HybridValues& c) const override;
86 
88  virtual DenseIndex getDim(const_iterator variable) const = 0;
89 
97  virtual Matrix augmentedJacobian() const = 0;
98 
106  virtual std::pair<Matrix,Vector> jacobian() const = 0;
107 
116  virtual Matrix augmentedInformation() const = 0;
117 
121  virtual Matrix information() const = 0;
122 
124  VectorValues hessianDiagonal() const;
125 
127  virtual void hessianDiagonalAdd(VectorValues& d) const = 0;
128 
130  virtual void hessianDiagonal(double* d) const = 0;
131 
133  virtual std::map<Key,Matrix> hessianBlockDiagonal() const = 0;
134 
136  virtual GaussianFactor::shared_ptr clone() const = 0;
137 
143  virtual GaussianFactor::shared_ptr negate() const = 0;
144 
150  virtual void updateHessian(const KeyVector& keys,
151  SymmetricBlockMatrix* info) const = 0;
152 
156 
158  virtual void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const = 0;
159 
161  virtual VectorValues gradientAtZero() const = 0;
162 
164  virtual void gradientAtZero(double* d) const = 0;
165 
167  virtual Vector gradient(Key key, const VectorValues& x) const = 0;
168 
172 
173  // Determine position of a given key
174  template <typename CONTAINER>
175  static DenseIndex Slot(const CONTAINER& keys, Key key) {
176  return std::find(keys.begin(), keys.end(), key) - keys.begin();
177  }
178 
180 
181  private:
182 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
183 
184  friend class boost::serialization::access;
185  template<class ARCHIVE>
186  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
187  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
188  }
189 #endif
190  }; // GaussianFactor
191 
193 template<>
194 struct traits<GaussianFactor> : public Testable<GaussianFactor> {
195 };
196 
197 } // \ namespace gtsam
VectorValues
gtsam::HybridValues
Definition: HybridValues.h:38
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
Testable.h
Concept check for values that can be used in unit tests.
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::GaussianFactor::This
GaussianFactor This
This class.
Definition: GaussianFactor.h:41
Matrix.h
typedef and functions to augment Eigen's MatrixXd
x
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
Definition: gnuplot_common_settings.hh:12
gtsam::GaussianFactor::GaussianFactor
GaussianFactor()
Definition: GaussianFactor.h:49
gtsam::GaussianFactor
Definition: GaussianFactor.h:38
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::Factor
Definition: Factor.h:69
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
Factor.h
The base class for all factors.
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::VectorValues
Definition: VectorValues.h:74
Eigen::internal::negate
T negate(const T &x)
Definition: packetmath_test_shared.h:24
gtsam::KeyFormatter
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
gtsam::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
gtsam::equals
Definition: Testable.h:112
y
Scalar * y
Definition: level1_cplx_impl.h:124
key
const gtsam::Symbol key('X', 0)
gtsam
traits
Definition: chartTesting.h:28
gtsam::Testable
Definition: Testable.h:152
error
static double error
Definition: testRot3.cpp:37
gtsam::traits
Definition: Group.h:36
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::GaussianFactor::Base
Factor Base
Our base class.
Definition: GaussianFactor.h:43
gtsam::GaussianFactor::Slot
static DenseIndex Slot(const CONTAINER &keys, Key key)
Definition: GaussianFactor.h:175
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::GaussianFactor::GaussianFactor
GaussianFactor(const CONTAINER &keys)
Definition: GaussianFactor.h:54
Base
Definition: test_virtual_functions.cpp:156
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:02:23