gtsam  4.0.0
gtsam
HessianFactor.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 #include <gtsam/linear/Scatter.h>
24 #include <gtsam/base/FastVector.h>
25 
26 #include <boost/make_shared.hpp>
27 
28 namespace gtsam {
29 
30  // Forward declarations
31  class Ordering;
32  class JacobianFactor;
33  class HessianFactor;
34  class GaussianConditional;
35  class GaussianBayesNet;
36  class GaussianFactorGraph;
37 
101  class GTSAM_EXPORT HessianFactor : public GaussianFactor {
102  protected:
103 
105 
106  public:
107 
109  typedef HessianFactor This;
110  typedef boost::shared_ptr<This> shared_ptr;
111  typedef SymmetricBlockMatrix::Block Block;
112  typedef SymmetricBlockMatrix::constBlock constBlock;
113 
114 
116  HessianFactor();
117 
123  HessianFactor(Key j, const Matrix& G, const Vector& g, double f);
124 
128  HessianFactor(Key j, const Vector& mu, const Matrix& Sigma);
129 
145  HessianFactor(Key j1, Key j2,
146  const Matrix& G11, const Matrix& G12, const Vector& g1,
147  const Matrix& G22, const Vector& g2, double f);
148 
153  HessianFactor(Key j1, Key j2, Key j3,
154  const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1,
155  const Matrix& G22, const Matrix& G23, const Vector& g2,
156  const Matrix& G33, const Vector& g3, double f);
157 
162  HessianFactor(const KeyVector& js, const std::vector<Matrix>& Gs,
163  const std::vector<Vector>& gs, double f);
164 
167  template<typename KEYS>
168  HessianFactor(const KEYS& keys, const SymmetricBlockMatrix& augmentedInformation);
169 
171  explicit HessianFactor(const JacobianFactor& cg);
172 
175  explicit HessianFactor(const GaussianFactor& factor);
176 
178  explicit HessianFactor(const GaussianFactorGraph& factors,
179  boost::optional<const Scatter&> scatter = boost::none);
180 
182  virtual ~HessianFactor() {}
183 
186  return boost::make_shared<HessianFactor>(*this); }
187 
189  virtual void print(const std::string& s = "",
190  const KeyFormatter& formatter = DefaultKeyFormatter) const;
191 
193  virtual bool equals(const GaussianFactor& lf, double tol = 1e-9) const;
194 
196  virtual double error(const VectorValues& c) const;
203  virtual DenseIndex getDim(const_iterator variable) const {
204  return info_.getDim(std::distance(begin(), variable));
205  }
206 
208  size_t rows() const { return info_.rows(); }
209 
215  virtual GaussianFactor::shared_ptr negate() const;
216 
218  virtual bool empty() const { return size() == 0 /*|| rows() == 0*/; }
219 
223  double constantTerm() const {
224  const auto view = info_.diagonalBlock(size());
225  return view(0, 0);
226  }
227 
231  double& constantTerm() { return info_.diagonalBlock(size())(0, 0); }
232 
237  SymmetricBlockMatrix::constBlock linearTerm(const_iterator j) const {
238  assert(!empty());
239  return info_.aboveDiagonalBlock(j - begin(), size());
240  }
241 
244  SymmetricBlockMatrix::constBlock linearTerm() const {
245  assert(!empty());
246  // get the last column (except the bottom right block)
247  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
248  }
249 
252  SymmetricBlockMatrix::Block linearTerm() {
253  assert(!empty());
254  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
255  }
256 
258  const SymmetricBlockMatrix& info() const { return info_; }
259 
262  SymmetricBlockMatrix& info() { return info_; }
263 
279  virtual Matrix augmentedInformation() const;
280 
282  Eigen::SelfAdjointView<SymmetricBlockMatrix::constBlock, Eigen::Upper> informationView() const;
283 
287  virtual Matrix information() const;
288 
290  virtual VectorValues hessianDiagonal() const;
291 
293  virtual void hessianDiagonal(double* d) const;
294 
296  virtual std::map<Key,Matrix> hessianBlockDiagonal() const;
297 
299  virtual std::pair<Matrix, Vector> jacobian() const;
300 
306  virtual Matrix augmentedJacobian() const;
307 
313  void updateHessian(const KeyVector& keys, SymmetricBlockMatrix* info) const;
314 
318  void updateHessian(HessianFactor* other) const {
319  assert(other);
320  updateHessian(other->keys_, &other->info_);
321  }
322 
324  void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const;
325 
327  VectorValues gradientAtZero() const;
328 
330  virtual void gradientAtZero(double* d) const;
331 
336  Vector gradient(Key key, const VectorValues& x) const;
337 
342  boost::shared_ptr<GaussianConditional> eliminateCholesky(const Ordering& keys);
343 
345  VectorValues solve();
346 
347 
348 #ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V4
349  const SymmetricBlockMatrix& matrixObject() const { return info_; }
353 #endif
354 
355  private:
356 
358  void Allocate(const Scatter& scatter);
359 
361  HessianFactor(const Scatter& scatter);
362 
363  friend class NonlinearFactorGraph;
364  friend class NonlinearClusterTree;
365 
367  friend class boost::serialization::access;
368  template<class ARCHIVE>
369  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
370  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor);
371  ar & BOOST_SERIALIZATION_NVP(info_);
372  }
373  };
374 
391 GTSAM_EXPORT std::pair<boost::shared_ptr<GaussianConditional>, boost::shared_ptr<HessianFactor> >
392  EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
393 
409 GTSAM_EXPORT std::pair<boost::shared_ptr<GaussianConditional>, boost::shared_ptr<GaussianFactor> >
410  EliminatePreferCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
411 
413 template<>
414 struct traits<HessianFactor> : public Testable<HessianFactor> {};
415 
416 } // \ namespace gtsam
417 
418 
SymmetricBlockMatrix::constBlock constBlock
A block from the Hessian matrix (const version)
Definition: HessianFactor.h:112
SymmetricBlockMatrix info_
The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'H[x -1].
Definition: HessianFactor.h:104
SymmetricBlockMatrix::Block Block
A block from the Hessian matrix.
Definition: HessianFactor.h:111
HessianFactor This
Typedef to this class.
Definition: HessianFactor.h:109
DenseIndex getDim(DenseIndex block) const
Number of dimensions for variable on this diagonal block.
Definition: SymmetricBlockMatrix.h:128
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
Definition: SymmetricBlockMatrix.h:155
GaussianFactor Base
Typedef to base class.
Definition: HessianFactor.h:108
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:63
Maps global variable indices to slot indices.
A thin wrapper around std::vector that uses a custom allocator.
void print(const Matrix &A, const string &s, ostream &stream)
print without optional string, must specify cout yourself
Definition: Matrix.cpp:141
virtual bool empty() const
Check if the factor is empty.
Definition: HessianFactor.h:218
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
Definition: HessianFactor.h:258
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:57
DenseIndex rows() const
Row size.
Definition: SymmetricBlockMatrix.h:119
Template to create a binary predicate.
Definition: Testable.h:110
boost::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Definition: HessianFactor.h:110
A helper that implements the traits interface for GTSAM types.
Definition: Testable.h:150
A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e.
Definition: GaussianFactorGraph.h:65
An abstract virtual base class for JacobianFactor and HessianFactor.
Definition: GaussianFactor.h:38
void updateHessian(HessianFactor *other) const
Update another Hessian factor.
Definition: HessianFactor.h:318
virtual ~HessianFactor()
Destructor.
Definition: HessianFactor.h:182
boost::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:33
virtual GaussianFactor::shared_ptr clone() const
Clone this HessianFactor.
Definition: HessianFactor.h:185
Contains the HessianFactor class, a general quadratic factor.
constBlock aboveDiagonalRange(DenseIndex i_startBlock, DenseIndex i_endBlock, DenseIndex j_startBlock, DenseIndex j_endBlock) const
Get a range [i,j) from the matrix. Indices are in block units.
Definition: SymmetricBlockMatrix.h:175
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:73
Access to matrices via blocks of pre-defined sizes.
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:56
virtual DenseIndex getDim(const_iterator variable) const
0.5*[x -1]'H[x -1] (also see constructor documentation)
Definition: HessianFactor.h:203
A manifold defines a space in which there is a notion of a linear tangent space that can be centered ...
Definition: concepts.h:30
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J'th diagonal block as a self adjoint view.
Definition: SymmetricBlockMatrix.h:140
A Gaussian factor in the squared-error form.
Definition: JacobianFactor.h:87
A factor with a quadratic error function - a Gaussian.
Definition: SymmetricBlockMatrix.h:51
SymmetricBlockMatrix::constBlock linearTerm(const_iterator j) const
Return the part of linear term as described above corresponding to the requested variable.
Definition: HessianFactor.h:237
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:72
double & constantTerm()
Return the constant term as described above.
Definition: HessianFactor.h:231
size_t rows() const
Return the number of columns and rows of the Hessian matrix, including the information vector.
Definition: HessianFactor.h:208
SymmetricBlockMatrix & info()
Return non-const information matrix.
Definition: HessianFactor.h:262
SymmetricBlockMatrix::Block linearTerm()
Return the complete linear term as described above.
Definition: HessianFactor.h:252
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:67
Definition: Ordering.h:34
double constantTerm() const
Return the constant term as described above.
Definition: HessianFactor.h:223
SymmetricBlockMatrix::constBlock linearTerm() const
Return the complete linear term as described above.
Definition: HessianFactor.h:244
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:101
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42