ISAM2.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 
20 #include <gtsam/nonlinear/ISAM2.h>
22 
23 #include <gtsam/base/debug.h>
24 #include <gtsam/base/timing.h>
27 
28 #include <algorithm>
29 #include <map>
30 #include <utility>
31 #include <variant>
32 
33 using namespace std;
34 
35 namespace gtsam {
36 
37 // Instantiate base class
38 template class BayesTree<ISAM2Clique>;
39 
40 /* ************************************************************************* */
41 ISAM2::ISAM2(const ISAM2Params& params) : params_(params), update_count_(0) {
42  if (std::holds_alternative<ISAM2DoglegParams>(params_.optimizationParams)) {
43  doglegDelta_ =
44  std::get<ISAM2DoglegParams>(params_.optimizationParams).initialDelta;
45  }
46 }
47 
48 /* ************************************************************************* */
50  if (std::holds_alternative<ISAM2DoglegParams>(params_.optimizationParams)) {
51  doglegDelta_ =
52  std::get<ISAM2DoglegParams>(params_.optimizationParams).initialDelta;
53  }
54 }
55 
56 /* ************************************************************************* */
57 bool ISAM2::equals(const ISAM2& other, double tol) const {
58  return Base::equals(other, tol) && theta_.equals(other.theta_, tol) &&
59  variableIndex_.equals(other.variableIndex_, tol) &&
62 }
63 
64 /* ************************************************************************* */
66  const ISAM2UpdateParams& updateParams, const FastList<Key>& affectedKeys,
67  const KeySet& relinKeys) {
69  FactorIndexSet candidates =
71 
72  gttic(affectedKeysSet);
73  // for fast lookup below
74  KeySet affectedKeysSet;
75  affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end());
76  gttoc(affectedKeysSet);
77 
78  gttic(check_candidates_and_linearize);
79  GaussianFactorGraph linearized;
80  for (const FactorIndex idx : candidates) {
81  bool inside = true;
82  bool useCachedLinear = params_.cacheLinearizedFactors;
83  for (Key key : nonlinearFactors_[idx]->keys()) {
84  if (affectedKeysSet.find(key) == affectedKeysSet.end()) {
85  inside = false;
86  break;
87  }
88  if (useCachedLinear && relinKeys.find(key) != relinKeys.end())
89  useCachedLinear = false;
90  }
91  if (inside) {
92  if (useCachedLinear) {
93 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
94  assert(linearFactors_[idx]);
95  assert(linearFactors_[idx]->keys() == nonlinearFactors_[idx]->keys());
96 #endif
97  linearized.push_back(linearFactors_[idx]);
98  } else {
99  auto linearFactor = nonlinearFactors_[idx]->linearize(theta_);
100  linearized.push_back(linearFactor);
102 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS
103  assert(linearFactors_[idx]->keys() == linearFactor->keys());
104 #endif
105  linearFactors_[idx] = linearFactor;
106  }
107  }
108  }
109  }
110  gttoc(check_candidates_and_linearize);
111 
112  return linearized;
113 }
114 
115 /* ************************************************************************* */
116 void ISAM2::recalculate(const ISAM2UpdateParams& updateParams,
117  const KeySet& relinKeys, ISAM2Result* result) {
120 
121  if (!result->markedKeys.empty() || !result->observedKeys.empty()) {
122  // Remove top of Bayes tree and convert to a factor graph:
123  // (a) For each affected variable, remove the corresponding clique and all
124  // parents up to the root. (b) Store orphaned sub-trees \BayesTree_{O} of
125  // removed cliques.
126  GaussianBayesNet affectedBayesNet;
127  Cliques orphans;
128  this->removeTop(
129  KeyVector(result->markedKeys.begin(), result->markedKeys.end()),
130  &affectedBayesNet, &orphans);
131 
132  // FactorGraph<GaussianFactor> factors(affectedBayesNet);
133  // bug was here: we cannot reuse the original factors, because then the
134  // cached factors get messed up [all the necessary data is actually
135  // contained in the affectedBayesNet, including what was passed in from the
136  // boundaries, so this would be correct; however, in the process we also
137  // generate new cached_ entries that will be wrong (ie. they don't contain
138  // what would be passed up at a certain point if batch elimination was done,
139  // but that's what we need); we could choose not to update cached_ from
140  // here, but then the new information (and potentially different variable
141  // ordering) is not reflected in the cached_ values which again will be
142  // wrong] so instead we have to retrieve the original linearized factors AND
143  // add the cached factors from the boundary
144 
145  // ordering provides all keys in conditionals, there cannot be others
146  // because path to root included
147  gttic(affectedKeys);
148  FastList<Key> affectedKeys;
149  for (const auto& conditional : affectedBayesNet)
150  affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(),
151  conditional->endFrontals());
152  gttoc(affectedKeys);
153 
154  KeySet affectedKeysSet;
155  static const double kBatchThreshold = 0.65;
156  if (affectedKeys.size() >= theta_.size() * kBatchThreshold) {
157  // Do a batch step - reorder and relinearize all variables
158  recalculateBatch(updateParams, &affectedKeysSet, result);
159  } else {
160  recalculateIncremental(updateParams, relinKeys, affectedKeys,
161  &affectedKeysSet, &orphans, result);
162  }
163 
164  // Root clique variables for detailed results
165  if (result->detail && params_.enableDetailedResults) {
166  for (const auto& root : roots_)
167  for (Key var : *root->conditional())
168  result->detail->variableStatus[var].inRootClique = true;
169  }
170 
171  // Update replaced keys mask (accumulates until back-substitution happens)
172  deltaReplacedMask_.insert(affectedKeysSet.begin(), affectedKeysSet.end());
173  }
174 }
175 
176 /* ************************************************************************* */
178  KeySet* affectedKeysSet, ISAM2Result* result) {
180 
181  gttic(add_keys);
182 
183  // copy the keys from the variableIndex_ to the affectedKeysSet
184  for (const auto& [key, _] : variableIndex_) {
185  affectedKeysSet->insert(key);
186  }
187  // Removed unused keys:
188  VariableIndex affectedFactorsVarIndex = variableIndex_;
189 
190  affectedFactorsVarIndex.removeUnusedVariables(result->unusedKeys.begin(),
191  result->unusedKeys.end());
192 
193  for (const Key key : result->unusedKeys) {
194  affectedKeysSet->erase(key);
195  }
196  gttoc(add_keys);
197 
198  gttic(ordering);
199  Ordering order;
200  if (updateParams.constrainedKeys) {
201  order = Ordering::ColamdConstrained(affectedFactorsVarIndex,
202  *updateParams.constrainedKeys);
203  } else {
204  if (theta_.size() > result->observedKeys.size()) {
205  // Only if some variables are unconstrained
206  FastMap<Key, int> constraintGroups;
207  for (Key var : result->observedKeys) constraintGroups[var] = 1;
208  order = Ordering::ColamdConstrained(affectedFactorsVarIndex,
209  constraintGroups);
210  } else {
211  order = Ordering::Colamd(affectedFactorsVarIndex);
212  }
213  }
214  gttoc(ordering);
215 
216  gttic(linearize);
217  auto linearized = nonlinearFactors_.linearize(theta_);
218  if (params_.cacheLinearizedFactors) linearFactors_ = *linearized;
219  gttoc(linearize);
220 
221  gttic(eliminate);
222  ISAM2BayesTree::shared_ptr bayesTree =
224  GaussianEliminationTree(*linearized, affectedFactorsVarIndex, order))
226  .first;
227  gttoc(eliminate);
228 
229  gttic(insert);
230  roots_.clear();
231  roots_.insert(roots_.end(), bayesTree->roots().begin(),
232  bayesTree->roots().end());
233  nodes_.clear();
234  nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
235  gttoc(insert);
236 
237  result->variablesReeliminated = affectedKeysSet->size();
239 
240  // Reeliminated keys for detailed results
242  for (Key key : theta_.keys()) {
243  result->detail->variableStatus[key].isReeliminated = true;
244  }
245  }
246 }
247 
248 /* ************************************************************************* */
250  const KeySet& relinKeys,
251  const FastList<Key>& affectedKeys,
252  KeySet* affectedKeysSet, Cliques* orphans,
253  ISAM2Result* result) {
255  const bool debug = ISDEBUG("ISAM2 recalculate");
256 
257  // 2. Add the new factors \Factors' into the resulting factor graph
258  FastList<Key> affectedAndNewKeys;
259  affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(),
260  affectedKeys.end());
261  affectedAndNewKeys.insert(affectedAndNewKeys.end(),
262  result->observedKeys.begin(),
263  result->observedKeys.end());
265  relinearizeAffectedFactors(updateParams, affectedAndNewKeys, relinKeys);
266 
267  if (debug) {
268  factors.print("Relinearized factors: ");
269  std::cout << "Affected keys: ";
270  for (const Key key : affectedKeys) {
271  std::cout << key << " ";
272  }
273  std::cout << std::endl;
274  }
275 
276  // Reeliminated keys for detailed results
278  for (Key key : affectedAndNewKeys) {
279  result->detail->variableStatus[key].isReeliminated = true;
280  }
281  }
282 
283  result->variablesReeliminated = affectedAndNewKeys.size();
284  result->factorsRecalculated = factors.size();
285 
286  gttic(cached);
287  // Add the cached intermediate results from the boundary of the orphans...
288  GaussianFactorGraph cachedBoundary =
290  if (debug) cachedBoundary.print("Boundary factors: ");
291  factors.push_back(cachedBoundary);
292  gttoc(cached);
293 
294  gttic(orphans);
295  // Add the orphaned subtrees
296  for (const auto& orphan : *orphans)
298  gttoc(orphans);
299 
300  // 3. Re-order and eliminate the factor graph into a Bayes net (Algorithm
301  // [alg:eliminate]), and re-assemble into a new Bayes tree (Algorithm
302  // [alg:BayesTree])
303 
304  gttic(reorder_and_eliminate);
305 
306  gttic(list_to_set);
307  // create a partial reordering for the new and contaminated factors
308  // result->markedKeys are passed in: those variables will be forced to the
309  // end in the ordering
310  affectedKeysSet->insert(result->markedKeys.begin(), result->markedKeys.end());
311  affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end());
312  gttoc(list_to_set);
313 
314  VariableIndex affectedFactorsVarIndex(factors);
315 
316  gttic(ordering_constraints);
317  // Create ordering constraints
318  FastMap<Key, int> constraintGroups;
319  if (updateParams.constrainedKeys) {
320  constraintGroups = *updateParams.constrainedKeys;
321  } else {
322  constraintGroups = FastMap<Key, int>();
323  const int group =
324  result->observedKeys.size() < affectedFactorsVarIndex.size() ? 1 : 0;
325  for (Key var : result->observedKeys)
326  constraintGroups.emplace(var, group);
327  }
328 
329  // Remove unaffected keys from the constraints
330  for (FastMap<Key, int>::iterator iter = constraintGroups.begin();
331  iter != constraintGroups.end();
332  /*Incremented in loop ++iter*/) {
333  if (result->unusedKeys.exists(iter->first) ||
334  !affectedKeysSet->exists(iter->first))
335  constraintGroups.erase(iter++);
336  else
337  ++iter;
338  }
339  gttoc(ordering_constraints);
340 
341  // Generate ordering
342  gttic(Ordering);
343  const Ordering ordering =
344  Ordering::ColamdConstrained(affectedFactorsVarIndex, constraintGroups);
345  gttoc(Ordering);
346 
347  // Do elimination
348  GaussianEliminationTree etree(factors, affectedFactorsVarIndex, ordering);
349  auto bayesTree = ISAM2JunctionTree(etree)
351  .first;
352  gttoc(reorder_and_eliminate);
353 
354  gttic(reassemble);
355  roots_.insert(roots_.end(), bayesTree->roots().begin(),
356  bayesTree->roots().end());
357  nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
358  gttoc(reassemble);
359 
360  // 4. The orphans have already been inserted during elimination
361 }
362 
363 /* ************************************************************************* */
364 void ISAM2::addVariables(const Values& newTheta,
366  gttic(addNewVariables);
367 
368  theta_.insert(newTheta);
369  if (ISDEBUG("ISAM2 AddVariables")) newTheta.print("The new variables are: ");
370  // Add zeros into the VectorValues
371  delta_.insert(newTheta.zeroVectors());
372  deltaNewton_.insert(newTheta.zeroVectors());
373  RgProd_.insert(newTheta.zeroVectors());
374 
375  // New keys for detailed results
376  if (detail && params_.enableDetailedResults) {
377  for (Key key : newTheta.keys()) {
378  detail->variableStatus[key].isNew = true;
379  }
380  }
381 }
382 
383 /* ************************************************************************* */
384 void ISAM2::removeVariables(const KeySet& unusedKeys) {
386 
387  variableIndex_.removeUnusedVariables(unusedKeys.begin(), unusedKeys.end());
388  for (Key key : unusedKeys) {
389  delta_.erase(key);
391  RgProd_.erase(key);
392  deltaReplacedMask_.erase(key);
394  theta_.erase(key);
395  fixedVariables_.erase(key);
396  }
397 }
398 
399 /* ************************************************************************* */
401  const NonlinearFactorGraph& newFactors, const Values& newTheta,
402  const FactorIndices& removeFactorIndices,
403  const std::optional<FastMap<Key, int> >& constrainedKeys,
404  const std::optional<FastList<Key> >& noRelinKeys,
405  const std::optional<FastList<Key> >& extraReelimKeys,
406  bool force_relinearize) {
408  params.constrainedKeys = constrainedKeys;
409  params.extraReelimKeys = extraReelimKeys;
410  params.force_relinearize = force_relinearize;
411  params.noRelinKeys = noRelinKeys;
412  params.removeFactorIndices = removeFactorIndices;
413 
414  return update(newFactors, newTheta, params);
415 }
416 
417 /* ************************************************************************* */
419  const Values& newTheta,
420  const ISAM2UpdateParams& updateParams) {
421  gttic(ISAM2_update);
422  this->update_count_ += 1;
423  UpdateImpl::LogStartingUpdate(newFactors, *this);
425  UpdateImpl update(params_, updateParams);
426 
427  // Update delta if we need it to check relinearization later
429  updateDelta(updateParams.forceFullSolve);
430 
431  // 1. Add any new factors \Factors:=\Factors\cup\Factors'.
432  update.pushBackFactors(newFactors, &nonlinearFactors_, &linearFactors_,
434  &result.keysWithRemovedFactors);
435  update.computeUnusedKeys(newFactors, variableIndex_,
436  result.keysWithRemovedFactors, &result.unusedKeys);
437 
438  // 2. Initialize any new variables \Theta_{new} and add
439  // \Theta:=\Theta\cup\Theta_{new}.
440  addVariables(newTheta, result.details());
443 
444  // 3. Mark linear update
445  update.gatherInvolvedKeys(newFactors, nonlinearFactors_,
446  result.keysWithRemovedFactors, &result.markedKeys);
447  update.updateKeys(result.markedKeys, &result);
448 
449  KeySet relinKeys;
450  result.variablesRelinearized = 0;
451  if (update.relinarizationNeeded(update_count_)) {
452  // 4. Mark keys in \Delta above threshold \beta:
453  relinKeys = update.gatherRelinearizeKeys(roots_, delta_, fixedVariables_,
454  &result.markedKeys);
455  update.recordRelinearizeDetail(relinKeys, result.details());
456  if (!relinKeys.empty()) {
457  // 5. Mark cliques that involve marked variables \Theta_{J} and ancestors.
458  update.findFluid(roots_, relinKeys, &result.markedKeys, result.details());
459  // 6. Update linearization point for marked variables:
460  // \Theta_{J}:=\Theta_{J}+\Delta_{J}.
461  theta_.retractMasked(delta_, relinKeys);
462  }
463  result.variablesRelinearized = result.markedKeys.size();
464  }
465 
466  // 7. Linearize new factors
467  update.linearizeNewFactors(newFactors, theta_, nonlinearFactors_.size(),
469  update.augmentVariableIndex(newFactors, result.newFactorsIndices,
470  &variableIndex_);
471 
472  // 8. Redo top of Bayes tree and update data structures
473  recalculate(updateParams, relinKeys, &result);
474  if (!result.unusedKeys.empty()) removeVariables(result.unusedKeys);
475  result.cliques = this->nodes().size();
476 
479  return result;
480 }
481 
482 /* ************************************************************************* */
484  const FastList<Key>& leafKeysList,
485  FactorIndices* marginalFactorsIndices,
486  FactorIndices* deletedFactorsIndices) {
487  // Convert to ordered set
488  KeySet leafKeys(leafKeysList.begin(), leafKeysList.end());
489 
490  // Keep track of marginal factors - map from clique to the marginal factors
491  // that should be incorporated into it, passed up from it's children.
492  // multimap<sharedClique, GaussianFactor::shared_ptr> marginalFactors;
493  map<Key, vector<GaussianFactor::shared_ptr> > marginalFactors;
494 
495  // Keep track of variables removed in subtrees
496  KeySet leafKeysRemoved;
497 
498  // Keep track of factors that get summarized by removing cliques
499  FactorIndexSet factorIndicesToRemove;
500 
501  // Remove the subtree and throw away the cliques
502  auto trackingRemoveSubtree = [&](const sharedClique& subtreeRoot) {
503  const Cliques removedCliques = this->removeSubtree(subtreeRoot);
504  for (const sharedClique& removedClique : removedCliques) {
505  auto cg = removedClique->conditional();
506  marginalFactors.erase(cg->front());
507  leafKeysRemoved.insert(cg->beginFrontals(), cg->endFrontals());
508  for (Key frontal : cg->frontals()) {
509  // Add to factors to remove
510  const auto& involved = variableIndex_[frontal];
511  factorIndicesToRemove.insert(involved.begin(), involved.end());
512 #if !defined(NDEBUG)
513  // Check for non-leaf keys
514  if (!leafKeys.exists(frontal))
515  throw std::runtime_error(
516  "Requesting to marginalize variables that are not leaves, "
517  "the ISAM2 object is now in an inconsistent state so should "
518  "no longer be used.");
519 #endif
520  }
521  }
522  return removedCliques;
523  };
524 
525  // Remove each variable and its subtrees
526  for (Key j : leafKeys) {
527  if (!leafKeysRemoved.exists(j)) { // If the index was not already removed
528  // by removing another subtree
529 
530  // Traverse up the tree to find the root of the marginalized subtree
532  while (clique->parent_.use_count() != 0) {
533  // Check if parent contains a marginalized leaf variable. Only need to
534  // check the first variable because it is the closest to the leaves.
535  sharedClique parent = clique->parent();
536  if (leafKeys.exists(parent->conditional()->front()))
537  clique = parent;
538  else
539  break;
540  }
541 
542  // See if we should remove the whole clique
543  bool marginalizeEntireClique = true;
544  for (Key frontal : clique->conditional()->frontals()) {
545  if (!leafKeys.exists(frontal)) {
546  marginalizeEntireClique = false;
547  break;
548  }
549  }
550 
551  // Remove either the whole clique or part of it
552  if (marginalizeEntireClique) {
553  // Remove the whole clique and its subtree, and keep the marginal
554  // factor.
555  auto marginalFactor = clique->cachedFactor();
556  // We do not need the marginal factors associated with this clique
557  // because their information is already incorporated in the new
558  // marginal factor. So, now associate this marginal factor with the
559  // parent of this clique.
560  marginalFactors[clique->parent()->conditional()->front()].push_back(
562  // Now remove this clique and its subtree - all of its marginal
563  // information has been stored in marginalFactors.
564  trackingRemoveSubtree(clique);
565  } else {
566  // Reeliminate the current clique and the marginals from its children,
567  // then keep only the marginal on the non-marginalized variables. We
568  // get the childrens' marginals from any existing children, plus
569  // the marginals from the marginalFactors multimap, which come from any
570  // subtrees already marginalized out.
571 
572  // Add child marginals and remove marginalized subtrees
574  KeySet factorsInSubtreeRoot;
575  Cliques subtreesToRemove;
576  for (const sharedClique& child : clique->children) {
577  // Remove subtree if child depends on any marginalized keys
578  for (Key parent : child->conditional()->parents()) {
579  if (leafKeys.exists(parent)) {
580  subtreesToRemove.push_back(child);
581  graph.push_back(child->cachedFactor()); // Add child marginal
582  break;
583  }
584  }
585  }
586  Cliques childrenRemoved;
587  for (const sharedClique& subtree : subtreesToRemove) {
588  const Cliques removed = trackingRemoveSubtree(subtree);
589  childrenRemoved.insert(childrenRemoved.end(), removed.begin(),
590  removed.end());
591  }
592 
593  // Add the factors that are pulled into the current clique by the
594  // marginalized variables. These are the factors that involve
595  // *marginalized* frontal variables in this clique but do not involve
596  // frontal variables of any of its children.
597  // TODO(dellaert): reuse cached linear factors
598  KeySet factorsFromMarginalizedInClique_step1;
599  for (Key frontal : clique->conditional()->frontals()) {
600  if (leafKeys.exists(frontal))
601  factorsFromMarginalizedInClique_step1.insert(
602  variableIndex_[frontal].begin(), variableIndex_[frontal].end());
603  }
604  // Remove any factors in subtrees that we're removing at this step
605  for (const sharedClique& removedChild : childrenRemoved) {
606  for (Key indexInClique : removedChild->conditional()->frontals()) {
607  for (Key factorInvolving : variableIndex_[indexInClique]) {
608  factorsFromMarginalizedInClique_step1.erase(factorInvolving);
609  }
610  }
611  }
612  // Create factor graph from factor indices
613  for (const auto index : factorsFromMarginalizedInClique_step1) {
614  graph.push_back(nonlinearFactors_[index]->linearize(theta_));
615  }
616 
617  // Reeliminate the linear graph to get the marginal and discard the
618  // conditional
619  auto cg = clique->conditional();
620  const KeySet cliqueFrontals(cg->beginFrontals(), cg->endFrontals());
621  KeyVector cliqueFrontalsToEliminate;
622  std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(),
623  leafKeys.begin(), leafKeys.end(),
624  std::back_inserter(cliqueFrontalsToEliminate));
625  auto eliminationResult1 = params_.getEliminationFunction()(
626  graph, Ordering(cliqueFrontalsToEliminate));
627 
628  // Add the resulting marginal
629  if (eliminationResult1.second)
630  marginalFactors[cg->front()].push_back(eliminationResult1.second);
631 
632  // Split the current clique
633  // Find the position of the last leaf key in this clique
634  DenseIndex nToRemove = 0;
635  while (leafKeys.exists(cg->keys()[nToRemove])) ++nToRemove;
636 
637  // Make the clique's matrix appear as a subset
638  const DenseIndex dimToRemove = cg->matrixObject().offset(nToRemove);
639  cg->matrixObject().firstBlock() = nToRemove;
640  cg->matrixObject().rowStart() = dimToRemove;
641 
642  // Change the keys in the clique
643  KeyVector originalKeys;
644  originalKeys.swap(cg->keys());
645  cg->keys().assign(originalKeys.begin() + nToRemove, originalKeys.end());
646  cg->nrFrontals() -= nToRemove;
647 
648  // Add to factorIndicesToRemove any factors involved in frontals of
649  // current clique
650  for (Key frontal : cliqueFrontalsToEliminate) {
651  const auto& involved = variableIndex_[frontal];
652  factorIndicesToRemove.insert(involved.begin(), involved.end());
653  }
654 
655  // Add removed keys
656  leafKeysRemoved.insert(cliqueFrontalsToEliminate.begin(),
657  cliqueFrontalsToEliminate.end());
658  }
659  }
660  }
661 
662  // At this point we have updated the BayesTree, now update the remaining iSAM2
663  // data structures
664 
665  // Gather factors to add - the new marginal factors
666  GaussianFactorGraph factorsToAdd;
667  for (const auto& key_factors : marginalFactors) {
668  for (const auto& factor : key_factors.second) {
669  if (factor) {
670  factorsToAdd.push_back(factor);
671  if (marginalFactorsIndices)
672  marginalFactorsIndices->push_back(nonlinearFactors_.size());
674  std::make_shared<LinearContainerFactor>(factor));
676  for (Key factorKey : *factor) {
677  fixedVariables_.insert(factorKey);
678  }
679  }
680  }
681  }
682  variableIndex_.augment(factorsToAdd); // Augment the variable index
683 
684  // Remove the factors to remove that have been summarized in the newly-added
685  // marginal factors
686  NonlinearFactorGraph removedFactors;
687  for (const auto index : factorIndicesToRemove) {
688  removedFactors.push_back(nonlinearFactors_[index]);
689  nonlinearFactors_.remove(index);
691  }
692  variableIndex_.remove(factorIndicesToRemove.begin(),
693  factorIndicesToRemove.end(), removedFactors);
694 
695  if (deletedFactorsIndices)
696  deletedFactorsIndices->assign(factorIndicesToRemove.begin(),
697  factorIndicesToRemove.end());
698 
699  // Remove the marginalized variables
700  removeVariables(KeySet(leafKeys.begin(), leafKeys.end()));
701 }
702 
703 /* ************************************************************************* */
704 // Marked const but actually changes mutable delta
705 void ISAM2::updateDelta(bool forceFullSolve) const {
707  if (std::holds_alternative<ISAM2GaussNewtonParams>(params_.optimizationParams)) {
708  // If using Gauss-Newton, update with wildfireThreshold
709  const ISAM2GaussNewtonParams& gaussNewtonParams =
710  std::get<ISAM2GaussNewtonParams>(params_.optimizationParams);
711  const double effectiveWildfireThreshold =
712  forceFullSolve ? 0.0 : gaussNewtonParams.wildfireThreshold;
713  gttic(Wildfire_update);
715  effectiveWildfireThreshold, &delta_);
716  deltaReplacedMask_.clear();
717  gttoc(Wildfire_update);
718  } else if (std::holds_alternative<ISAM2DoglegParams>(params_.optimizationParams)) {
719  // If using Dogleg, do a Dogleg step
720  const ISAM2DoglegParams& doglegParams =
721  std::get<ISAM2DoglegParams>(params_.optimizationParams);
722  const double effectiveWildfireThreshold =
723  forceFullSolve ? 0.0 : doglegParams.wildfireThreshold;
724 
725  // Do one Dogleg iteration
726  gttic(Dogleg_Iterate);
727 
728  // Compute Newton's method step
729  gttic(Wildfire_update);
731  roots_, deltaReplacedMask_, effectiveWildfireThreshold, &deltaNewton_);
732  gttoc(Wildfire_update);
733 
734  // Compute steepest descent step
735  const VectorValues gradAtZero = this->gradientAtZero(); // Compute gradient
737  &RgProd_); // Update RgProd
739  gradAtZero, RgProd_); // Compute gradient search point
740 
741  // Clear replaced keys mask because now we've updated deltaNewton_ and
742  // RgProd_
743  deltaReplacedMask_.clear();
744 
745  // Compute dogleg point
748  *doglegDelta_, doglegParams.adaptationMode, dx_u, deltaNewton_,
750  doglegParams.verbose));
751  gttoc(Dogleg_Iterate);
752 
753  gttic(Copy_dx_d);
754  // Update Delta and linear step
755  doglegDelta_ = doglegResult.delta;
756  delta_ =
757  doglegResult
758  .dx_d; // Copy the VectorValues containing with the linear solution
759  gttoc(Copy_dx_d);
760  } else {
761  throw std::runtime_error("iSAM2: unknown ISAM2Params type");
762  }
763 }
764 
765 /* ************************************************************************* */
767  gttic(ISAM2_calculateEstimate);
768  const VectorValues& delta(getDelta());
769  gttic(Expmap);
770  return theta_.retract(delta);
771  gttoc(Expmap);
772 }
773 
774 /* ************************************************************************* */
776  const Vector& delta = getDelta()[key];
777  return *theta_.at(key).retract_(delta);
778 }
779 
780 /* ************************************************************************* */
782  updateDelta(true); // Force full solve when updating delta_
783  return theta_.retract(delta_);
784 }
785 
786 /* ************************************************************************* */
789  ->information()
790  .inverse();
791 }
792 
793 /* ************************************************************************* */
795  if (!deltaReplacedMask_.empty()) updateDelta();
796  return delta_;
797 }
798 
799 /* ************************************************************************* */
800 double ISAM2::error(const VectorValues& x) const {
801  return GaussianFactorGraph(*this).error(x);
802 }
803 
804 /* ************************************************************************* */
806  // Create result
807  VectorValues g;
808 
809  // Sum up contributions for each clique
810  for (const auto& root : this->roots()) root->addGradientAtZero(&g);
811 
812  return g;
813 }
814 
815 } // namespace gtsam
const gtsam::Symbol key('X', 0)
void removeVariables(const KeySet &unusedKeys)
Definition: ISAM2.cpp:384
GaussianFactorGraph relinearizeAffectedFactors(const ISAM2UpdateParams &updateParams, const FastList< Key > &affectedKeys, const KeySet &relinKeys)
Definition: ISAM2.cpp:65
static void LogRecalculateKeys(const ISAM2Result &result)
Definition: ISAM2-impl.h:470
A insert(1, 2)=0
void removeTop(const KeyVector &keys, BayesNetType *bn, Cliques *orphans)
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const
Definition: ISAM2-impl.h:198
static size_t UpdateGaussNewtonDelta(const ISAM2::Roots &roots, const KeySet &replacedKeys, double wildfireThreshold, VectorValues *delta)
Definition: ISAM2-impl.cpp:47
Matrix marginalCovariance(Key key) const
Definition: ISAM2.cpp:787
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
size_t size() const
The number of variable entries. This is equal to the number of unique variable Keys.
Definition: VariableIndex.h:78
size_t variablesReeliminated
Definition: ISAM2Result.h:82
Global debugging flags.
VectorValues RgProd_
Definition: ISAM2.h:65
const Nodes & nodes() const
Definition: BayesTree.h:146
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminate(const Eliminate &function) const
static IterationResult Iterate(double delta, TrustRegionAdaptationMode mode, const VectorValues &dx_u, const VectorValues &dx_n, const M &Rd, const F &f, const VALUES &x0, const double f_error, const bool verbose=false)
const ValueType at(Key j) const
Definition: Values-inl.h:204
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
Definition: ISAM2-impl.h:412
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
Definition: ISAM2-impl.h:500
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
Definition: ISAM2-impl.h:140
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
Definition: ISAM2-impl.h:487
static VectorValues ComputeGradientSearch(const VectorValues &gradAtZero, const VectorValues &RgProd)
Definition: ISAM2-impl.cpp:145
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
bool exists(const VALUE &e) const
Definition: FastSet.h:98
KeyVector keys() const
Definition: Values.cpp:218
const GaussianFactorGraph factors
VariableIndex variableIndex_
Definition: ISAM2.h:52
void recalculateIncremental(const ISAM2UpdateParams &updateParams, const KeySet &relinKeys, const FastList< Key > &affectedKeys, KeySet *affectedKeysSet, Cliques *orphans, ISAM2Result *result)
Perform an incremental update of the factor graph to return a new Bayes Tree with affected keys...
Definition: ISAM2.cpp:249
Pose2_ Expmap(const Vector3_ &xi)
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
Definition: ISAM2-impl.h:400
bool equals(const This &other, double tol=1e-9) const
Definition: BFloat16.h:88
iterator iter(handle obj)
Definition: pytypes.h:2273
void remove(size_t i)
Definition: FactorGraph.h:393
iterator insert(const std::pair< Key, Vector > &key_value)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
Definition: ISAM2.cpp:400
double error(const VectorValues &x) const
virtual bool equals(const ISAM2 &other, double tol=1e-9) const
Definition: ISAM2.cpp:57
DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode
Definition: ISAM2Params.h:74
NonlinearFactorGraph graph
std::optional< double > doglegDelta_
Definition: ISAM2.h:90
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
Definition: ISAM2-impl.h:451
static enum @1107 ordering
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
Print out graph to std::cout, with optional key formatter.
const_iterator end() const
Iterator to the first variable entry.
ISAM2Params params_
Definition: ISAM2.h:87
ptrdiff_t DenseIndex
The index type for Eigen objects.
Definition: types.h:108
void g(const string &key, int i)
Definition: testBTree.cpp:41
static constexpr bool debug
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
Definition: ISAM2-impl.h:370
static const SmartProjectionParams params
Values retract(const VectorValues &delta) const
Definition: Values.cpp:98
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
Definition: ISAM2-impl.h:174
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
static Ordering Colamd(const FACTOR_GRAPH &graph)
KeySet fixedVariables_
Definition: ISAM2.h:94
FactorIndices newFactorsIndices
Definition: ISAM2Result.h:95
void augment(const FG &factors, const FactorIndices *newFactorIndices=nullptr)
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:36
size_t size() const
Definition: FactorGraph.h:334
#define gttic(label)
Definition: timing.h:295
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: Values.cpp:66
Cliques removeSubtree(const sharedClique &subtree)
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
#define ISDEBUG(S)
Definition: debug.h:60
Eigen::VectorXd Vector
Definition: Vector.h:38
std::optional< FastMap< Key, int > > constrainedKeys
NonlinearFactorGraph nonlinearFactors_
Definition: ISAM2.h:81
Values result
VectorValues zeroVectors() const
Definition: Values.cpp:260
KeyVector observedKeys
Definition: ISAM2Result.h:103
GaussianFactorGraph::Eliminate getEliminationFunction() const
Definition: ISAM2Params.h:323
Class that stores detailed iSAM2 result.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
void recalculateBatch(const ISAM2UpdateParams &updateParams, KeySet *affectedKeysSet, ISAM2Result *result)
Definition: ISAM2.cpp:177
size_t variablesRelinearized
Definition: ISAM2Result.h:74
void recalculate(const ISAM2UpdateParams &updateParams, const KeySet &relinKeys, ISAM2Result *result)
Remove marked top and either recalculate in batch or incrementally.
Definition: ISAM2.cpp:116
KeySet keysWithRemovedFactors
Definition: ISAM2Result.h:106
GaussianFactorGraph linearFactors_
Definition: ISAM2.h:84
void retractMasked(const VectorValues &delta, const KeySet &mask)
Definition: Values.cpp:103
VectorValues gradientAtZero() const
Definition: ISAM2.cpp:805
DetailedResults * details()
Return pointer to detail, 0 if no detail requested.
Definition: ISAM2Result.h:163
std::optional< double > errorBefore
Definition: ISAM2Result.h:52
StatusMap variableStatus
The status of each variable during this update, see VariableStatus.
Definition: ISAM2Result.h:151
Values theta_
Definition: ISAM2.h:48
size_t size() const
Definition: Values.h:178
OptimizationParams optimizationParams
Definition: ISAM2Params.h:151
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
bool equals(const Values &other, double tol=1e-9) const
Definition: Values.cpp:77
int update_count_
Definition: ISAM2.h:96
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
double error(const Values &values) const
Bayes Tree is a tree of cliques of a Bayes Chain.
bool equals(const VariableIndex &other, double tol=0.0) const
Test for equality (for unit tests and debug assertions).
void marginalizeLeaves(const FastList< Key > &leafKeys, FactorIndices *marginalFactorsIndices=nullptr, FactorIndices *deletedFactorsIndices=nullptr)
Definition: ISAM2.cpp:483
KeySet deltaReplacedMask_
Definition: ISAM2.h:76
static Ordering ColamdConstrained(const FACTOR_GRAPH &graph, const FastMap< Key, int > &groups)
std::shared_ptr< This > shared_ptr
Definition: ISAM2-impl.h:46
const_iterator begin() const
Iterator to the first variable entry.
traits
Definition: chartTesting.h:28
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
Definition: ISAM2-impl.h:227
std::optional< FastList< Key > > noRelinKeys
void unsafe_erase(typename Base::iterator position)
Definition: ConcurrentMap.h:94
const sharedClique & clique(Key j) const
Definition: BayesTree.h:155
static size_t UpdateRgProd(const ISAM2::Roots &roots, const KeySet &replacedKeys, const VectorValues &gradAtZero, VectorValues *RgProd)
Definition: ISAM2-impl.cpp:130
constexpr descr< N - 1 > _(char const (&text)[N])
Definition: descr.h:109
#define gttoc(label)
Definition: timing.h:296
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
const Roots & roots() const
Definition: BayesTree.h:152
std::optional< double > errorAfter
Definition: ISAM2Result.h:64
FactorIndices removeFactorIndices
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, std::optional< double > *result) const
Definition: ISAM2-impl.h:191
const VectorValues & getDelta() const
Definition: ISAM2.cpp:794
void addVariables(const Values &newTheta, ISAM2Result::DetailedResults *detail=0)
Definition: ISAM2.cpp:364
void erase(Key var)
Definition: VectorValues.h:226
Values calculateBestEstimate() const
Definition: ISAM2.cpp:781
VectorValues delta_
Definition: ISAM2.h:61
FastSet< Key > KeySet
Definition: Key.h:90
void insert(Key j, const Value &val)
Definition: Values.cpp:155
void updateDelta(bool forceFullSolve=false) const
Definition: ISAM2.cpp:705
std::optional< FastList< Key > > extraReelimKeys
VectorValues deltaNewton_
Definition: ISAM2.h:63
const G double tol
Definition: Group.h:86
const KeyVector keys
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Definition: Key.h:86
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
Definition: ISAM2-impl.h:435
bool verbose
Whether Dogleg prints iteration and convergence information.
Definition: ISAM2Params.h:77
void erase(Key j)
Definition: Values.cpp:210
void removeUnusedVariables(ITERATOR firstKey, ITERATOR lastKey)
Remove unused empty variables (in debug mode verifies they are empty).
std::uint64_t FactorIndex
Integer nonlinear factor index type.
Definition: types.h:105
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
double error(const VectorValues &x) const
Definition: ISAM2.cpp:800
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
Values calculateEstimate() const
Definition: ISAM2.cpp:766
std::optional< DetailedResults > detail
Definition: ISAM2Result.h:156
std::ptrdiff_t j
const ISAM2Params & params() const
Definition: ISAM2.h:279
Timing utilities.
size_t factorsRecalculated
Definition: ISAM2Result.h:86
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
Definition: ISAM2-impl.h:115
bool relinarizationNeeded(size_t update_count) const
Definition: ISAM2-impl.h:133


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:25