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 
27 namespace gtsam {
28 
29  // Forward declarations
30  class Ordering;
31  class JacobianFactor;
32  class HessianFactor;
33  class GaussianConditional;
34  class GaussianBayesNet;
35  class GaussianFactorGraph;
36 
100  class GTSAM_EXPORT HessianFactor : public GaussianFactor {
101  protected:
102 
104 
105  public:
106 
108  typedef HessianFactor This;
109  typedef std::shared_ptr<This> shared_ptr;
112 
113 
115  HessianFactor();
116 
122  HessianFactor(Key j, const Matrix& G, const Vector& g, double f);
123 
127  HessianFactor(Key j, const Vector& mu, const Matrix& Sigma);
128 
144  HessianFactor(Key j1, Key j2,
145  const Matrix& G11, const Matrix& G12, const Vector& g1,
146  const Matrix& G22, const Vector& g2, double f);
147 
152  HessianFactor(Key j1, Key j2, Key j3,
153  const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1,
154  const Matrix& G22, const Matrix& G23, const Vector& g2,
155  const Matrix& G33, const Vector& g3, double f);
156 
161  HessianFactor(const KeyVector& js, const std::vector<Matrix>& Gs,
162  const std::vector<Vector>& gs, double f);
163 
166  template<typename KEYS>
167  HessianFactor(const KEYS& keys, const SymmetricBlockMatrix& augmentedInformation);
168 
170  explicit HessianFactor(const JacobianFactor& cg);
171 
174  explicit HessianFactor(const GaussianFactor& factor);
175 
177  explicit HessianFactor(const GaussianFactorGraph& factors,
178  const Scatter& scatter);
179 
183 
185  ~HessianFactor() override {}
186 
189  return std::make_shared<HessianFactor>(*this); }
190 
192  void print(const std::string& s = "",
193  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
194 
196  bool equals(const GaussianFactor& lf, double tol = 1e-9) const override;
197 
199  using GaussianFactor::error;
200 
205  double error(const VectorValues& c) const override;
206 
212  DenseIndex getDim(const_iterator variable) const override {
213  return info_.getDim(std::distance(begin(), variable));
214  }
215 
217  size_t rows() const { return info_.rows(); }
218 
224  GaussianFactor::shared_ptr negate() const override;
225 
229  double constantTerm() const {
230  const auto view = info_.diagonalBlock(size());
231  return view(0, 0);
232  }
233 
237  double& constantTerm() { return info_.diagonalBlock(size())(0, 0); }
238 
244  assert(!empty());
245  return info_.aboveDiagonalBlock(j - begin(), size());
246  }
247 
251  assert(!empty());
252  // get the last column (except the bottom right block)
253  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
254  }
255 
259  assert(!empty());
260  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
261  }
262 
264  const SymmetricBlockMatrix& info() const { return info_; }
265 
268  SymmetricBlockMatrix& info() { return info_; }
269 
285  Matrix augmentedInformation() const override;
286 
289 
293  Matrix information() const override;
294 
296  void hessianDiagonalAdd(VectorValues& d) const override;
297 
299  using Base::hessianDiagonal;
300 
302  void hessianDiagonal(double* d) const override;
303 
305  std::map<Key,Matrix> hessianBlockDiagonal() const override;
306 
308  std::pair<Matrix, Vector> jacobian() const override;
309 
315  Matrix augmentedJacobian() const override;
316 
322  void updateHessian(const KeyVector& keys, SymmetricBlockMatrix* info) const override;
323 
328  assert(other);
329  updateHessian(other->keys_, &other->info_);
330  }
331 
333  void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const override;
334 
336  VectorValues gradientAtZero() const override;
337 
339  void gradientAtZero(double* d) const override;
340 
345  Vector gradient(Key key, const VectorValues& x) const override;
346 
351  std::shared_ptr<GaussianConditional> eliminateCholesky(const Ordering& keys);
352 
354  VectorValues solve();
355 
356  private:
358  void Allocate(const Scatter& scatter);
359 
361  HessianFactor(const Scatter& scatter);
362 
363  friend class NonlinearFactorGraph;
364  friend class NonlinearClusterTree;
365 
366 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
367 
368  friend class boost::serialization::access;
369  template<class ARCHIVE>
370  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
371  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor);
372  ar & BOOST_SERIALIZATION_NVP(info_);
373  }
374 #endif
375  };
376 
393 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<HessianFactor> >
394  EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
395 
411 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<GaussianFactor> >
412  EliminatePreferCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
413 
415 template<>
416 struct traits<HessianFactor> : public Testable<HessianFactor> {};
417 
418 } // \ namespace gtsam
419 
420 
gtsam::GaussianFactor::error
virtual double error(const VectorValues &c) const
Definition: GaussianFactor.cpp:27
Eigen::Block
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
HessianFactor-inl.h
Contains the HessianFactor class, a general quadratic factor.
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
FastVector.h
A thin wrapper around std::vector that uses a custom allocator.
gtsam::HessianFactor
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:100
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
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
g1
Pose3 g1(Rot3(), Point3(100.0, 0.0, 300.0))
mu
double mu
Definition: testBoundingConstraint.cpp:37
gtsam::HessianFactor::constantTerm
double & constantTerm()
Definition: HessianFactor.h:237
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
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::NonlinearClusterTree
Definition: NonlinearClusterTree.h:14
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::HessianFactor::updateHessian
void updateHessian(HessianFactor *other) const
Definition: HessianFactor.h:327
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::HessianFactor::Base
GaussianFactor Base
Typedef to base class.
Definition: HessianFactor.h:107
gtsam::HessianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Definition: HessianFactor.h:109
Eigen::SelfAdjointView
Expression of a selfadjoint matrix from a triangular part of a dense matrix.
Definition: SelfAdjointView.h:49
gtsam::HessianFactor::info
SymmetricBlockMatrix & info()
Definition: HessianFactor.h:268
gtsam::HessianFactor::info
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
Definition: HessianFactor.h:264
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:38
gtsam::SymmetricBlockMatrix::aboveDiagonalRange
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:172
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::HessianFactor::clone
GaussianFactor::shared_ptr clone() const override
Definition: HessianFactor.h:188
size
Scalar Scalar int size
Definition: benchVecAdd.cpp:17
gtsam::EliminatePreferCholesky
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: HessianFactor.cpp:540
view
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 y set format x g set format y g set format x2 g set format y2 g set format z g set angles radians set nogrid set key title set key left top Right noreverse box linetype linewidth samplen spacing width set nolabel set noarrow set nologscale set logscale x set set pointsize set encoding default set nopolar set noparametric set view
Definition: gnuplot_common_settings.hh:27
gtsam::HessianFactor::info_
SymmetricBlockMatrix info_
The full augmented information matrix, s.t. the quadratic error is 0.5*[x -1]'H[x -1].
Definition: HessianFactor.h:103
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
GaussianConditional
gtsam::HessianFactor::constBlock
SymmetricBlockMatrix::constBlock constBlock
A block from the Hessian matrix (const version)
Definition: HessianFactor.h:111
gtsam::VectorValues
Definition: VectorValues.h:74
Eigen::internal::negate
T negate(const T &x)
Definition: packetmath_test_shared.h:24
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::HessianFactor::linearTerm
SymmetricBlockMatrix::constBlock linearTerm() const
Definition: HessianFactor.h:250
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
g2
Pose3 g2(g1.expmap(h *V1_g1))
gtsam::HessianFactor::This
HessianFactor This
Typedef to this class.
Definition: HessianFactor.h:108
SymmetricBlockMatrix.h
Access to matrices via blocks of pre-defined sizes. Used in GaussianFactor and GaussianConditional.
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
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::Scatter
Definition: Scatter.h:49
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
gtsam::SymmetricBlockMatrix::rows
DenseIndex rows() const
Row size.
Definition: SymmetricBlockMatrix.h:116
gtsam::equals
Definition: Testable.h:112
y
Scalar * y
Definition: level1_cplx_impl.h:124
key
const gtsam::Symbol key('X', 0)
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::Factor::const_iterator
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:83
gtsam::HessianFactor::~HessianFactor
~HessianFactor() override
Definition: HessianFactor.h:185
empty
Definition: test_copy_move.cpp:19
gtsam::HessianFactor::linearTerm
SymmetricBlockMatrix::constBlock linearTerm(const_iterator j) const
Definition: HessianFactor.h:243
gtsam
traits
Definition: SFMdata.h:40
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
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
gtsam::HessianFactor::linearTerm
SymmetricBlockMatrix::Block linearTerm()
Definition: HessianFactor.h:258
gtsam::SymmetricBlockMatrix::diagonalBlock
Eigen::SelfAdjointView< Block, Eigen::Upper > diagonalBlock(DenseIndex J)
Return the J'th diagonal block as a self adjoint view.
Definition: SymmetricBlockMatrix.h:137
JacobianFactor
gtsam::HessianFactor::rows
size_t rows() const
Definition: HessianFactor.h:217
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::HessianFactor::constantTerm
double constantTerm() const
Definition: HessianFactor.h:229
gtsam::SymmetricBlockMatrix::getDim
DenseIndex getDim(DenseIndex block) const
Number of dimensions for variable on this diagonal block.
Definition: SymmetricBlockMatrix.h:125
gtsam::distance
Double_ distance(const OrientedPlane3_ &p)
Definition: slam/expressions.h:117
GaussianFactor.h
A factor with a quadratic error function - a Gaussian.
gtsam::HessianFactor::Block
SymmetricBlockMatrix::Block Block
A block from the Hessian matrix.
Definition: HessianFactor.h:110
gtsam::SymmetricBlockMatrix::aboveDiagonalBlock
constBlock aboveDiagonalBlock(DenseIndex I, DenseIndex J) const
Get block above the diagonal (I, J).
Definition: SymmetricBlockMatrix.h:152
gtsam::EliminateCholesky
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< HessianFactor > > EliminateCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: HessianFactor.cpp:517
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53
gtsam::Ordering
Definition: inference/Ordering.h:33
j1
double j1(double x)
Definition: j1.c:174
gtsam::HessianFactor::getDim
DenseIndex getDim(const_iterator variable) const override
Definition: HessianFactor.h:212
Scatter.h
Maps global variable indices to slot indices.
gtsam::HessianFactor::HessianFactor
HessianFactor(const GaussianFactorGraph &factors)
Definition: HessianFactor.h:181
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:24