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  /* ************************************************************************* */
117  const VerticalBlockMatrix& augmentedMatrix) const {
118  // Check noise model dimension
119  if (model && (DenseIndex)model->dim() != augmentedMatrix.rows())
120  throw InvalidNoiseModel(augmentedMatrix.rows(), model->dim());
121 
122  // Check number of variables
123  if ((DenseIndex)Base::keys_.size() != augmentedMatrix.nBlocks() - 1)
124  throw std::invalid_argument(
125  "Error in JacobianFactor constructor input. Number of provided keys "
126  "plus one for the RHS vector must equal the number of provided "
127  "matrix blocks.");
128 
129  // Check RHS dimension
130  if (augmentedMatrix(augmentedMatrix.nBlocks() - 1).cols() != 1)
131  throw std::invalid_argument(
132  "Error in JacobianFactor constructor input. The last provided "
133  "matrix block must be the RHS vector, but the last provided block "
134  "had more than one column.");
135 }
136 
137 /* ************************************************************************* */
138 // Helper functions for combine constructor
139 namespace {
140 std::tuple<FastVector<DenseIndex>, DenseIndex, DenseIndex> _countDims(
142  const FastVector<VariableSlots::const_iterator>& variableSlots) {
143  gttic(countDims);
144 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
145  FastVector<DenseIndex> varDims(variableSlots.size(), numeric_limits<DenseIndex>::max());
146 #else
147  FastVector<DenseIndex> varDims(variableSlots.size(),
149 #endif
150  DenseIndex m = 0;
151  DenseIndex n = 0;
152  for (size_t jointVarpos = 0; jointVarpos < variableSlots.size();
153  ++jointVarpos) {
154  const VariableSlots::const_iterator& slots = variableSlots[jointVarpos];
155 
156  assert(slots->second.size() == factors.size());
157 
158  bool foundVariable = false;
159  for (size_t sourceFactorI = 0; sourceFactorI < slots->second.size();
160  ++sourceFactorI) {
161  const size_t sourceVarpos = slots->second[sourceFactorI];
162  if (sourceVarpos != VariableSlots::Empty) {
163  const JacobianFactor& sourceFactor = *factors[sourceFactorI];
164  if (sourceFactor.cols() > 1) {
165  foundVariable = true;
166  DenseIndex vardim = sourceFactor.getDim(
167  sourceFactor.begin() + sourceVarpos);
168 
169 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
170  if(varDims[jointVarpos] == numeric_limits<DenseIndex>::max()) {
171  varDims[jointVarpos] = vardim;
172  n += vardim;
173  } else {
174  if(!(varDims[jointVarpos] == vardim)) {
175  std::stringstream ss;
176  ss << "Factor " << sourceFactorI << " variable " << DefaultKeyFormatter(sourceFactor.keys()[sourceVarpos]) <<
177  " has different dimensionality of " << vardim << " instead of " << varDims[jointVarpos];
178  throw std::runtime_error(ss.str());
179  }
180  }
181 #else
182 
183  varDims[jointVarpos] = vardim;
184  n += vardim;
185  break;
186 #endif
187  }
188  }
189  }
190 
191  if (!foundVariable)
192  throw std::invalid_argument(
193  "Unable to determine dimensionality for all variables");
194  }
195 
197  m += factor->rows();
198  }
199 
200 #if !defined(NDEBUG) && defined(GTSAM_EXTRA_CONSISTENCY_CHECKS)
201  for(DenseIndex d: varDims) {
202  assert(d != numeric_limits<DenseIndex>::max());
203  }
204 #endif
205 
206  return std::make_tuple(varDims, m, n);
207 }
208 
209 /* ************************************************************************* */
210 FastVector<JacobianFactor::shared_ptr> _convertOrCastToJacobians(
211  const GaussianFactorGraph& factors) {
212  gttic(Convert_to_Jacobians);
213  FastVector<JacobianFactor::shared_ptr> jacobians;
214  jacobians.reserve(factors.size());
216  if (factor) {
217  if (JacobianFactor::shared_ptr jf = std::dynamic_pointer_cast<
219  jacobians.push_back(jf);
220  else
221  jacobians.push_back(std::make_shared<JacobianFactor>(*factor));
222  }
223  }
224  return jacobians;
225 }
226 }
227 
228 /* ************************************************************************* */
230  const FastVector<VariableSlots::const_iterator>& orderedSlots) {
231 
232  // Cast or convert to Jacobians
233  FastVector<JacobianFactor::shared_ptr> jacobians = _convertOrCastToJacobians(
234  graph);
235 
236  // Count dimensions
237  const auto [varDims, m, n] = _countDims(jacobians, orderedSlots);
238 
239  // Allocate matrix and copy keys in order
240  gttic(allocate);
241  Ab_ = VerticalBlockMatrix(varDims, m, true); // Allocate augmented matrix
242  Base::keys_.resize(orderedSlots.size());
243  // Copy keys in order
244  std::transform(orderedSlots.begin(), orderedSlots.end(),
245  Base::keys_.begin(),
246  [](const VariableSlots::const_iterator& it) {return it->first;});
247  gttoc(allocate);
248 
249  // Loop over slots in combined factor and copy blocks from source factors
250  gttic(copy_blocks);
251  size_t combinedSlot = 0;
252  for(VariableSlots::const_iterator varslot: orderedSlots) {
253  JacobianFactor::ABlock destSlot(this->getA(this->begin() + combinedSlot));
254  // Loop over source jacobians
255  DenseIndex nextRow = 0;
256  for (size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
257  // Slot in source factor
258  const size_t sourceSlot = varslot->second[factorI];
259  const DenseIndex sourceRows = jacobians[factorI]->rows();
260  if (sourceRows > 0) {
262  destSlot.middleRows(nextRow, sourceRows));
263  // Copy if exists in source factor, otherwise set zero
264  if (sourceSlot != VariableSlots::Empty)
265  destBlock = jacobians[factorI]->getA(
266  jacobians[factorI]->begin() + sourceSlot);
267  else
268  destBlock.setZero();
269  nextRow += sourceRows;
270  }
271  }
272  ++combinedSlot;
273  }
274  gttoc(copy_blocks);
275 
276  // Copy the RHS vectors and sigmas
277  gttic(copy_vectors);
278  bool anyConstrained = false;
279  std::optional<Vector> sigmas;
280  // Loop over source jacobians
281  DenseIndex nextRow = 0;
282  for (size_t factorI = 0; factorI < jacobians.size(); ++factorI) {
283  const DenseIndex sourceRows = jacobians[factorI]->rows();
284  if (sourceRows > 0) {
285  this->getb().segment(nextRow, sourceRows) = jacobians[factorI]->getb();
286  if (jacobians[factorI]->get_model()) {
287  // If the factor has a noise model and we haven't yet allocated sigmas, allocate it.
288  if (!sigmas)
289  sigmas = Vector::Constant(m, 1.0);
290  sigmas->segment(nextRow, sourceRows) =
291  jacobians[factorI]->get_model()->sigmas();
292  if (jacobians[factorI]->isConstrained())
293  anyConstrained = true;
294  }
295  nextRow += sourceRows;
296  }
297  }
298  gttoc(copy_vectors);
299 
300  if (sigmas)
301  this->setModel(anyConstrained, *sigmas);
302 }
303 
304 /* ************************************************************************* */
305 // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
306 // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
307 // be added after all of the ordered variables.
309  const Ordering& ordering,
310  const VariableSlots& variableSlots) {
311  gttic(Order_slots);
312 
314  orderedSlots.reserve(variableSlots.size());
315 
316  // If an ordering is provided, arrange the slots first that ordering
318  size_t nOrderingSlotsUsed = 0;
319  orderedSlots.resize(ordering.size());
320  FastMap<Key, size_t> inverseOrdering = ordering.invert();
321  for (VariableSlots::const_iterator item = variableSlots.begin();
322  item != variableSlots.end(); ++item) {
323  FastMap<Key, size_t>::const_iterator orderingPosition =
324  inverseOrdering.find(item->first);
325  if (orderingPosition == inverseOrdering.end()) {
326  unorderedSlots.push_back(item);
327  } else {
328  orderedSlots[orderingPosition->second] = item;
329  ++nOrderingSlotsUsed;
330  }
331  }
332  if (nOrderingSlotsUsed != ordering.size())
333  throw std::invalid_argument(
334  "The ordering provided to the JacobianFactor combine constructor\n"
335  "contained extra variables that did not appear in the factors to combine.");
336  // Add the remaining slots
337  for(VariableSlots::const_iterator item: unorderedSlots) {
338  orderedSlots.push_back(item);
339  }
340 
341  gttoc(Order_slots);
342 
343  return orderedSlots;
344 }
345 
346 /* ************************************************************************* */
348  gttic(JacobianFactor_combine_constructor);
349 
350  // Compute VariableSlots if one was not provided
351  // Binds reference, does not copy VariableSlots
352  const VariableSlots & variableSlots = VariableSlots(graph);
353 
354  gttic(Order_slots);
355  // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
356  // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
357  // be added after all of the ordered variables.
359  orderedSlots.reserve(variableSlots.size());
360 
361  // If no ordering is provided, arrange the slots as they were, which will be sorted
362  // numerically since VariableSlots uses a map sorting on Key.
363  for (VariableSlots::const_iterator item = variableSlots.begin();
364  item != variableSlots.end(); ++item)
365  orderedSlots.push_back(item);
366  gttoc(Order_slots);
367 
368  JacobianFactorHelper(graph, orderedSlots);
369 }
370 
371 /* ************************************************************************* */
373  const VariableSlots& p_variableSlots) {
374  gttic(JacobianFactor_combine_constructor);
375 
376  // Binds reference, does not copy VariableSlots
377  const VariableSlots & variableSlots = p_variableSlots;
378 
379  gttic(Order_slots);
380  // Order variable slots - we maintain the vector of ordered slots, as well as keep a list
381  // 'unorderedSlots' of any variables discovered that are not in the ordering. Those will then
382  // be added after all of the ordered variables.
384  orderedSlots.reserve(variableSlots.size());
385 
386  // If no ordering is provided, arrange the slots as they were, which will be sorted
387  // numerically since VariableSlots uses a map sorting on Key.
388  for (VariableSlots::const_iterator item = variableSlots.begin();
389  item != variableSlots.end(); ++item)
390  orderedSlots.push_back(item);
391  gttoc(Order_slots);
392 
393  JacobianFactorHelper(graph, orderedSlots);
394 }
395 
396 /* ************************************************************************* */
398  const Ordering& ordering) {
399  gttic(JacobianFactor_combine_constructor);
400 
401  // Compute VariableSlots if one was not provided
402  // Binds reference, does not copy VariableSlots
403  const VariableSlots & variableSlots = VariableSlots(graph);
404 
405  // Order variable slots
407  orderedSlotsHelper(ordering, variableSlots);
408 
409  JacobianFactorHelper(graph, orderedSlots);
410 }
411 
412 /* ************************************************************************* */
414  const Ordering& ordering,
415  const VariableSlots& p_variableSlots) {
416  gttic(JacobianFactor_combine_constructor);
417 
418  // Order variable slots
420  orderedSlotsHelper(ordering, p_variableSlots);
421 
422  JacobianFactorHelper(graph, orderedSlots);
423 }
424 
425 /* ************************************************************************* */
426 void JacobianFactor::print(const string& s,
427  const KeyFormatter& formatter) const {
428  if (!s.empty())
429  cout << s << "\n";
430  for (const_iterator key = begin(); key != end(); ++key) {
431  cout << " A[" << formatter(*key) << "] = ";
432  cout << getA(key).format(matlabFormat()) << endl;
433  }
434  cout << formatMatrixIndented(" b = ", getb(), true) << "\n";
435  if (model_)
436  model_->print(" Noise model: ");
437  else
438  cout << " No noise model" << endl;
439 }
440 
441 /* ************************************************************************* */
442 // Check if two linear factors are equal
443 bool JacobianFactor::equals(const GaussianFactor& f_, double tol) const {
444  static const bool verbose = false;
445  if (!dynamic_cast<const JacobianFactor*>(&f_)) {
446  if (verbose)
447  cout << "JacobianFactor::equals: Incorrect type" << endl;
448  return false;
449  } else {
450  const JacobianFactor& f(static_cast<const JacobianFactor&>(f_));
451 
452  // Check keys
453  if (keys() != f.keys()) {
454  if (verbose)
455  cout << "JacobianFactor::equals: keys do not match" << endl;
456  return false;
457  }
458 
459  // Check noise model
460  if ((model_ && !f.model_) || (!model_ && f.model_)) {
461  if (verbose)
462  cout << "JacobianFactor::equals: noise model mismatch" << endl;
463  return false;
464  }
465  if (model_ && f.model_ && !model_->equals(*f.model_, tol)) {
466  if (verbose)
467  cout << "JacobianFactor::equals: noise modesl are not equal" << endl;
468  return false;
469  }
470 
471  // Check matrix sizes
472  if (!(Ab_.rows() == f.Ab_.rows() && Ab_.cols() == f.Ab_.cols())) {
473  if (verbose)
474  cout << "JacobianFactor::equals: augmented size mismatch" << endl;
475  return false;
476  }
477 
478  // Check matrix contents
479  constABlock Ab1(Ab_.range(0, Ab_.nBlocks()));
480  constABlock Ab2(f.Ab_.range(0, f.Ab_.nBlocks()));
481  for (size_t row = 0; row < (size_t) Ab1.rows(); ++row)
482  if (!equal_with_abs_tol(Ab1.row(row), Ab2.row(row), tol)
483  && !equal_with_abs_tol(-Ab1.row(row), Ab2.row(row), tol)) {
484  if (verbose)
485  cout << "JacobianFactor::equals: matrix mismatch at row " << row << endl;
486  return false;
487  }
488 
489  return true;
490  }
491 }
492 
493 /* ************************************************************************* */
495  Vector e = -getb();
496  for (size_t pos = 0; pos < size(); ++pos)
497  e += Ab_(pos) * c[keys_[pos]];
498  return e;
499 }
500 
501 /* ************************************************************************* */
504  if (model_) model_->whitenInPlace(e);
505  return e;
506 }
507 
508 /* ************************************************************************* */
509 double JacobianFactor::error(const VectorValues& c) const {
511  // Use the noise model distance function to get the correct error if available.
512  if (model_) return 0.5 * model_->squaredMahalanobisDistance(e);
513  return 0.5 * e.dot(e);
514 }
515 
516 /* ************************************************************************* */
518  if (model_) {
519  Matrix AbWhitened = Ab_.full();
520  model_->WhitenInPlace(AbWhitened);
521  return AbWhitened.transpose() * AbWhitened;
522  } else {
523  return Ab_.full().transpose() * Ab_.full();
524  }
525 }
526 
527 /* ************************************************************************* */
529  if (model_) {
530  Matrix AWhitened = this->getA();
531  model_->WhitenInPlace(AWhitened);
532  return AWhitened.transpose() * AWhitened;
533  } else {
534  return this->getA().transpose() * this->getA();
535  }
536 }
537 
538 /* ************************************************************************* */
540  for (size_t pos = 0; pos < size(); ++pos) {
541  Key j = keys_[pos];
542  size_t nj = Ab_(pos).cols();
543  auto result = d.emplace(j, nj);
544 
545  Vector& dj = result.first->second;
546 
547  for (size_t k = 0; k < nj; ++k) {
548  Eigen::Ref<const Vector> column_k = Ab_(pos).col(k);
549  if (model_) {
550  Vector column_k_copy = column_k;
551  model_->whitenInPlace(column_k_copy);
552  if(!result.second)
553  dj(k) += dot(column_k_copy, column_k_copy);
554  else
555  dj(k) = dot(column_k_copy, column_k_copy);
556  } else {
557  if (!result.second)
558  dj(k) += dot(column_k, column_k);
559  else
560  dj(k) = dot(column_k, column_k);
561  }
562  }
563  }
564 }
565 
566 /* ************************************************************************* */
567 // Raw memory access version should be called in Regular Factors only currently
568 void JacobianFactor::hessianDiagonal(double* d) const {
569  throw std::runtime_error("JacobianFactor::hessianDiagonal raw memory access is allowed for Regular Factors only");
570 }
571 
572 /* ************************************************************************* */
573 map<Key, Matrix> JacobianFactor::hessianBlockDiagonal() const {
574  map<Key, Matrix> blocks;
575  for (size_t pos = 0; pos < size(); ++pos) {
576  Key j = keys_[pos];
577  Matrix Aj = Ab_(pos);
578  if (model_)
579  Aj = model_->Whiten(Aj);
580  blocks.emplace(j, Aj.transpose() * Aj);
581  }
582  return blocks;
583 }
584 
585 /* ************************************************************************* */
587  SymmetricBlockMatrix* info) const {
588  gttic(updateHessian_JacobianFactor);
589 
590  if (rows() == 0) return;
591 
592  // Whiten the factor if it has a noise model
593  const SharedDiagonal& model = get_model();
594  if (model && !model->isUnit()) {
595  if (model->isConstrained())
596  throw invalid_argument(
597  "JacobianFactor::updateHessian: cannot update information with "
598  "constrained noise model");
599  JacobianFactor whitenedFactor = whiten();
600  whitenedFactor.updateHessian(infoKeys, info);
601  } else {
602  // Ab_ is the augmented Jacobian matrix A, and we perform I += A'*A below
603  DenseIndex n = Ab_.nBlocks() - 1, N = info->nBlocks() - 1;
604 
605  // Pre-calculate slots
606  vector<DenseIndex> slots(n + 1);
607  for (DenseIndex j = 0; j < n; ++j) slots[j] = Slot(infoKeys, keys_[j]);
608  slots[n] = N;
609 
610  // Apply updates to the upper triangle
611  // Loop over blocks of A, including RHS with j==n
612  for (DenseIndex j = 0; j <= n; ++j) {
614  const DenseIndex J = slots[j];
615  // Fill off-diagonal blocks with Ai'*Aj
616  for (DenseIndex i = 0; i < j; ++i) {
617  const DenseIndex I = slots[i];
618  info->updateOffDiagonalBlock(I, J, Ab_(i).transpose() * Ab_j);
619  }
620  // Fill diagonal block with Aj'*Aj
621  info->diagonalBlock(J).rankUpdate(Ab_j.transpose());
622  }
623  }
624 }
625 
626 /* ************************************************************************* */
628  Vector Ax(Ab_.rows());
629  Ax.setZero();
630  if (empty())
631  return Ax;
632 
633  // Just iterate over all A matrices and multiply in correct config part
634  for (size_t pos = 0; pos < size(); ++pos) {
635  // http://eigen.tuxfamily.org/dox/TopicWritingEfficientProductExpression.html
636  Ax.noalias() += Ab_(pos) * x[keys_[pos]];
637  }
638 
639  if (model_) model_->whitenInPlace(Ax);
640  return Ax;
641 }
642 
643 /* ************************************************************************* */
645  VectorValues& x) const {
646  Vector E(e.size());
647  E.noalias() = alpha * e;
648  if (model_) model_->whitenInPlace(E);
649  // Just iterate over all A matrices and insert Ai^e into VectorValues
650  for (size_t pos = 0; pos < size(); ++pos) {
651  const Key j = keys_[pos];
652  // To avoid another malloc if key exists, we explicitly check
653  auto it = x.find(j);
654  if (it != x.end()) {
655  // http://eigen.tuxfamily.org/dox/TopicWritingEfficientProductExpression.html
656  it->second.noalias() += Ab_(pos).transpose() * E;
657  } else {
658  x.emplace(j, Ab_(pos).transpose() * E);
659  }
660  }
661 }
662 
663 /* ************************************************************************* */
665  VectorValues& y) const {
666  Vector Ax = (*this) * x;
668 }
669 
670 /* ************************************************************************* */
679 void JacobianFactor::multiplyHessianAdd(double alpha, const double* x, double* y,
680  const std::vector<size_t>& accumulatedDims) const {
681 
683  typedef Eigen::Map<Vector> VectorMap;
684  typedef Eigen::Map<const Vector> ConstVectorMap;
685 
686  if (empty())
687  return;
688  Vector Ax = Vector::Zero(Ab_.rows());
689 
693  for (size_t pos = 0; pos < size(); ++pos) {
694  size_t offset = accumulatedDims[keys_[pos]];
695  size_t dim = accumulatedDims[keys_[pos] + 1] - offset;
696  Ax += Ab_(pos) * ConstVectorMap(x + offset, dim);
697  }
699  if (model_) {
700  model_->whitenInPlace(Ax);
701  model_->whitenInPlace(Ax);
702  }
703 
705  Ax *= alpha;
706 
708  for (size_t pos = 0; pos < size(); ++pos) {
709  size_t offset = accumulatedDims[keys_[pos]];
710  size_t dim = accumulatedDims[keys_[pos] + 1] - offset;
711  VectorMap(y + offset, dim) += Ab_(pos).transpose() * Ax;
712  }
713 }
714 
715 /* ************************************************************************* */
717  VectorValues g;
718  Vector b = getb();
719  // Gradient is really -A'*b / sigma^2
720  // transposeMultiplyAdd will divide by sigma once, so we need one more
721  if (model_) model_->whitenInPlace(b);
722  this->transposeMultiplyAdd(-1.0, b, g); // g -= A'*b/sigma^2
723  return g;
724 }
725 
726 /* ************************************************************************* */
727 // Raw memory access version should be called in Regular Factors only currently
728 void JacobianFactor::gradientAtZero(double* d) const {
729  throw std::runtime_error("JacobianFactor::gradientAtZero raw memory access is allowed for Regular Factors only");
730 }
731 
732 /* ************************************************************************* */
734  // TODO: optimize it for JacobianFactor without converting to a HessianFactor
735  HessianFactor hessian(*this);
736  return hessian.gradient(key, x);
737 }
738 
739 /* ************************************************************************* */
740 pair<Matrix, Vector> JacobianFactor::jacobian() const {
741  pair<Matrix, Vector> result = jacobianUnweighted();
742  // divide in sigma so error is indeed 0.5*|Ax-b|
743  if (model_)
744  model_->WhitenSystem(result.first, result.second);
745  return result;
746 }
747 
748 /* ************************************************************************* */
749 pair<Matrix, Vector> JacobianFactor::jacobianUnweighted() const {
750  Matrix A(Ab_.range(0, size()));
751  Vector b(getb());
752  return make_pair(A, b);
753 }
754 
755 /* ************************************************************************* */
758  if (model_)
759  model_->WhitenInPlace(Ab);
760  return Ab;
761 }
762 
763 /* ************************************************************************* */
765  return Ab_.range(0, Ab_.nBlocks());
766 }
767 
768 /* ************************************************************************* */
770  JacobianFactor result(*this);
771  if (model_) {
772  result.model_->WhitenInPlace(result.Ab_.full());
773  result.model_ = SharedDiagonal();
774  }
775  return result;
776 }
777 
778 /* ************************************************************************* */
780  HessianFactor hessian(*this);
781  return hessian.negate();
782 }
783 
784 /* ************************************************************************* */
787  const Ordering& keys) {
789  graph.add(*this);
790  return EliminateQR(graph, keys);
791 }
792 
793 /* ************************************************************************* */
794 void JacobianFactor::setModel(bool anyConstrained, const Vector& sigmas) {
795  if ((size_t) sigmas.size() != this->rows())
796  throw InvalidNoiseModel(this->rows(), sigmas.size());
797  if (anyConstrained)
799  else
801 }
802 
803 /* ************************************************************************* */
804 std::pair<GaussianConditional::shared_ptr, JacobianFactor::shared_ptr> EliminateQR(
805  const GaussianFactorGraph& factors, const Ordering& keys) {
807  // Combine and sort variable blocks in elimination order
808  JacobianFactor::shared_ptr jointFactor;
809  try {
810  jointFactor = std::make_shared<JacobianFactor>(factors, keys);
811  } catch (std::invalid_argument&) {
813  "EliminateQR was called with a request to eliminate variables that are not\n"
814  "involved in the provided factors.");
815  }
816 
817  // Do dense elimination
818  // The following QR variants eliminate to fully triangular or trapezoidal
819  SharedDiagonal noiseModel;
820  VerticalBlockMatrix& Ab = jointFactor->Ab_;
821  if (jointFactor->model_) {
822  // The noiseModel QR can, in the case of constraints, yield a "staggered" QR where
823  // some rows have more leading zeros than in an upper triangular matrix.
824  // In either case, QR will put zeros below the "diagonal".
825  jointFactor->model_ = jointFactor->model_->QR(Ab.matrix());
826  } else {
827  // The inplace variant will have no valid rows anymore below m==n
828  // and only entries above the diagonal are valid.
829  inplace_QR(Ab.matrix());
830  // We zero below the diagonal to agree with the result from noieModel QR
831  Ab.matrix().triangularView<Eigen::StrictlyLower>().setZero();
832  size_t m = Ab.rows(), n = Ab.cols() - 1;
833  size_t maxRank = min(m, n);
834  jointFactor->model_ = noiseModel::Unit::Create(maxRank);
835  }
836 
837  // Split elimination result into conditional and remaining factor
838  GaussianConditional::shared_ptr conditional = //
839  jointFactor->splitConditional(keys.size());
840 
841  return make_pair(conditional, jointFactor);
842 }
843 
844 /* ************************************************************************* */
846  gttic(JacobianFactor_splitConditional);
847 
848  if (!model_) {
849  throw std::invalid_argument(
850  "JacobianFactor::splitConditional cannot be given a nullptr noise model");
851  }
852 
853  if (nrFrontals > size()) {
854  throw std::invalid_argument(
855  "JacobianFactor::splitConditional was requested to split off more variables than exist.");
856  }
857 
858  // Convert nr of keys to number of scalar columns
859  DenseIndex frontalDim = Ab_.range(0, nrFrontals).cols();
860 
861  // Check that the noise model has at least this dimension
862  // If this is *not* the case, we do not have enough information on the frontal variables.
863  if ((DenseIndex)model_->dim() < frontalDim)
865 
866  // Restrict the matrix to be in the first nrFrontals variables and create the conditional
867  const DenseIndex originalRowEnd = Ab_.rowEnd();
868  Ab_.rowEnd() = Ab_.rowStart() + frontalDim;
869  SharedDiagonal conditionalNoiseModel;
870  conditionalNoiseModel =
871  noiseModel::Diagonal::Sigmas(model_->sigmas().segment(Ab_.rowStart(), Ab_.rows()));
872  GaussianConditional::shared_ptr conditional =
873  std::make_shared<GaussianConditional>(Base::keys_, nrFrontals, Ab_, conditionalNoiseModel);
874 
875  const DenseIndex maxRemainingRows =
876  std::min(Ab_.cols(), originalRowEnd) - Ab_.rowStart() - frontalDim;
877  const DenseIndex remainingRows = std::min(model_->sigmas().size() - frontalDim, maxRemainingRows);
878  Ab_.rowStart() += frontalDim;
879  Ab_.rowEnd() = Ab_.rowStart() + remainingRows;
880  Ab_.firstBlock() += nrFrontals;
881 
882  // Take lower-right block of Ab to get the new factor
883  keys_.erase(begin(), begin() + nrFrontals);
884  // Set sigmas with the right model
885  if (model_->isConstrained())
886  model_ = noiseModel::Constrained::MixedSigmas(model_->sigmas().tail(remainingRows));
887  else
888  model_ = noiseModel::Diagonal::Sigmas(model_->sigmas().tail(remainingRows));
889  assert(model_->dim() == (size_t)Ab_.rows());
890 
891  return conditional;
892 }
893 
894 } // namespace gtsam
gttoc
#define gttoc(label)
Definition: timing.h:327
Dims
std::vector< Eigen::Index > Dims
Definition: testGaussianConditional.cpp:46
timing.h
Timing utilities.
gtsam::VerticalBlockMatrix::rowEnd
const DenseIndex & rowEnd() const
Definition: VerticalBlockMatrix.h:211
gtsam::JacobianFactor::checkAb
void checkAb(const SharedDiagonal &model, const VerticalBlockMatrix &augmentedMatrix) const
Common code between VerticalBlockMatrix constructors.
Definition: JacobianFactor.cpp:116
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:845
GaussianConditional.h
Conditional Gaussian Base class.
gtsam::JacobianFactor::unweighted_error
Vector unweighted_error(const VectorValues &c) const
Definition: JacobianFactor.cpp:494
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:298
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:276
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:165
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:192
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:129
gtsam::JacobianFactor::rows
size_t rows() const
Definition: JacobianFactor.h:290
gtsam::HessianFactor::negate
GaussianFactor::shared_ptr negate() const override
Definition: HessianFactor.cpp:376
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:740
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:779
gtsam::JacobianFactor::hessianDiagonalAdd
void hessianDiagonalAdd(VectorValues &d) const override
Add the current diagonal to a VectorValues instance.
Definition: JacobianFactor.cpp:539
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:304
gtsam::JacobianFactor::operator*
Vector operator*(const VectorValues &x) const
Definition: JacobianFactor.cpp:627
gtsam::JacobianFactor::eliminate
std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > eliminate(const Ordering &keys)
Definition: JacobianFactor.cpp:786
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:664
gtsam::JacobianFactor::model_
noiseModel::Diagonal::shared_ptr model_
Definition: JacobianFactor.h:107
gtsam::VerticalBlockMatrix::firstBlock
const DenseIndex & firstBlock() const
Definition: VerticalBlockMatrix.h:217
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:205
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:56
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:733
gtsam::JacobianFactor::getDim
DenseIndex getDim(const_iterator variable) const override
Definition: JacobianFactor.h:283
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:215
gtsam::JacobianFactor::information
Matrix information() const override
Definition: JacobianFactor.cpp:528
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:749
gtsam::JacobianFactor::gradientAtZero
VectorValues gradientAtZero() const override
A'*b for Jacobian.
Definition: JacobianFactor.cpp:716
gtsam::JacobianFactor::EliminateQR
friend GTSAM_EXPORT std::pair< std::shared_ptr< GaussianConditional >, shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:804
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:437
gtsam::JacobianFactor::augmentedJacobian
Matrix augmentedJacobian() const override
Definition: JacobianFactor.cpp:756
info
else if n * info
Definition: 3rdparty/Eigen/lapack/cholesky.cpp:18
gtsam::VerticalBlockMatrix::nBlocks
DenseIndex nBlocks() const
Block count.
Definition: VerticalBlockMatrix.h:156
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:295
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:502
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:626
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:308
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:153
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:443
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:573
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:223
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:229
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:150
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:426
gtsam::JacobianFactor::error
double error(const VectorValues &c) const override
Definition: JacobianFactor.cpp:509
gtsam::JacobianFactor::transposeMultiplyAdd
void transposeMultiplyAdd(double alpha, const Vector &e, VectorValues &x) const
Definition: JacobianFactor.cpp:644
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:310
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:769
gtsam::JacobianFactor::setModel
void setModel(bool anyConstrained, const Vector &sigmas)
Definition: JacobianFactor.cpp:794
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::JacobianFactor::augmentedJacobianUnweighted
Matrix augmentedJacobianUnweighted() const
Definition: JacobianFactor.cpp:764
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:517
gttic
#define gttic(label)
Definition: timing.h:326
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:587
gtsam::JacobianFactor::updateHessian
void updateHessian(const KeyVector &keys, SymmetricBlockMatrix *info) const override
Definition: JacobianFactor.cpp:586
gtsam::EliminateQR
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:804


gtsam
Author(s):
autogenerated on Sun Feb 16 2025 04:01:37