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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:18