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 boost::shared_ptr<This> shared_ptr;
43  typedef Factor Base;
44 
47 
50  template<typename CONTAINER>
51  GaussianFactor(const CONTAINER& keys) : Base(keys) {}
52 
54  virtual ~GaussianFactor() {}
55 
56  // Implementing Testable interface
57 
59  void print(
60  const std::string& s = "",
61  const KeyFormatter& formatter = DefaultKeyFormatter) const override = 0;
62 
64  virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const = 0;
65 
67  virtual double error(const VectorValues& c) const = 0;
70  virtual DenseIndex getDim(const_iterator variable) const = 0;
71 
79  virtual Matrix augmentedJacobian() const = 0;
80 
88  virtual std::pair<Matrix,Vector> jacobian() const = 0;
89 
98  virtual Matrix augmentedInformation() const = 0;
99 
103  virtual Matrix information() const = 0;
104 
106  VectorValues hessianDiagonal() const;
107 
109  virtual void hessianDiagonalAdd(VectorValues& d) const = 0;
110 
112  virtual void hessianDiagonal(double* d) const = 0;
113 
115  virtual std::map<Key,Matrix> hessianBlockDiagonal() const = 0;
116 
118  virtual GaussianFactor::shared_ptr clone() const = 0;
119 
121  virtual bool empty() const = 0;
122 
128  virtual GaussianFactor::shared_ptr negate() const = 0;
129 
135  virtual void updateHessian(const KeyVector& keys,
136  SymmetricBlockMatrix* info) const = 0;
137 
139  virtual void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const = 0;
140 
142  virtual VectorValues gradientAtZero() const = 0;
143 
145  virtual void gradientAtZero(double* d) const = 0;
146 
148  virtual Vector gradient(Key key, const VectorValues& x) const = 0;
149 
150  // Determine position of a given key
151  template <typename CONTAINER>
152  static DenseIndex Slot(const CONTAINER& keys, Key key) {
153  return std::find(keys.begin(), keys.end(), key) - keys.begin();
154  }
155 
156  private:
158  friend class boost::serialization::access;
159  template<class ARCHIVE>
160  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
161  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Base);
162  }
163 
164  }; // GaussianFactor
165 
167 template<>
168 struct traits<GaussianFactor> : public Testable<GaussianFactor> {
169 };
170 
171 } // \ namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
Scalar * y
Concept check for values that can be used in unit tests.
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
void serialize(ARCHIVE &ar, const unsigned int)
GaussianFactor This
This class.
static const KeyFormatter DefaultKeyFormatter
Definition: Key.h:43
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:67
const KeyFormatter & formatter
else if n * info
T negate(const T &x)
Definition: packetmath.cpp:27
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
Eigen::VectorXd Vector
Definition: Vector.h:38
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
RealScalar alpha
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
traits
Definition: chartTesting.h:28
GaussianFactor(const CONTAINER &keys)
Factor Base
Our base class.
static double error
Definition: testRot3.cpp:39
const G double tol
Definition: Group.h:83
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
const KeyVector keys
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
static DenseIndex Slot(const CONTAINER &keys, Key key)
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
The base class for all factors.


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