JacobianFactor.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 
23 #include <gtsam/linear/Scatter.h>
28 #include <gtsam/base/debug.h>
29 #include <gtsam/base/timing.h>
30 #include <gtsam/base/Matrix.h>
31 #include <gtsam/base/FastMap.h>
32 #include <gtsam/base/cholesky.h>
33 
34 #include <cmath>
35 #include <cassert>
36 #include <sstream>
37 #include <stdexcept>
38 
39 using namespace std;
40 
41 namespace gtsam {
42 
43 // Typedefs used in constructors below.
44 using Dims = std::vector<Key>;
45 using Pairs = std::vector<std::pair<Key, Matrix>>;
46 
47 /* ************************************************************************* */
48 JacobianFactor::JacobianFactor() :
49  Ab_(Dims{1}, 0) {
50  getb().setZero();
51 }
52 
53 /* ************************************************************************* */
55  // Copy the matrix data depending on what type of factor we're copying from
56  if (const JacobianFactor* asJacobian = dynamic_cast<const JacobianFactor*>(&gf))
57  *this = JacobianFactor(*asJacobian);
58  else if (const HessianFactor* asHessian = dynamic_cast<const HessianFactor*>(&gf))
59  *this = JacobianFactor(*asHessian);
60  else
61  throw std::invalid_argument(
62  "In JacobianFactor(const GaussianFactor& rhs), rhs is neither a JacobianFactor nor a HessianFactor");
63 }
64 
65 /* ************************************************************************* */
67  Ab_(Dims{1}, b_in.size()) {
68  getb() = b_in;
69 }
70 
71 /* ************************************************************************* */
73  const SharedDiagonal& model) {
74  fillTerms(Pairs{{i1, A1}}, b, model);
75 }
76 
77 /* ************************************************************************* */
79  const Matrix& A2, const Vector& b, const SharedDiagonal& model) {
80  fillTerms(Pairs{{i1, A1}, {i2, A2}}, b, model);
81 }
82 
83 /* ************************************************************************* */
85  const Matrix& A2, Key i3, const Matrix& A3, const Vector& b,
86  const SharedDiagonal& model) {
87  fillTerms(Pairs{{i1, A1}, {i2, A2}, {i3, A3}}, b, model);
88 }
89 
90 /* ************************************************************************* */
92  : Base(factor),
93  Ab_(VerticalBlockMatrix::LikeActiveViewOf(factor.info(), factor.rows())) {
94  // Copy Hessian into our matrix and then do in-place Cholesky
95  Ab_.full() = factor.info().selfadjointView();
96 
97  // Do Cholesky to get a Jacobian
98  const auto [maxrank, success] = choleskyCareful(Ab_.matrix());
99 
100  // Check that Cholesky succeeded OR it managed to factor the full Hessian.
101  // THe latter case occurs with non-positive definite matrices arising from QP.
102  if (success || maxrank == factor.rows() - 1) {
103  // Zero out lower triangle
104  Ab_.matrix().topRows(maxrank).triangularView<Eigen::StrictlyLower>() =
105  Matrix::Zero(maxrank, Ab_.matrix().cols());
106  // FIXME: replace with triangular system
107  Ab_.rowEnd() = maxrank;
108  model_ = SharedDiagonal(); // is equivalent to Unit::Create(maxrank)
109  } else {
110  // indefinite system
111  throw IndeterminantLinearSystemException(factor.keys().front());
112  }
113 }
114 
115 /* ************************************************************************* */
116 // Helper functions for combine constructor
117 namespace {
118 std::tuple<FastVector<DenseIndex>, DenseIndex, DenseIndex> _countDims(
120  const FastVector<VariableSlots::const_iterator>& variableSlots) {
121  gttic(countDims);
122 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
123  FastVector<DenseIndex> varDims(variableSlots.size(), numeric_limits<DenseIndex>::max());
124 #else
125  FastVector<DenseIndex> varDims(variableSlots.size(),
127 #endif
128  DenseIndex m = 0;
129  DenseIndex n = 0;
130  for (size_t jointVarpos = 0; jointVarpos < variableSlots.size();
131  ++jointVarpos) {
132  const VariableSlots::const_iterator& slots = variableSlots[jointVarpos];
133 
134  assert(slots->second.size() == factors.size());
135 
136  bool foundVariable = false;
137  for (size_t sourceFactorI = 0; sourceFactorI < slots->second.size();
138  ++sourceFactorI) {
139  const size_t sourceVarpos = slots->second[sourceFactorI];
140  if (sourceVarpos != VariableSlots::Empty) {
141  const JacobianFactor& sourceFactor = *factors[sourceFactorI];
142  if (sourceFactor.cols() > 1) {
143  foundVariable = true;
144  DenseIndex vardim = sourceFactor.getDim(
145  sourceFactor.begin() + sourceVarpos);
146 
147 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
148  if(varDims[jointVarpos] == numeric_limits<DenseIndex>::max()) {
149  varDims[jointVarpos] = vardim;
150  n += vardim;
151  } else {
152  if(!(varDims[jointVarpos] == vardim)) {
153  std::stringstream ss;
154  ss << "Factor " << sourceFactorI << " variable " << DefaultKeyFormatter(sourceFactor.keys()[sourceVarpos]) <<
155  " has different dimensionality of " << vardim << " instead of " << varDims[jointVarpos];
156  throw std::runtime_error(ss.str());
157  }
158  }
159 #else
160 
161  varDims[jointVarpos] = vardim;
162  n += vardim;
163  break;
164 #endif
165  }
166  }
167  }
168 
169  if (!foundVariable)
170  throw std::invalid_argument(
171  "Unable to determine dimensionality for all variables");
172  }
173 
175  m += factor->rows();
176  }
177 
178 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS)
179  for(DenseIndex d: varDims) {
180  assert(d != numeric_limits<DenseIndex>::max());
181  }
182 #endif
183 
184  return std::make_tuple(varDims, m, n);
185 }
186 
187 /* ************************************************************************* */
188 FastVector<JacobianFactor::shared_ptr> _convertOrCastToJacobians(
189  const GaussianFactorGraph& factors) {
190  gttic(Convert_to_Jacobians);
191  FastVector<JacobianFactor::shared_ptr> jacobians;
192  jacobians.reserve(factors.size());
194  if (factor) {
195  if (JacobianFactor::shared_ptr jf = std::dynamic_pointer_cast<
197  jacobians.push_back(jf);
198  else
199  jacobians.push_back(std::make_shared<JacobianFactor>(*factor));
200  }
201  }
202  return jacobians;
203 }
204 }
205 
206 /* ************************************************************************* */
208  const FastVector<VariableSlots::const_iterator>& orderedSlots) {
209 
210  // Cast or convert to Jacobians
211  FastVector<JacobianFactor::shared_ptr> jacobians = _convertOrCastToJacobians(
212  graph);
213 
214  // Count dimensions
215  const auto [varDims, m, n] = _countDims(jacobians, orderedSlots);
216 
217  // Allocate matrix and copy keys in order
218  gttic(allocate);
219  Ab_ = VerticalBlockMatrix(varDims, m, true); // Allocate augmented matrix
220  Base::keys_.resize(orderedSlots.size());
221  // Copy keys in order
222  std::transform(orderedSlots.begin(), orderedSlots.end(),
223  Base::keys_.begin(),
224  [](const VariableSlots::const_iterator& it) {return it->first;});
225  gttoc(allocate);
226 
227  // Loop over slots in combined factor and copy blocks from source factors
228  gttic(copy_blocks);
229  size_t combinedSlot = 0;
230  for(VariableSlots::const_iterator varslot: orderedSlots) {
231  JacobianFactor::ABlock destSlot(this->getA(this->begin() + combinedSlot));
232  // Loop over source jacobians
233  DenseIndex nextRow = 0;
234  for (size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
235  // Slot in source factor
236  const size_t sourceSlot = varslot->second[factorI];
237  const DenseIndex sourceRows = jacobians[factorI]->rows();
238  if (sourceRows > 0) {
240  destSlot.middleRows(nextRow, sourceRows));
241  // Copy if exists in source factor, otherwise set zero
242  if (sourceSlot != VariableSlots::Empty)
243  destBlock = jacobians[factorI]->getA(
244  jacobians[factorI]->begin() + sourceSlot);
245  else
246  destBlock.setZero();
247  nextRow += sourceRows;
248  }
249  }
250  ++combinedSlot;
251  }
252  gttoc(copy_blocks);
253 
254  // Copy the RHS vectors and sigmas
255  gttic(copy_vectors);
256  bool anyConstrained = false;
257  std::optional<Vector> sigmas;
258  // Loop over source jacobians
259  DenseIndex nextRow = 0;
260  for (size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
261  const DenseIndex sourceRows = jacobians[factorI]->rows();
262  if (sourceRows > 0) {
263  this->getb().segment(nextRow, sourceRows) = jacobians[factorI]->getb();
264  if (jacobians[factorI]->get_model()) {
265  // If the factor has a noise model and we haven't yet allocated sigmas, allocate it.
266  if (!sigmas)
267  sigmas = Vector::Constant(m, 1.0);
268  sigmas->segment(nextRow, sourceRows) =
269  jacobians[factorI]->get_model()->sigmas();
270  if (jacobians[factorI]->isConstrained())
271  anyConstrained = true;
272  }
273  nextRow += sourceRows;
274  }
275  }
276  gttoc(copy_vectors);
277 
278  if (sigmas)
279  this->setModel(anyConstrained, *sigmas);
280 }
281 
282 /* ************************************************************************* */
283 // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
284 // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
285 // be added after all of the ordered variables.
287  const Ordering& ordering,
288  const VariableSlots& variableSlots) {
289  gttic(Order_slots);
290 
292  orderedSlots.reserve(variableSlots.size());
293 
294  // If an ordering is provided, arrange the slots first that ordering
296  size_t nOrderingSlotsUsed = 0;
297  orderedSlots.resize(ordering.size());
298  FastMap<Key, size_t> inverseOrdering = ordering.invert();
299  for (VariableSlots::const_iterator item = variableSlots.begin();
300  item != variableSlots.end(); ++item) {
301  FastMap<Key, size_t>::const_iterator orderingPosition =
302  inverseOrdering.find(item->first);
303  if (orderingPosition == inverseOrdering.end()) {
304  unorderedSlots.push_back(item);
305  } else {
306  orderedSlots[orderingPosition->second] = item;
307  ++nOrderingSlotsUsed;
308  }
309  }
310  if (nOrderingSlotsUsed != ordering.size())
311  throw std::invalid_argument(
312  "The ordering provided to the JacobianFactor combine constructor\n"
313  "contained extra variables that did not appear in the factors to combine.");
314  // Add the remaining slots
315  for(VariableSlots::const_iterator item: unorderedSlots) {
316  orderedSlots.push_back(item);
317  }
318 
319  gttoc(Order_slots);
320 
321  return orderedSlots;
322 }
323 
324 /* ************************************************************************* */
326  gttic(JacobianFactor_combine_constructor);
327 
328  // Compute VariableSlots if one was not provided
329  // Binds reference, does not copy VariableSlots
330  const VariableSlots & variableSlots = VariableSlots(graph);
331 
332  gttic(Order_slots);
333  // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
334  // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
335  // be added after all of the ordered variables.
337  orderedSlots.reserve(variableSlots.size());
338 
339  // If no ordering is provided, arrange the slots as they were, which will be sorted
340  // numerically since VariableSlots uses a map sorting on Key.
341  for (VariableSlots::const_iterator item = variableSlots.begin();
342  item != variableSlots.end(); ++item)
343  orderedSlots.push_back(item);
344  gttoc(Order_slots);
345 
346  JacobianFactorHelper(graph, orderedSlots);
347 }
348 
349 /* ************************************************************************* */
351  const VariableSlots& p_variableSlots) {
352  gttic(JacobianFactor_combine_constructor);
353 
354  // Binds reference, does not copy VariableSlots
355  const VariableSlots & variableSlots = p_variableSlots;
356 
357  gttic(Order_slots);
358  // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
359  // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
360  // be added after all of the ordered variables.
362  orderedSlots.reserve(variableSlots.size());
363 
364  // If no ordering is provided, arrange the slots as they were, which will be sorted
365  // numerically since VariableSlots uses a map sorting on Key.
366  for (VariableSlots::const_iterator item = variableSlots.begin();
367  item != variableSlots.end(); ++item)
368  orderedSlots.push_back(item);
369  gttoc(Order_slots);
370 
371  JacobianFactorHelper(graph, orderedSlots);
372 }
373 
374 /* ************************************************************************* */
376  const Ordering& ordering) {
377  gttic(JacobianFactor_combine_constructor);
378 
379  // Compute VariableSlots if one was not provided
380  // Binds reference, does not copy VariableSlots
381  const VariableSlots & variableSlots = VariableSlots(graph);
382 
383  // Order variable slots
385  orderedSlotsHelper(ordering, variableSlots);
386 
387  JacobianFactorHelper(graph, orderedSlots);
388 }
389 
390 /* ************************************************************************* */
392  const Ordering& ordering,
393  const VariableSlots& p_variableSlots) {
394  gttic(JacobianFactor_combine_constructor);
395 
396  // Order variable slots
398  orderedSlotsHelper(ordering, p_variableSlots);
399 
400  JacobianFactorHelper(graph, orderedSlots);
401 }
402 
403 /* ************************************************************************* */
404 void JacobianFactor::print(const string& s,
405  const KeyFormatter& formatter) const {
406  if (!s.empty())
407  cout << s << "\n";
408  for (const_iterator key = begin(); key != end(); ++key) {
409  cout << " A[" << formatter(*key) << "] = ";
410  cout << getA(key).format(matlabFormat()) << endl;
411  }
412  cout << formatMatrixIndented(" b = ", getb(), true) << "\n";
413  if (model_)
414  model_->print(" Noise model: ");
415  else
416  cout << " No noise model" << endl;
417 }
418 
419 /* ************************************************************************* */
420 // Check if two linear factors are equal
421 bool JacobianFactor::equals(const GaussianFactor& f_, double tol) const {
422  static const bool verbose = false;
423  if (!dynamic_cast<const JacobianFactor*>(&f_)) {
424  if (verbose)
425  cout << "JacobianFactor::equals: Incorrect type" << endl;
426  return false;
427  } else {
428  const JacobianFactor& f(static_cast<const JacobianFactor&>(f_));
429 
430  // Check keys
431  if (keys() != f.keys()) {
432  if (verbose)
433  cout << "JacobianFactor::equals: keys do not match" << endl;
434  return false;
435  }
436 
437  // Check noise model
438  if ((model_ && !f.model_) || (!model_ && f.model_)) {
439  if (verbose)
440  cout << "JacobianFactor::equals: noise model mismatch" << endl;
441  return false;
442  }
443  if (model_ && f.model_ && !model_->equals(*f.model_, tol)) {
444  if (verbose)
445  cout << "JacobianFactor::equals: noise modesl are not equal" << endl;
446  return false;
447  }
448 
449  // Check matrix sizes
450  if (!(Ab_.rows() == f.Ab_.rows() && Ab_.cols() == f.Ab_.cols())) {
451  if (verbose)
452  cout << "JacobianFactor::equals: augmented size mismatch" << endl;
453  return false;
454  }
455 
456  // Check matrix contents
457  constABlock Ab1(Ab_.range(0, Ab_.nBlocks()));
458  constABlock Ab2(f.Ab_.range(0, f.Ab_.nBlocks()));
459  for (size_t row = 0; row < (size_t) Ab1.rows(); ++row)
460  if (!equal_with_abs_tol(Ab1.row(row), Ab2.row(row), tol)
461  && !equal_with_abs_tol(-Ab1.row(row), Ab2.row(row), tol)) {
462  if (verbose)
463  cout << "JacobianFactor::equals: matrix mismatch at row " << row << endl;
464  return false;
465  }
466 
467  return true;
468  }
469 }
470 
471 /* ************************************************************************* */
473  Vector e = -getb();
474  for (size_t pos = 0; pos < size(); ++pos)
475  e += Ab_(pos) * c[keys_[pos]];
476  return e;
477 }
478 
479 /* ************************************************************************* */
482  if (model_) model_->whitenInPlace(e);
483  return e;
484 }
485 
486 /* ************************************************************************* */
487 double JacobianFactor::error(const VectorValues& c) const {
489  // Use the noise model distance function to get the correct error if available.
490  if (model_) return 0.5 * model_->squaredMahalanobisDistance(e);
491  return 0.5 * e.dot(e);
492 }
493 
494 /* ************************************************************************* */
496  if (model_) {
497  Matrix AbWhitened = Ab_.full();
498  model_->WhitenInPlace(AbWhitened);
499  return AbWhitened.transpose() * AbWhitened;
500  } else {
501  return Ab_.full().transpose() * Ab_.full();
502  }
503 }
504 
505 /* ************************************************************************* */
507  if (model_) {
508  Matrix AWhitened = this->getA();
509  model_->WhitenInPlace(AWhitened);
510  return AWhitened.transpose() * AWhitened;
511  } else {
512  return this->getA().transpose() * this->getA();
513  }
514 }
515 
516 /* ************************************************************************* */
518  for (size_t pos = 0; pos < size(); ++pos) {
519  Key j = keys_[pos];
520  size_t nj = Ab_(pos).cols();
521  auto result = d.emplace(j, nj);
522 
523  Vector& dj = result.first->second;
524 
525  for (size_t k = 0; k < nj; ++k) {
526  Eigen::Ref<const Vector> column_k = Ab_(pos).col(k);
527  if (model_) {
528  Vector column_k_copy = column_k;
529  model_->whitenInPlace(column_k_copy);
530  if(!result.second)
531  dj(k) += dot(column_k_copy, column_k_copy);
532  else
533  dj(k) = dot(column_k_copy, column_k_copy);
534  } else {
535  if (!result.second)
536  dj(k) += dot(column_k, column_k);
537  else
538  dj(k) = dot(column_k, column_k);
539  }
540  }
541  }
542 }
543 
544 /* ************************************************************************* */
545 // Raw memory access version should be called in Regular Factors only currently
546 void JacobianFactor::hessianDiagonal(double* d) const {
547  throw std::runtime_error("JacobianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
548 }
549 
550 /* ************************************************************************* */
551 map<Key, Matrix> JacobianFactor::hessianBlockDiagonal() const {
552  map<Key, Matrix> blocks;
553  for (size_t pos = 0; pos < size(); ++pos) {
554  Key j = keys_[pos];
555  Matrix Aj = Ab_(pos);
556  if (model_)
557  Aj = model_->Whiten(Aj);
558  blocks.emplace(j, Aj.transpose() * Aj);
559  }
560  return blocks;
561 }
562 
563 /* ************************************************************************* */
565  SymmetricBlockMatrix* info) const {
566  gttic(updateHessian_JacobianFactor);
567 
568  if (rows() == 0) return;
569 
570  // Whiten the factor if it has a noise model
571  const SharedDiagonal& model = get_model();
572  if (model && !model->isUnit()) {
573  if (model->isConstrained())
574  throw invalid_argument(
575  "JacobianFactor::updateHessian: cannot update information with "
576  "constrained noise model");
577  JacobianFactor whitenedFactor = whiten();
578  whitenedFactor.updateHessian(infoKeys, info);
579  } else {
580  // Ab_ is the augmented Jacobian matrix A, and we perform I += A'*A below
581  DenseIndex n = Ab_.nBlocks() - 1, N = info->nBlocks() - 1;
582 
583  // Apply updates to the upper triangle
584  // Loop over blocks of A, including RHS with j==n
585  vector<DenseIndex> slots(n+1);
586  for (DenseIndex j = 0; j <= n; ++j) {
588  const DenseIndex J = (j == n) ? N : Slot(infoKeys, keys_[j]);
589  slots[j] = J;
590  // Fill off-diagonal blocks with Ai'*Aj
591  for (DenseIndex i = 0; i < j; ++i) {
592  const DenseIndex I = slots[i]; // because i<j, slots[i] is valid.
593  info->updateOffDiagonalBlock(I, J, Ab_(i).transpose() * Ab_j);
594  }
595  // Fill diagonal block with Aj'*Aj
596  info->diagonalBlock(J).rankUpdate(Ab_j.transpose());
597  }
598  }
599 }
600 
601 /* ************************************************************************* */
603  Vector Ax(Ab_.rows());
604  Ax.setZero();
605  if (empty())
606  return Ax;
607 
608  // Just iterate over all A matrices and multiply in correct config part
609  for (size_t pos = 0; pos < size(); ++pos) {
610  // http://eigen.tuxfamily.org/dox/TopicWritingEfficientProductExpression.html
611  Ax.noalias() += Ab_(pos) * x[keys_[pos]];
612  }
613 
614  if (model_) model_->whitenInPlace(Ax);
615  return Ax;
616 }
617 
618 /* ************************************************************************* */
620  VectorValues& x) const {
621  Vector E(e.size());
622  E.noalias() = alpha * e;
623  if (model_) model_->whitenInPlace(E);
624  // Just iterate over all A matrices and insert Ai^e into VectorValues
625  for (size_t pos = 0; pos < size(); ++pos) {
626  const Key j = keys_[pos];
627  // To avoid another malloc if key exists, we explicitly check
628  auto it = x.find(j);
629  if (it != x.end()) {
630  // http://eigen.tuxfamily.org/dox/TopicWritingEfficientProductExpression.html
631  it->second.noalias() += Ab_(pos).transpose() * E;
632  } else {
633  x.emplace(j, Ab_(pos).transpose() * E);
634  }
635  }
636 }
637 
638 /* ************************************************************************* */
640  VectorValues& y) const {
641  Vector Ax = (*this) * x;
643 }
644 
645 /* ************************************************************************* */
654 void JacobianFactor::multiplyHessianAdd(double alpha, const double* x, double* y,
655  const std::vector<size_t>& accumulatedDims) const {
656 
658  typedef Eigen::Map<Vector> VectorMap;
659  typedef Eigen::Map<const Vector> ConstVectorMap;
660 
661  if (empty())
662  return;
663  Vector Ax = Vector::Zero(Ab_.rows());
664 
668  for (size_t pos = 0; pos < size(); ++pos) {
669  size_t offset = accumulatedDims[keys_[pos]];
670  size_t dim = accumulatedDims[keys_[pos] + 1] - offset;
671  Ax += Ab_(pos) * ConstVectorMap(x + offset, dim);
672  }
674  if (model_) {
675  model_->whitenInPlace(Ax);
676  model_->whitenInPlace(Ax);
677  }
678 
680  Ax *= alpha;
681 
683  for (size_t pos = 0; pos < size(); ++pos) {
684  size_t offset = accumulatedDims[keys_[pos]];
685  size_t dim = accumulatedDims[keys_[pos] + 1] - offset;
686  VectorMap(y + offset, dim) += Ab_(pos).transpose() * Ax;
687  }
688 }
689 
690 /* ************************************************************************* */
692  VectorValues g;
693  Vector b = getb();
694  // Gradient is really -A'*b / sigma^2
695  // transposeMultiplyAdd will divide by sigma once, so we need one more
696  if (model_) model_->whitenInPlace(b);
697  this->transposeMultiplyAdd(-1.0, b, g); // g -= A'*b/sigma^2
698  return g;
699 }
700 
701 /* ************************************************************************* */
702 // Raw memory access version should be called in Regular Factors only currently
703 void JacobianFactor::gradientAtZero(double* d) const {
704  throw std::runtime_error("JacobianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
705 }
706 
707 /* ************************************************************************* */
709  // TODO: optimize it for JacobianFactor without converting to a HessianFactor
710  HessianFactor hessian(*this);
711  return hessian.gradient(key, x);
712 }
713 
714 /* ************************************************************************* */
715 pair<Matrix, Vector> JacobianFactor::jacobian() const {
716  pair<Matrix, Vector> result = jacobianUnweighted();
717  // divide in sigma so error is indeed 0.5*|Ax-b|
718  if (model_)
719  model_->WhitenSystem(result.first, result.second);
720  return result;
721 }
722 
723 /* ************************************************************************* */
724 pair<Matrix, Vector> JacobianFactor::jacobianUnweighted() const {
725  Matrix A(Ab_.range(0, size()));
726  Vector b(getb());
727  return make_pair(A, b);
728 }
729 
730 /* ************************************************************************* */
733  if (model_)
734  model_->WhitenInPlace(Ab);
735  return Ab;
736 }
737 
738 /* ************************************************************************* */
740  return Ab_.range(0, Ab_.nBlocks());
741 }
742 
743 /* ************************************************************************* */
745  JacobianFactor result(*this);
746  if (model_) {
747  result.model_->WhitenInPlace(result.Ab_.full());
748  result.model_ = SharedDiagonal();
749  }
750  return result;
751 }
752 
753 /* ************************************************************************* */
755  HessianFactor hessian(*this);
756  return hessian.negate();
757 }
758 
759 /* ************************************************************************* */
762  const Ordering& keys) {
764  graph.add(*this);
765  return EliminateQR(graph, keys);
766 }
767 
768 /* ************************************************************************* */
769 void JacobianFactor::setModel(bool anyConstrained, const Vector& sigmas) {
770  if ((size_t) sigmas.size() != this->rows())
771  throw InvalidNoiseModel(this->rows(), sigmas.size());
772  if (anyConstrained)
774  else
776 }
777 
778 /* ************************************************************************* */
779 std::pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr> EliminateQR(
780  const GaussianFactorGraph& factors, const Ordering& keys) {
782  // Combine and sort variable blocks in elimination order
783  JacobianFactor::shared_ptr jointFactor;
784  try {
785  jointFactor = std::make_shared<JacobianFactor>(factors, keys);
786  } catch (std::invalid_argument&) {
788  "EliminateQR was called with a request to eliminate variables that are not\n"
789  "involved in the provided factors.");
790  }
791 
792  // Do dense elimination
793  // The following QR variants eliminate to fully triangular or trapezoidal
794  SharedDiagonal noiseModel;
795  VerticalBlockMatrix& Ab = jointFactor->Ab_;
796  if (jointFactor->model_) {
797  // The noiseModel QR can, in the case of constraints, yield a "staggered" QR where
798  // some rows have more leading zeros than in an upper triangular matrix.
799  // In either case, QR will put zeros below the "diagonal".
800  jointFactor->model_ = jointFactor->model_->QR(Ab.matrix());
801  } else {
802  // The inplace variant will have no valid rows anymore below m==n
803  // and only entries above the diagonal are valid.
804  inplace_QR(Ab.matrix());
805  // We zero below the diagonal to agree with the result from noieModel QR
806  Ab.matrix().triangularView<Eigen::StrictlyLower>().setZero();
807  size_t m = Ab.rows(), n = Ab.cols() - 1;
808  size_t maxRank = min(m, n);
809  jointFactor->model_ = noiseModel::Unit::Create(maxRank);
810  }
811 
812  // Split elimination result into conditional and remaining factor
813  GaussianConditional::shared_ptr conditional = //
814  jointFactor->splitConditional(keys.size());
815 
816  return make_pair(conditional, jointFactor);
817 }
818 
819 /* ************************************************************************* */
821  gttic(JacobianFactor_splitConditional);
822 
823  if (!model_) {
824  throw std::invalid_argument(
825  "JacobianFactor::splitConditional cannot be given a nullptr noise model");
826  }
827 
828  if (nrFrontals > size()) {
829  throw std::invalid_argument(
830  "JacobianFactor::splitConditional was requested to split off more variables than exist.");
831  }
832 
833  // Convert nr of keys to number of scalar columns
834  DenseIndex frontalDim = Ab_.range(0, nrFrontals).cols();
835 
836  // Check that the noise model has at least this dimension
837  // If this is *not* the case, we do not have enough information on the frontal variables.
838  if ((DenseIndex)model_->dim() < frontalDim)
840 
841  // Restrict the matrix to be in the first nrFrontals variables and create the conditional
842  const DenseIndex originalRowEnd = Ab_.rowEnd();
843  Ab_.rowEnd() = Ab_.rowStart() + frontalDim;
844  SharedDiagonal conditionalNoiseModel;
845  conditionalNoiseModel =
846  noiseModel::Diagonal::Sigmas(model_->sigmas().segment(Ab_.rowStart(), Ab_.rows()));
847  GaussianConditional::shared_ptr conditional =
848  std::make_shared<GaussianConditional>(Base::keys_, nrFrontals, Ab_, conditionalNoiseModel);
849 
850  const DenseIndex maxRemainingRows =
851  std::min(Ab_.cols(), originalRowEnd) - Ab_.rowStart() - frontalDim;
852  const DenseIndex remainingRows = std::min(model_->sigmas().size() - frontalDim, maxRemainingRows);
853  Ab_.rowStart() += frontalDim;
854  Ab_.rowEnd() = Ab_.rowStart() + remainingRows;
855  Ab_.firstBlock() += nrFrontals;
856 
857  // Take lower-right block of Ab to get the new factor
858  keys_.erase(begin(), begin() + nrFrontals);
859  // Set sigmas with the right model
860  if (model_->isConstrained())
861  model_ = noiseModel::Constrained::MixedSigmas(model_->sigmas().tail(remainingRows));
862  else
863  model_ = noiseModel::Diagonal::Sigmas(model_->sigmas().tail(remainingRows));
864  assert(model_->dim() == (size_t)Ab_.rows());
865 
866  return conditional;
867 }
868 
869 } // namespace gtsam
gttoc
#define gttoc(label)
Definition: timing.h:296
Dims
std::vector< Eigen::Index > Dims
Definition: testGaussianConditional.cpp:46
timing.h
Timing utilities.
gtsam::VerticalBlockMatrix::rowEnd
const DenseIndex & rowEnd() const
Definition: VerticalBlockMatrix.h:178
gtsam::VariableSlots::Empty
static const GTSAM_EXPORT size_t Empty
Definition: VariableSlots.h:56
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::JacobianFactor::splitConditional
std::shared_ptr< GaussianConditional > splitConditional(size_t nrFrontals)
Definition: JacobianFactor.cpp:820
GaussianConditional.h
Conditional Gaussian Base class.
gtsam::JacobianFactor::unweighted_error
Vector unweighted_error(const VectorValues &c) const
Definition: JacobianFactor.cpp:472
Eigen::Block
Expression of a fixed-size or dynamic-size block.
Definition: Block.h:103
A3
static const double A3[]
Definition: expn.h:8
gtsam::VariableSlots
Definition: VariableSlots.h:51
RowsBlockXpr
Block< Derived, Dynamic, internal::traits< Derived >::ColsAtCompileTime, IsRowMajor > RowsBlockXpr
Definition: BlockMethods.h:23
gtsam::JacobianFactor::Ab_
VerticalBlockMatrix Ab_
Definition: JacobianFactor.h:106
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
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
d
static const double d[K][N]
Definition: igam.h:11
gtsam::noiseModel::Constrained::MixedSigmas
static shared_ptr MixedSigmas(const Vector &mu, const Vector &sigmas)
Definition: NoiseModel.cpp:377
test_constructor::sigmas
Vector1 sigmas
Definition: testHybridNonlinearFactor.cpp:52
gtsam::JacobianFactor::get_model
const SharedDiagonal & get_model() const
Definition: JacobianFactor.h:292
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
c
Scalar Scalar * c
Definition: benchVecAdd.cpp:17
gtsam::JacobianFactor::isConstrained
bool isConstrained() const
Definition: JacobianFactor.h:270
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
pybind_wrapper_test_script.this
this
Definition: pybind_wrapper_test_script.py:38
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::JacobianFactor
Definition: JacobianFactor.h:91
gtsam::FastMap< Key, size_t >
gtsam::GaussianFactor
Definition: GaussianFactor.h:38
formatter
const KeyFormatter & formatter
Definition: treeTraversal-inst.h:204
gtsam::VerticalBlockMatrix::range
Block range(DenseIndex startBlock, DenseIndex endBlock)
Definition: VerticalBlockMatrix.h:132
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
gtsam::Factor::empty
bool empty() const
Whether the factor is empty (involves zero variables).
Definition: Factor.h:131
gtsam::VerticalBlockMatrix::full
Block full()
Definition: VerticalBlockMatrix.h:159
gtsam::Matrix
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
gtsam::InvalidNoiseModel
Definition: linearExceptions.h:106
gtsam::noiseModel::Diagonal::Sigmas
static shared_ptr Sigmas(const Vector &sigmas, bool smart=true)
Definition: NoiseModel.cpp:292
Ordering.h
Variable ordering for the elimination algorithm.
gtsam::Factor
Definition: Factor.h:70
gtsam::matlabFormat
const Eigen::IOFormat & matlabFormat()
Definition: Matrix.cpp:140
gtsam::JacobianFactor::rows
size_t rows() const
Definition: JacobianFactor.h:284
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::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
gtsam::JacobianFactor::negate
GaussianFactor::shared_ptr negate() const override
Definition: JacobianFactor.cpp:754
gtsam::JacobianFactor::hessianDiagonalAdd
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
Definition: JacobianFactor.cpp:517
rows
int rows
Definition: Tutorial_commainit_02.cpp:1
gtsam::choleskyCareful
pair< size_t, bool > choleskyCareful(Matrix &ATA, int order)
Definition: base/cholesky.cpp:76
gtsam::JacobianFactor::getb
const constBVector getb() const
Definition: JacobianFactor.h:298
gtsam::JacobianFactor::operator*
Vector operator*(const VectorValues &x) const
Definition: JacobianFactor.cpp:602
gtsam::JacobianFactor::eliminate
std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > eliminate(const Ordering &keys)
Definition: JacobianFactor.cpp:761
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
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
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")
ss
static std::stringstream ss
Definition: testBTree.cpp:31
gtsam::JacobianFactor::multiplyHessianAdd
void multiplyHessianAdd(double alpha, const VectorValues &x, VectorValues &y) const override
Definition: JacobianFactor.cpp:639
gtsam::JacobianFactor::model_
noiseModel::Diagonal::shared_ptr model_
Definition: JacobianFactor.h:107
gtsam::VerticalBlockMatrix::firstBlock
const DenseIndex & firstBlock() const
Definition: VerticalBlockMatrix.h:184
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::VerticalBlockMatrix::rowStart
const DenseIndex & rowStart() const
Definition: VerticalBlockMatrix.h:172
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::JacobianFactor::fillTerms
void fillTerms(const TERMS &terms, const Vector &b, const SharedDiagonal &noiseModel)
Internal function to fill blocks and set dimensions.
Definition: JacobianFactor-inl.h:60
J
JacobiRotation< float > J
Definition: Jacobi_makeJacobi.cpp:3
gtsam::JacobianFactor::gradient
Vector gradient(Key key, const VectorValues &x) const override
Compute the gradient wrt a key at any values.
Definition: JacobianFactor.cpp:708
gtsam::JacobianFactor::getDim
DenseIndex getDim(const_iterator variable) const override
Definition: JacobianFactor.h:277
gtsam::VerticalBlockMatrix
Definition: VerticalBlockMatrix.h:44
gtsam::VectorValues
Definition: VectorValues.h:74
j
std::ptrdiff_t j
Definition: tut_arithmetic_redux_minmax.cpp:2
make_tuple
tuple make_tuple()
Definition: cast.h:1383
I
#define I
Definition: main.h:112
gtsam::row
const MATRIX::ConstRowXpr row(const MATRIX &A, size_t j)
Definition: base/Matrix.h:221
gtsam::JacobianFactor::information
Matrix information() const override
Definition: JacobianFactor.cpp:506
gtsam::JacobianFactor::jacobianUnweighted
std::pair< Matrix, Vector > jacobianUnweighted() const
Returns (dense) A,b pair associated with factor, does not bake in weights.
Definition: JacobianFactor.cpp:724
gtsam::JacobianFactor::gradientAtZero
VectorValues gradientAtZero() const override
A'*b for Jacobian.
Definition: JacobianFactor.cpp:691
gtsam::JacobianFactor::EliminateQR
friend GTSAM_EXPORT std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:779
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
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::noiseModel::Unit::Create
static shared_ptr Create(size_t dim)
Definition: NoiseModel.h:631
Eigen::PlainObjectBase::rows
EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT
Definition: PlainObjectBase.h:143
gtsam::SharedDiagonal
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:764
A2
static const double A2[]
Definition: expn.h:7
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:196
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::VerticalBlockMatrix::nBlocks
DenseIndex nBlocks() const
Block count.
Definition: VerticalBlockMatrix.h:123
Eigen::StrictlyLower
@ StrictlyLower
Definition: Constants.h:221
VectorValues.h
Factor Graph Values.
m
Matrix3f m
Definition: AngleAxis_mimic_euler.cpp:1
transform
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
gtsam::Factor::end
const_iterator end() const
Definition: Factor.h:149
gtsam::FastList
Definition: FastList.h:43
Eigen::Map
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
size_t
std::size_t size_t
Definition: wrap/pybind11/include/pybind11/detail/common.h:490
gtsam::JacobianFactor::cols
size_t cols() const
Definition: JacobianFactor.h:289
model
noiseModel::Diagonal::shared_ptr model
Definition: doc/Code/Pose2SLAMExample.cpp:7
g
void g(const string &key, int i)
Definition: testBTree.cpp:41
ordering
static enum @1096 ordering
gtsam::JacobianFactor::error_vector
Vector error_vector(const VectorValues &c) const
Definition: JacobianFactor.cpp:480
y
Scalar * y
Definition: level1_cplx_impl.h:124
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)
E
DiscreteKey E(5, 2)
JacobianFactor.h
tree::f
Point2(* f)(const Point3 &, OptionalJacobian< 2, 3 >)
Definition: testExpression.cpp:218
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
gtsam::b
const G & b
Definition: Group.h:79
gtsam::Pairs
std::vector< std::pair< Key, Matrix > > Pairs
Definition: JacobianFactor.cpp:45
VariableSlots.h
VariableSlots describes the structure of a combined factor in terms of where each block comes from in...
gtsam::inplace_QR
void inplace_QR(Matrix &A)
Definition: Matrix.cpp:637
gtsam::Factor::const_iterator
KeyVector::const_iterator const_iterator
Const iterator over keys.
Definition: Factor.h:83
gtsam::orderedSlotsHelper
FastVector< VariableSlots::const_iterator > orderedSlotsHelper(const Ordering &ordering, const VariableSlots &variableSlots)
Definition: JacobianFactor.cpp:286
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:281
gtsam
traits
Definition: SFMdata.h:40
gtsam::VerticalBlockMatrix::cols
DenseIndex cols() const
Column size.
Definition: VerticalBlockMatrix.h:120
gtsam::Factor::keys_
KeyVector keys_
The keys involved in this factor.
Definition: Factor.h:88
gtsam::Factor::front
Key front() const
First key.
Definition: Factor.h:134
i1
double i1(double x)
Definition: i1.c:150
gtsam::JacobianFactor::equals
bool equals(const GaussianFactor &lf, double tol=1e-9) const override
assert equality up to a tolerance
Definition: JacobianFactor.cpp:421
gtsam::Factor::keys
const KeyVector & keys() const
Access the factor's involved variable keys.
Definition: Factor.h:143
gtsam::JacobianFactor::hessianBlockDiagonal
std::map< Key, Matrix > hessianBlockDiagonal() const override
Return the block diagonal of the Hessian for this factor.
Definition: JacobianFactor.cpp:551
gtsam::DenseIndex
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:103
gtsam::VerticalBlockMatrix::matrix
const Matrix & matrix() const
Definition: VerticalBlockMatrix.h:190
std
Definition: BFloat16.h:88
A1
static const double A1[]
Definition: expn.h:6
gtsam::JacobianFactor::JacobianFactorHelper
void JacobianFactorHelper(const GaussianFactorGraph &graph, const FastVector< VariableSlots::const_iterator > &orderedSlots)
Definition: JacobianFactor.cpp:207
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
JacobianFactor
gtsam::VerticalBlockMatrix::rows
DenseIndex rows() const
Row size.
Definition: VerticalBlockMatrix.h:117
gtsam::GaussianFactor::Slot
static DenseIndex Slot(const CONTAINER &keys, Key key)
Definition: GaussianFactor.h:175
gtsam::JacobianFactor::print
void print(const std::string &s="", const KeyFormatter &formatter=DefaultKeyFormatter) const override
print with optional string
Definition: JacobianFactor.cpp:404
gtsam::JacobianFactor::error
double error(const VectorValues &c) const override
Definition: JacobianFactor.cpp:487
gtsam::JacobianFactor::transposeMultiplyAdd
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
Definition: JacobianFactor.cpp:619
min
#define min(a, b)
Definition: datatypes.h:19
gtsam::tol
const G double tol
Definition: Group.h:79
gtsam::JacobianFactor::shared_ptr
std::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: JacobianFactor.h:97
setZero
v setZero(3)
gtsam::JacobianFactor::JacobianFactor
JacobianFactor()
Definition: JacobianFactor.cpp:48
N
#define N
Definition: igam.h:9
gtsam::IndeterminantLinearSystemException
Definition: linearExceptions.h:94
gtsam::JacobianFactor::getA
constABlock getA() const
Definition: JacobianFactor.h:304
pos
Definition: example-NearestNeighbor.cpp:32
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
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
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::JacobianFactor::whiten
JacobianFactor whiten() const
Definition: JacobianFactor.cpp:744
gtsam::JacobianFactor::setModel
void setModel(bool anyConstrained, const Vector &sigmas)
Definition: JacobianFactor.cpp:769
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::JacobianFactor::augmentedJacobianUnweighted
Matrix augmentedJacobianUnweighted() const
Definition: JacobianFactor.cpp:739
Scatter.h
Maps global variable indices to slot indices.
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::JacobianFactor::augmentedInformation
Matrix augmentedInformation() const override
Definition: JacobianFactor.cpp:495
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::formatMatrixIndented
std::string formatMatrixIndented(const std::string &label, const Matrix &matrix, bool makeVectorHorizontal)
Definition: Matrix.cpp:598
gtsam::JacobianFactor::updateHessian
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
Definition: JacobianFactor.cpp:564
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:48