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 namespace gtsam {
27 
28  // Forward declarations
29  class Ordering;
30  class JacobianFactor;
31  class HessianFactor;
32  class GaussianConditional;
33  class GaussianBayesNet;
34  class GaussianFactorGraph;
35 
99  class GTSAM_EXPORT HessianFactor : public GaussianFactor {
100  protected:
101 
103 
104  public:
105 
107  typedef HessianFactor This;
108  typedef std::shared_ptr<This> shared_ptr;
111 
112 
114  HessianFactor();
115 
121  HessianFactor(Key j, const Matrix& G, const Vector& g, double f);
122 
126  HessianFactor(Key j, const Vector& mu, const Matrix& Sigma);
127 
143  HessianFactor(Key j1, Key j2,
144  const Matrix& G11, const Matrix& G12, const Vector& g1,
145  const Matrix& G22, const Vector& g2, double f);
146 
151  HessianFactor(Key j1, Key j2, Key j3,
152  const Matrix& G11, const Matrix& G12, const Matrix& G13, const Vector& g1,
153  const Matrix& G22, const Matrix& G23, const Vector& g2,
154  const Matrix& G33, const Vector& g3, double f);
155 
160  HessianFactor(const KeyVector& js, const std::vector<Matrix>& Gs,
161  const std::vector<Vector>& gs, double f);
162 
165  template<typename KEYS>
166  HessianFactor(const KEYS& keys, const SymmetricBlockMatrix& augmentedInformation);
167 
169  explicit HessianFactor(const JacobianFactor& cg);
170 
173  explicit HessianFactor(const GaussianFactor& factor);
174 
176  explicit HessianFactor(const GaussianFactorGraph& factors,
177  const Scatter& scatter);
178 
182 
184  ~HessianFactor() override {}
185 
188  return std::make_shared<HessianFactor>(*this); }
189 
191  void print(const std::string& s = "",
192  const KeyFormatter& formatter = DefaultKeyFormatter) const override;
193 
195  bool equals(const GaussianFactor& lf, double tol = 1e-9) const override;
196 
198  using GaussianFactor::error;
199 
204  double error(const VectorValues& c) const override;
205 
211  DenseIndex getDim(const_iterator variable) const override {
212  return info_.getDim(std::distance(begin(), variable));
213  }
214 
216  size_t rows() const { return info_.rows(); }
217 
223  GaussianFactor::shared_ptr negate() const override;
224 
228  double constantTerm() const {
229  const auto view = info_.diagonalBlock(size());
230  return view(0, 0);
231  }
232 
236  double& constantTerm() { return info_.diagonalBlock(size())(0, 0); }
237 
243 #ifndef NDEBUG
244  if(empty()) throw;
245 #endif
246  return info_.aboveDiagonalBlock(j - begin(), size());
247  }
248 
252 #ifndef NDEBUG
253  if(empty()) throw;
254 #endif
255  // get the last column (except the bottom right block)
256  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
257  }
258 
262 #ifndef NDEBUG
263  if(empty()) throw;
264 #endif
265  return info_.aboveDiagonalRange(0, size(), size(), size() + 1);
266  }
267 
269  const SymmetricBlockMatrix& info() const { return info_; }
270 
273  SymmetricBlockMatrix& info() { return info_; }
274 
290  Matrix augmentedInformation() const override;
291 
294 
298  Matrix information() const override;
299 
301  void hessianDiagonalAdd(VectorValues& d) const override;
302 
304  using Base::hessianDiagonal;
305 
307  void hessianDiagonal(double* d) const override;
308 
310  std::map<Key,Matrix> hessianBlockDiagonal() const override;
311 
313  std::pair<Matrix, Vector> jacobian() const override;
314 
320  Matrix augmentedJacobian() const override;
321 
327  void updateHessian(const KeyVector& keys, SymmetricBlockMatrix* info) const override;
328 
333 #ifndef NDEBUG
334  if(!other) throw;
335 #endif
336  updateHessian(other->keys_, &other->info_);
337  }
338 
340  void multiplyHessianAdd(double alpha, const VectorValues& x, VectorValues& y) const override;
341 
343  VectorValues gradientAtZero() const override;
344 
346  void gradientAtZero(double* d) const override;
347 
352  Vector gradient(Key key, const VectorValues& x) const override;
353 
358  std::shared_ptr<GaussianConditional> eliminateCholesky(const Ordering& keys);
359 
361  VectorValues solve();
362 
363  private:
365  void Allocate(const Scatter& scatter);
366 
368  HessianFactor(const Scatter& scatter);
369 
370  friend class NonlinearFactorGraph;
371  friend class NonlinearClusterTree;
372 
373 #ifdef GTSAM_ENABLE_BOOST_SERIALIZATION
374 
375  friend class boost::serialization::access;
376  template<class ARCHIVE>
377  void serialize(ARCHIVE & ar, const unsigned int /*version*/) {
378  ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(GaussianFactor);
379  ar & BOOST_SERIALIZATION_NVP(info_);
380  }
381 #endif
382  };
383 
400 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<HessianFactor> >
401  EliminateCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
402 
418 GTSAM_EXPORT std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<GaussianFactor> >
419  EliminatePreferCholesky(const GaussianFactorGraph& factors, const Ordering& keys);
420 
422 template<>
423 struct traits<HessianFactor> : public Testable<HessianFactor> {};
424 
425 } // \ namespace gtsam
426 
427 
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:99
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:236
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:332
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:106
gtsam::HessianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
A shared_ptr to this class.
Definition: HessianFactor.h:108
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:273
gtsam::HessianFactor::info
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
Definition: HessianFactor.h:269
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
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:187
pruning_fixture::factor
DecisionTreeFactor factor(D &C &B &A, "0.0 0.0 0.0 0.60658897 0.61241912 0.61241969 0.61247685 0.61247742 0.0 " "0.0 0.0 0.99995287 1.0 1.0 1.0 1.0")
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:541
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:102
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:156
GaussianConditional
gtsam::HessianFactor::constBlock
SymmetricBlockMatrix::constBlock constBlock
A block from the Hessian matrix (const version)
Definition: HessianFactor.h:110
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:251
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:107
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:184
empty
Definition: test_copy_move.cpp:19
gtsam::HessianFactor::linearTerm
SymmetricBlockMatrix::constBlock linearTerm(const_iterator j) const
Definition: HessianFactor.h:242
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:261
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:216
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::HessianFactor::constantTerm
double constantTerm() const
Definition: HessianFactor.h:228
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:109
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:518
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:211
Scatter.h
Maps global variable indices to slot indices.
gtsam::HessianFactor::HessianFactor
HessianFactor(const GaussianFactorGraph &factors)
Definition: HessianFactor.h:180
pybind_wrapper_test_script.other
other
Definition: pybind_wrapper_test_script.py:42


gtsam
Author(s):
autogenerated on Sun Dec 22 2024 04:11:39