HessianFactor.cpp
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 
25 #include <gtsam/base/cholesky.h>
26 #include <gtsam/base/debug.h>
27 #include <gtsam/base/FastMap.h>
28 #include <gtsam/base/Vector.h>
29 #include <gtsam/base/Matrix.h>
31 #include <gtsam/base/timing.h>
32 
33 #include <sstream>
34 #include <cassert>
35 #include <limits>
36 
37 using namespace std;
38 
39 namespace gtsam {
40 
41 // Typedefs used in constructors below.
42 using Dims = std::vector<Key>;
43 
44 /* ************************************************************************* */
45 void HessianFactor::Allocate(const Scatter& scatter) {
46  gttic(HessianFactor_Allocate);
47 
48  // Allocate with dimensions for each variable plus 1 at the end for the information vector
49  const size_t n = scatter.size();
50  keys_.resize(n);
51  FastVector<DenseIndex> dims(n + 1);
52  DenseIndex slot = 0;
53  for(const SlotEntry& slotentry: scatter) {
54  keys_[slot] = slotentry.key;
55  dims[slot] = slotentry.dimension;
56  ++slot;
57  }
58  dims.back() = 1;
59  info_ = SymmetricBlockMatrix(dims);
60 }
61 
62 /* ************************************************************************* */
63 HessianFactor::HessianFactor(const Scatter& scatter) {
64  Allocate(scatter);
65 }
66 
67 /* ************************************************************************* */
68 HessianFactor::HessianFactor() :
69  info_(Dims{1}) {
70  assert(info_.rows() == 1);
71  constantTerm() = 0.0;
72 }
73 
74 /* ************************************************************************* */
75 HessianFactor::HessianFactor(Key j, const Matrix& G, const Vector& g, double f)
76  : GaussianFactor(KeyVector{j}), info_(Dims{static_cast<Key>(G.cols()), 1}) {
77  if (G.rows() != G.cols() || G.rows() != g.size())
78  throw invalid_argument(
79  "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
80  info_.setDiagonalBlock(0, G);
81  linearTerm() = g;
82  constantTerm() = f;
83 }
84 
85 /* ************************************************************************* */
86 // error is 0.5*(x-mu)'*inv(Sigma)*(x-mu) = 0.5*(x'*G*x - 2*x'*G*mu + mu'*G*mu)
87 // where G = inv(Sigma), g = G*mu, f = mu'*G*mu = mu'*g
89  : GaussianFactor(KeyVector{j}), info_(Dims{static_cast<Key>(Sigma.cols()), 1}) {
90  if (Sigma.rows() != Sigma.cols() || Sigma.rows() != mu.size())
91  throw invalid_argument(
92  "Attempting to construct HessianFactor with inconsistent matrix and/or vector dimensions");
93  info_.setDiagonalBlock(0, Sigma.inverse()); // G
94  linearTerm() = info_.diagonalBlock(0) * mu; // g
95  constantTerm() = mu.dot(linearTerm().col(0)); // f
96 }
97 
98 /* ************************************************************************* */
100  const Matrix& G12, const Vector& g1, const Matrix& G22, const Vector& g2,
101  double f) :
102  GaussianFactor(KeyVector{j1,j2}), info_(
103  Dims{static_cast<Key>(G11.cols()),static_cast<Key>(G22.cols()),1}) {
104  info_.setDiagonalBlock(0, G11);
105  info_.setOffDiagonalBlock(0, 1, G12);
106  info_.setDiagonalBlock(1, G22);
107  linearTerm() << g1, g2;
108  constantTerm() = f;
109 }
110 
111 /* ************************************************************************* */
113  const Matrix& G12, const Matrix& G13, const Vector& g1, const Matrix& G22,
114  const Matrix& G23, const Vector& g2, const Matrix& G33, const Vector& g3,
115  double f) :
116  GaussianFactor(KeyVector{j1,j2,j3}), info_(
117  Dims{static_cast<Key>(G11.cols()),static_cast<Key>(G22.cols()),static_cast<Key>(G33.cols()),1}) {
118  if (G11.rows() != G11.cols() || G11.rows() != G12.rows()
119  || G11.rows() != G13.rows() || G11.rows() != g1.size()
120  || G22.cols() != G12.cols() || G33.cols() != G13.cols()
121  || G22.cols() != g2.size() || G33.cols() != g3.size())
122  throw invalid_argument(
123  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
124  info_.setDiagonalBlock(0, G11);
125  info_.setOffDiagonalBlock(0, 1, G12);
126  info_.setOffDiagonalBlock(0, 2, G13);
127  info_.setDiagonalBlock(1, G22);
128  info_.setOffDiagonalBlock(1, 2, G23);
129  info_.setDiagonalBlock(2, G33);
130  linearTerm() << g1, g2, g3;
131  constantTerm() = f;
132 }
133 
134 /* ************************************************************************* */
135 namespace {
136 static std::vector<DenseIndex> _getSizeHFVec(const std::vector<Vector>& m) {
137  std::vector<DenseIndex> dims;
138  for (const Vector& v : m) {
139  dims.push_back(v.size());
140  }
141  return dims;
142 }
143 } // namespace
144 
145 /* ************************************************************************* */
147  const std::vector<Matrix>& Gs, const std::vector<Vector>& gs, double f) :
148  GaussianFactor(js), info_(_getSizeHFVec(gs), true) {
149  // Get the number of variables
150  size_t variable_count = js.size();
151 
152  // Verify the provided number of entries in the vectors are consistent
153  if (gs.size() != variable_count
154  || Gs.size() != (variable_count * (variable_count + 1)) / 2)
155  throw invalid_argument(
156  "Inconsistent number of entries between js, Gs, and gs in HessianFactor constructor.\nThe number of keys provided \
157  in js must match the number of linear vector pieces in gs. The number of upper-diagonal blocks in Gs must be n*(n+1)/2");
158 
159  // Verify the dimensions of each provided matrix are consistent
160  // Note: equations for calculating the indices derived from the "sum of an arithmetic sequence" formula
161  for (size_t i = 0; i < variable_count; ++i) {
162  DenseIndex block_size = gs[i].size();
163  // Check rows
164  for (size_t j = 0; j < variable_count - i; ++j) {
165  size_t index = i * (2 * variable_count - i + 1) / 2 + j;
166  if (Gs[index].rows() != block_size) {
167  throw invalid_argument(
168  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
169  }
170  }
171  // Check cols
172  for (size_t j = 0; j <= i; ++j) {
173  size_t index = j * (2 * variable_count - j + 1) / 2 + (i - j);
174  if (Gs[index].cols() != block_size) {
175  throw invalid_argument(
176  "Inconsistent matrix and/or vector dimensions in HessianFactor constructor");
177  }
178  }
179  }
180 
181  // Fill in the blocks
182  size_t index = 0;
183  for (size_t i = 0; i < variable_count; ++i) {
184  for (size_t j = i; j < variable_count; ++j) {
185  if (i == j) {
186  info_.setDiagonalBlock(i, Gs[index]);
187  } else {
188  info_.setOffDiagonalBlock(i, j, Gs[index]);
189  }
190  index++;
191  }
192  info_.setOffDiagonalBlock(i, variable_count, gs[i]);
193  }
194  constantTerm() = f;
195 }
196 
197 /* ************************************************************************* */
198 namespace {
199 void _FromJacobianHelper(const JacobianFactor& jf, SymmetricBlockMatrix& info) {
200  gttic(HessianFactor_fromJacobian);
201  const SharedDiagonal& jfModel = jf.get_model();
202  auto A = jf.matrixObject().full();
203  if (jfModel) {
204  if (jf.get_model()->isConstrained())
205  throw invalid_argument(
206  "Cannot construct HessianFactor from JacobianFactor with constrained noise model");
207 
208  auto D = (jfModel->invsigmas().array() * jfModel->invsigmas().array()).matrix().asDiagonal();
209 
210  info.setFullMatrix(A.transpose() * D * A);
211  } else {
212  info.setFullMatrix(A.transpose() * A);
213  }
214 }
215 }
216 
217 /* ************************************************************************* */
219  GaussianFactor(jf), info_(
220  SymmetricBlockMatrix::LikeActiveViewOf(jf.matrixObject())) {
221  _FromJacobianHelper(jf, info_);
222 }
223 
224 /* ************************************************************************* */
226  GaussianFactor(gf) {
227  // Copy the matrix data depending on what type of factor we're copying from
228  if (const JacobianFactor* jf = dynamic_cast<const JacobianFactor*>(&gf)) {
230  _FromJacobianHelper(*jf, info_);
231  } else if (const HessianFactor* hf = dynamic_cast<const HessianFactor*>(&gf)) {
232  info_ = hf->info_;
233  } else {
234  throw std::invalid_argument(
235  "In HessianFactor(const GaussianFactor& gf), gf is neither a JacobianFactor nor a HessianFactor");
236  }
237 }
238 
239 /* ************************************************************************* */
241  const Scatter& scatter) {
242  gttic(HessianFactor_MergeConstructor);
243 
244  Allocate(scatter);
245 
246  // Form A' * A
247  gttic(update);
248  info_.setZero();
249  for(const auto& factor: factors)
250  if (factor)
251  factor->updateHessian(keys_, &info_);
252  gttoc(update);
253 }
254 
255 /* ************************************************************************* */
256 void HessianFactor::print(const std::string& s,
257  const KeyFormatter& formatter) const {
258  cout << s << "\n";
259  cout << " keys: ";
260  for (const_iterator key = begin(); key != end(); ++key)
261  cout << formatter(*key) << "(" << getDim(key) << ") ";
262  cout << "\n";
264  "Augmented information matrix: ");
265 }
266 
267 /* ************************************************************************* */
268 bool HessianFactor::equals(const GaussianFactor& lf, double tol) const {
269  const HessianFactor* rhs = dynamic_cast<const HessianFactor*>(&lf);
270  if (!rhs || !Factor::equals(lf, tol))
271  return false;
273  tol);
274 }
275 
276 /* ************************************************************************* */
278  return info_.selfadjointView();
279 }
280 
281 /* ************************************************************************* */
284  return info_.selfadjointView(0, size());
285 }
286 
287 /* ************************************************************************* */
289  return informationView();
290 }
291 
292 /* ************************************************************************* */
294  for (DenseIndex j = 0; j < (DenseIndex)size(); ++j) {
295  auto result = d.emplace(keys_[j], info_.diagonal(j));
296  if(!result.second) {
297  // if emplace fails, it returns an iterator to the existing element, which we add to:
298  result.first->second += info_.diagonal(j);
299  }
300  }
301 }
302 
303 /* ************************************************************************* */
304 // Raw memory access version should be called in Regular Factors only currently
305 void HessianFactor::hessianDiagonal(double* d) const {
306  throw std::runtime_error(
307  "HessianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
308 }
309 
310 /* ************************************************************************* */
311 map<Key, Matrix> HessianFactor::hessianBlockDiagonal() const {
312  map<Key, Matrix> blocks;
313  // Loop over all variables
314  for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) {
315  // Get the diagonal block, and insert it
316  blocks.emplace(keys_[j], info_.diagonalBlock(j));
317  }
318  return blocks;
319 }
320 
321 /* ************************************************************************* */
323  return JacobianFactor(*this).augmentedJacobian();
324 }
325 
326 /* ************************************************************************* */
327 std::pair<Matrix, Vector> HessianFactor::jacobian() const {
328  return JacobianFactor(*this).jacobian();
329 }
330 
331 /* ************************************************************************* */
332 double HessianFactor::error(const VectorValues& c) const {
333  // error 0.5*(f - 2*x'*g + x'*G*x)
334  const double f = constantTerm();
335  if (empty()) {
336  return 0.5 * f;
337  }
338  double xtg = 0, xGx = 0;
339  // extract the relevant subset of the VectorValues
340  // NOTE may not be as efficient
341  const Vector x = c.vector(keys());
342  xtg = x.dot(linearTerm().col(0));
343  auto AtA = informationView();
344  xGx = x.transpose() * AtA * x;
345  return 0.5 * (f - 2.0 * xtg + xGx);
346 }
347 
348 /* ************************************************************************* */
350  SymmetricBlockMatrix* info) const {
351  gttic(updateHessian_HessianFactor);
352  assert(info);
353  // Apply updates to the upper triangle
354  DenseIndex nrVariablesInThisFactor = size(), nrBlocksInInfo = info->nBlocks() - 1;
355  vector<DenseIndex> slots(nrVariablesInThisFactor + 1);
356  // Loop over this factor's blocks with indices (i,j)
357  // For every block (i,j), we determine the block (I,J) in info.
358  for (DenseIndex j = 0; j <= nrVariablesInThisFactor; ++j) {
359  const bool rhs = (j == nrVariablesInThisFactor);
360  const DenseIndex J = rhs ? nrBlocksInInfo : Slot(infoKeys, keys_[j]);
361  slots[j] = J;
362  for (DenseIndex i = 0; i <= j; ++i) {
363  const DenseIndex I = slots[i]; // because i<=j, slots[i] is valid.
364 
365  if (i == j) {
366  assert(I == J);
368  } else {
369  assert(i < j);
370  assert(I != J);
372  }
373  }
374  }
375 }
376 
377 /* ************************************************************************* */
379  shared_ptr result = std::make_shared<This>(*this);
380  // Negate the information matrix of the result
381  result->info_.negate();
382  return std::move(result);
383 }
384 
385 /* ************************************************************************* */
387  VectorValues& yvalues) const {
388 
389  // Create a vector of temporary y values, corresponding to rows i
390  vector<Vector> y;
391  y.reserve(size());
392  for (const_iterator it = begin(); it != end(); it++)
393  y.push_back(Vector::Zero(getDim(it)));
394 
395  // Accessing the VectorValues one by one is expensive
396  // So we will loop over columns to access x only once per column
397  // And fill the above temporary y values, to be added into yvalues after
398  for (DenseIndex j = 0; j < (DenseIndex) size(); ++j) {
399  // xj is the input vector
400  Vector xj = x.at(keys_[j]);
401  DenseIndex i = 0;
402  for (; i < j; ++i)
403  y[i] += info_.aboveDiagonalBlock(i, j) * xj;
404 
405  // blocks on the diagonal are only half
406  y[i] += info_.diagonalBlock(j) * xj;
407  // for below diagonal, we take transpose block from upper triangular part
408  for (i = j + 1; i < (DenseIndex) size(); ++i)
409  y[i] += info_.aboveDiagonalBlock(j, i).transpose() * xj;
410  }
411 
412  // copy to yvalues
413  for (DenseIndex i = 0; i < (DenseIndex) size(); ++i) {
414  const auto [it, didNotExist] = yvalues.tryInsert(keys_[i], Vector());
415  if (didNotExist)
416  it->second = alpha * y[i]; // init
417  else
418  it->second += alpha * y[i]; // add
419  }
420 }
421 
422 /* ************************************************************************* */
424  VectorValues g;
425  size_t n = size();
426  for (size_t j = 0; j < n; ++j)
427  g.emplace(keys_[j], -info_.aboveDiagonalBlock(j, n));
428  return g;
429 }
430 
431 /* ************************************************************************* */
432 // Raw memory access version should be called in Regular Factors only currently
433 void HessianFactor::gradientAtZero(double* d) const {
434  throw std::runtime_error(
435  "HessianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
436 }
437 
438 /* ************************************************************************* */
440  const Factor::const_iterator it_i = find(key);
441  const DenseIndex I = std::distance(begin(), it_i);
442 
443  // Sum over G_ij*xj for all xj connecting to xi
444  Vector b = Vector::Zero(x.at(key).size());
445  for (Factor::const_iterator it_j = begin(); it_j != end(); ++it_j) {
446  const DenseIndex J = std::distance(begin(), it_j);
447 
448  // Obtain Gij from the Hessian factor
449  // Hessian factor only stores an upper triangular matrix, so be careful when i>j
450  const Matrix Gij = info_.block(I, J);
451  // Accumulate Gij*xj to gradf
452  b += Gij * x.at(*it_j);
453  }
454  // Subtract the linear term gi
455  b += -linearTerm(it_i);
456  return b;
457 }
458 
459 /* ************************************************************************* */
460 std::shared_ptr<GaussianConditional> HessianFactor::eliminateCholesky(const Ordering& keys) {
461  gttic(HessianFactor_eliminateCholesky);
462 
464 
465  try {
466  // Do dense elimination
467  size_t nFrontals = keys.size();
468  assert(nFrontals <= size());
469  info_.choleskyPartial(nFrontals);
470 
471  // TODO(frank): pre-allocate GaussianConditional and write into it
472  const VerticalBlockMatrix Ab = info_.split(nFrontals);
473  conditional = std::make_shared<GaussianConditional>(keys_, nFrontals, Ab);
474 
475  // Erase the eliminated keys in this factor
476  keys_.erase(begin(), begin() + nFrontals);
477  } catch (const CholeskyFailed&) {
478 #ifndef NDEBUG
479  cout << "Partial Cholesky on HessianFactor failed." << endl;
480  keys.print("Frontal keys ");
481  print("HessianFactor:");
482 #endif
484  }
485 
486  // Return result
487  return conditional;
488 }
489 
490 /* ************************************************************************* */
492  gttic(HessianFactor_solve);
493 
494  // Do Cholesky Factorization
495  const size_t n = size();
496  assert(size_t(info_.nBlocks()) == n + 1);
498  auto R = info_.triangularView(0, n);
499  auto eta = linearTerm();
500 
501  // Solve
502  const Vector solution = R.solve(eta);
503 
504  // Parse into VectorValues
506  std::size_t offset = 0;
507  for (DenseIndex j = 0; j < (DenseIndex)n; ++j) {
508  const DenseIndex dim = info_.getDim(j);
509  delta.emplace(keys_[j], solution.segment(offset, dim));
510  offset += dim;
511  }
512 
513  return delta;
514 }
515 
516 /* ************************************************************************* */
517 std::pair<std::shared_ptr<GaussianConditional>, std::shared_ptr<HessianFactor> >
520 
521  // Build joint factor
522  HessianFactor::shared_ptr jointFactor;
523  try {
524  Scatter scatter(factors, keys);
525  jointFactor = std::make_shared<HessianFactor>(factors, scatter);
526  } catch (std::invalid_argument&) {
528  "EliminateCholesky was called with a request to eliminate variables that are not\n"
529  "involved in the provided factors.");
530  }
531 
532  // Do dense elimination
533  auto conditional = jointFactor->eliminateCholesky(keys);
534 
535  // Return result
536  return make_pair(conditional, jointFactor);
537 }
538 
539 /* ************************************************************************* */
540 std::pair<std::shared_ptr<GaussianConditional>,
541  std::shared_ptr<GaussianFactor> > EliminatePreferCholesky(
542  const GaussianFactorGraph& factors, const Ordering& keys) {
544 
545  // If any JacobianFactors have constrained noise models, we have to convert
546  // all factors to JacobianFactors. Otherwise, we can convert all factors
547  // to HessianFactors. This is because QR can handle constrained noise
548  // models but Cholesky cannot.
549  if (hasConstraints(factors))
550  return EliminateQR(factors, keys);
551  else
552  return EliminateCholesky(factors, keys);
553 }
554 
555 } // gtsam
gttoc
#define gttoc(label)
Definition: timing.h:296
timing.h
Timing utilities.
relicense.update
def update(text)
Definition: relicense.py:46
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
GaussianConditional.h
Conditional Gaussian Base class.
col
m col(1)
D
MatrixXcd D
Definition: EigenSolver_EigenSolver_MatrixType.cpp:14
gtsam::HessianFactor::equals
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
Definition: HessianFactor.cpp:268
Vector.h
typedef and functions to augment Eigen's VectorXd
gtsam::HessianFactor::augmentedInformation
Matrix augmentedInformation() const override
Definition: HessianFactor.cpp:277
gtsam::SymmetricBlockMatrix::setOffDiagonalBlock
void setOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Set an off-diagonal block. Only the upper triangular portion of xpr is evaluated.
Definition: SymmetricBlockMatrix.h:203
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
gtsam::HessianFactor
A Gaussian factor using the canonical parameters (information form)
Definition: HessianFactor.h:99
s
RealScalar s
Definition: level1_cplx_impl.h:126
d
static const double d[K][N]
Definition: igam.h:11
gtsam::JacobianFactor::get_model
const SharedDiagonal & get_model() const
Definition: JacobianFactor.h:292
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
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::FastVector
std::vector< T, typename internal::FastDefaultVectorAllocator< T >::type > FastVector
Definition: FastVector.h:34
Matrix.h
typedef and functions to augment Eigen's MatrixXd
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::HessianFactor::gradientAtZero
VectorValues gradientAtZero() const override
eta for Hessian
Definition: HessianFactor.cpp:423
gtsam::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::GaussianFactor
Definition: GaussianFactor.h:38
gtsam::HessianFactor::HessianFactor
HessianFactor()
Definition: HessianFactor.cpp:68
gtsam::Factor::find
const_iterator find(Key key) const
find
Definition: Factor.h:140
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
cholesky.h
Efficient incomplete Cholesky on rank-deficient matrices, todo: constrained Cholesky.
gtsam::equal_with_abs_tol
bool equal_with_abs_tol(const Eigen::DenseBase< MATRIX > &A, const Eigen::DenseBase< MATRIX > &B, double tol=1e-9)
Definition: base/Matrix.h:80
HessianFactor.h
Contains the HessianFactor class, a general quadratic factor.
gtsam::Factor::empty
bool empty() const
Whether the factor is empty (involves zero variables).
Definition: Factor.h:131
gtsam::SymmetricBlockMatrix::selfadjointView
Eigen::SelfAdjointView< constBlock, Eigen::Upper > selfadjointView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j).
Definition: SymmetricBlockMatrix.h:158
gtsam::VerticalBlockMatrix::full
Block full()
Definition: VerticalBlockMatrix.h:159
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::HessianFactor::informationView
Eigen::SelfAdjointView< SymmetricBlockMatrix::constBlock, Eigen::Upper > informationView() const
Return self-adjoint view onto the information matrix (NOT augmented).
Definition: HessianFactor.cpp:283
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::SymmetricBlockMatrix::setDiagonalBlock
void setDiagonalBlock(DenseIndex I, const XprType &xpr)
Set a diagonal block. Only the upper triangular portion of xpr is evaluated.
Definition: SymmetricBlockMatrix.h:197
gtsam::HessianFactor::error
double error(const VectorValues &c) const override
Definition: HessianFactor.cpp:332
gtsam::HessianFactor::multiplyHessianAdd
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
Definition: HessianFactor.cpp:386
gtsam::HessianFactor::info
const SymmetricBlockMatrix & info() const
Return underlying information matrix.
Definition: HessianFactor.h:269
gtsam::HessianFactor::negate
GaussianFactor::shared_ptr negate() const override
Definition: HessianFactor.cpp:378
gtsam::JacobianFactor::jacobian
std::pair< Matrix, Vector > jacobian() const override
Returns (dense) A,b pair associated with factor, bakes in the weights.
Definition: JacobianFactor.cpp:715
gtsam::Factor::begin
const_iterator begin() const
Definition: Factor.h:146
gtsam::Factor::shared_ptr
std::shared_ptr< Factor > shared_ptr
A shared_ptr to this class.
Definition: Factor.h:76
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
gtsam::KeyVector
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:92
result
Values result
Definition: OdometryOptimize.cpp:8
A
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Definition: bench_gemm.cpp:48
gtsam::GaussianFactor::hessianDiagonal
VectorValues hessianDiagonal() const
Return the diagonal of the Hessian for this factor.
Definition: GaussianFactor.cpp:35
gtsam::CholeskyFailed
Indicate Cholesky factorization failure.
Definition: ThreadsafeException.h:115
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")
gtsam::EliminatePreferCholesky
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: HessianFactor.cpp:541
n
int n
Definition: BiCGSTAB_simple.cpp:1
gtsam::Dims
std::vector< Key > Dims
Definition: HessianFactor.cpp:42
linearExceptions.h
Exceptions that may be thrown by linear solver components.
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
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
gtsam::VerticalBlockMatrix
Definition: VerticalBlockMatrix.h:44
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
ThreadsafeException.h
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
gtsam::HessianFactor::solve
VectorValues solve()
Solve the system A'*A delta = A'*b in-place, return delta as VectorValues.
Definition: HessianFactor.cpp:491
gtsam::HessianFactor::augmentedJacobian
Matrix augmentedJacobian() const override
Definition: HessianFactor.cpp:322
I
#define I
Definition: main.h:112
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::GaussianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactor.h:42
gtsam::InvalidDenseElimination
Definition: linearExceptions.h:134
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
gtsam::SymmetricBlockMatrix::LikeActiveViewOf
static SymmetricBlockMatrix LikeActiveViewOf(const SymmetricBlockMatrix &other)
Definition: SymmetricBlockMatrix.cpp:34
gtsam::HessianFactor::gradient
Vector gradient(Key key, const VectorValues &x) const override
Definition: HessianFactor.cpp:439
gtsam::JacobianFactor::augmentedJacobian
Matrix augmentedJacobian() const override
Definition: JacobianFactor.cpp:731
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
gtsam::Scatter
Definition: Scatter.h:49
gtsam::VectorValues::tryInsert
std::pair< iterator, bool > tryInsert(Key j, const Vector &value)
Definition: VectorValues.h:212
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
gtsam::SymmetricBlockMatrix::nBlocks
DenseIndex nBlocks() const
Block count.
Definition: SymmetricBlockMatrix.h:122
gtsam::HessianFactor::hessianDiagonalAdd
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
Definition: HessianFactor.cpp:293
gtsam::Factor::end
const_iterator end() const
Definition: Factor.h:149
size_t
std::size_t size_t
Definition: wrap/pybind11/include/pybind11/detail/common.h:490
gtsam::HessianFactor::print
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
Definition: HessianFactor.cpp:256
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
y
Scalar * y
Definition: level1_cplx_impl.h:124
matrix
Map< Matrix< T, Dynamic, Dynamic, ColMajor >, 0, OuterStride<> > matrix(T *data, int rows, int cols, int stride)
Definition: gtsam/3rdparty/Eigen/blas/common.h:110
offset
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 set set set surface set nocontour set clabel set mapping cartesian set nohidden3d set cntrparam order set cntrparam linear set cntrparam levels auto set cntrparam points set size set set xzeroaxis lt lw set x2zeroaxis lt lw set yzeroaxis lt lw set y2zeroaxis lt lw set tics in set ticslevel set tics set mxtics default set mytics default set mx2tics default set my2tics default set xtics border mirror norotate autofreq set ytics border mirror norotate autofreq set ztics border nomirror norotate autofreq set nox2tics set noy2tics set timestamp bottom norotate offset
Definition: gnuplot_common_settings.hh:64
key
const gtsam::Symbol key('X', 0)
JacobianFactor.h
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::HessianFactor::information
Matrix information() const override
Definition: HessianFactor.cpp:288
gtsam::SymmetricBlockMatrix::triangularView
Eigen::TriangularView< constBlock, Eigen::Upper > triangularView(DenseIndex I, DenseIndex J) const
Return the square sub-matrix that contains blocks(i:j, i:j) as a triangular view.
Definition: SymmetricBlockMatrix.h:165
gtsam::b
const G & b
Definition: Group.h:79
gtsam::SymmetricBlockMatrix::updateDiagonalBlock
void updateDiagonalBlock(DenseIndex I, const XprType &xpr)
Increment the diagonal block by the values in xpr. Only reads the upper triangular part of xpr.
Definition: SymmetricBlockMatrix.h:214
gtsam::Factor::const_iterator
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:83
gtsam::HessianFactor::jacobian
std::pair< Matrix, Vector > jacobian() const override
Return (dense) matrix associated with factor.
Definition: HessianFactor.cpp:327
gtsam
traits
Definition: SFMdata.h:40
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
gtsam::SymmetricBlockMatrix::setZero
void setZero()
Set the entire active matrix zero.
Definition: SymmetricBlockMatrix.h:260
gtsam::SymmetricBlockMatrix::split
VerticalBlockMatrix split(DenseIndex nFrontals)
Definition: SymmetricBlockMatrix.cpp:92
gtsam::HessianFactor::Allocate
void Allocate(const Scatter &scatter)
Allocate for given scatter pattern.
Definition: HessianFactor.cpp:45
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::HessianFactor::updateHessian
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
Definition: HessianFactor.cpp:349
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::Factor::equals
bool equals(const This &other, double tol=1e-9) const
check equality
Definition: Factor.cpp:42
gtsam::SymmetricBlockMatrix::updateOffDiagonalBlock
void updateOffDiagonalBlock(DenseIndex I, DenseIndex J, const XprType &xpr)
Definition: SymmetricBlockMatrix.h:230
std
Definition: BFloat16.h:88
gtsam::HessianFactor::eliminateCholesky
std::shared_ptr< GaussianConditional > eliminateCholesky(const Ordering &keys)
Definition: HessianFactor.cpp:460
G
JacobiRotation< float > G
Definition: Jacobi_makeGivens.cpp:2
gtsam::SymmetricBlockMatrix::diagonal
Vector diagonal(DenseIndex J) const
Get the diagonal of the J'th diagonal block.
Definition: SymmetricBlockMatrix.h:147
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
gtsam::GaussianConditional::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianConditional.h:46
exampleQR::Ab
Matrix Ab
Definition: testNoiseModel.cpp:207
v
Array< int, Dynamic, 1 > v
Definition: Array_initializer_list_vector_cxx11.cpp:1
gtsam::HessianFactor::rows
size_t rows() const
Definition: HessianFactor.h:216
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::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::JacobianFactor::matrixObject
const VerticalBlockMatrix & matrixObject() const
Definition: JacobianFactor.h:257
gtsam::distance
Double_ distance(const OrientedPlane3_ &p)
Definition: slam/expressions.h:117
GaussianFactor.h
A factor with a quadratic error function - a Gaussian.
gtsam::SymmetricBlockMatrix::block
Matrix block(DenseIndex I, DenseIndex J) const
Definition: SymmetricBlockMatrix.cpp:60
gtsam::IndeterminantLinearSystemException
Definition: linearExceptions.h:94
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
cols
int cols
Definition: Tutorial_commainit_02.cpp:1
gtsam::hasConstraints
bool hasConstraints(const GaussianFactorGraph &factors)
Definition: GaussianFactorGraph.cpp:442
gtsam::SymmetricBlockMatrix::choleskyPartial
void choleskyPartial(DenseIndex nFrontals)
Definition: SymmetricBlockMatrix.cpp:83
gtsam::HessianFactor::hessianBlockDiagonal
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
Definition: HessianFactor.cpp:311
gtsam::Factor::size
size_t size() const
Definition: Factor.h:160
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::SymmetricBlockMatrix
Definition: SymmetricBlockMatrix.h:53
gtsam::SlotEntry
One SlotEntry stores the slot index for a variable, as well its dim.
Definition: Scatter.h:32
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
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
R
Rot2 R(Rot2::fromAngle(0.1))
gttic
#define gttic(label)
Definition: timing.h:295
debug.h
Global debugging flags.
FastMap.h
A thin wrapper around std::map that uses boost's fast_pool_allocator.
gtsam::EliminateQR
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:779


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