ISAM2-impl.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
19 #pragma once
20 
21 #include <gtsam/nonlinear/ISAM2.h>
23 
24 #include <gtsam/base/debug.h>
25 #include <gtsam/inference/JunctionTree-inst.h> // We need the inst file because we'll make a special JT templated on ISAM2
26 #include <gtsam/inference/Symbol.h>
30 
31 #include <algorithm>
32 #include <limits>
33 #include <string>
34 #include <utility>
35 #include <variant>
36 #include <cassert>
37 
38 namespace gtsam {
39 
40 /* ************************************************************************* */
41 // Special BayesTree class that uses ISAM2 cliques - this is the result of
42 // reeliminating ISAM2 subtrees.
43 class ISAM2BayesTree : public ISAM2::Base {
44  public:
45  typedef ISAM2::Base Base;
47  typedef std::shared_ptr<This> shared_ptr;
48 
50 };
51 
52 /* ************************************************************************* */
53 // Special JunctionTree class that produces ISAM2 BayesTree cliques, used for
54 // reeliminating ISAM2 subtrees.
56  : public JunctionTree<ISAM2BayesTree, GaussianFactorGraph> {
57  public:
60  typedef std::shared_ptr<This> shared_ptr;
61 
62  explicit ISAM2JunctionTree(const GaussianEliminationTree& eliminationTree)
63  : Base(eliminationTree) {}
64 };
65 
66 /* ************************************************************************* */
67 struct GTSAM_EXPORT DeltaImpl {
68  struct GTSAM_EXPORT PartialSolveResult {
70  };
71 
72  struct GTSAM_EXPORT ReorderingMode {
74  enum { /*AS_ADDED,*/ COLAMD } algorithm;
75  enum { NO_CONSTRAINT, CONSTRAIN_LAST } constrain;
76  std::optional<FastMap<Key, int> > constrainedKeys;
77  };
78 
82  static size_t UpdateGaussNewtonDelta(const ISAM2::Roots& roots,
83  const KeySet& replacedKeys,
84  double wildfireThreshold,
86 
91  static size_t UpdateRgProd(const ISAM2::Roots& roots,
92  const KeySet& replacedKeys,
93  const VectorValues& gradAtZero,
94  VectorValues* RgProd);
95 
99  static VectorValues ComputeGradientSearch(const VectorValues& gradAtZero,
100  const VectorValues& RgProd);
101 };
102 
103 /* ************************************************************************* */
109 struct GTSAM_EXPORT UpdateImpl {
112  UpdateImpl(const ISAM2Params& params, const ISAM2UpdateParams& updateParams)
113  : params_(params), updateParams_(updateParams) {}
114 
115  // Provide some debugging information at the start of update
116  static void LogStartingUpdate(const NonlinearFactorGraph& newFactors,
117  const ISAM2& isam2) {
118  gttic(pushBackFactors);
119  const bool debug = ISDEBUG("ISAM2 update");
120  const bool verbose = ISDEBUG("ISAM2 update verbose");
121 
122  if (verbose) {
123  std::cout << "ISAM2::update\n";
124  isam2.print("ISAM2: ");
125  }
126 
127  if (debug || verbose) {
128  newFactors.print("The new factors are: ");
129  }
130  }
131 
132  // Check relinearization if we're at the nth step, or we are using a looser
133  // loop relinerization threshold.
134  bool relinarizationNeeded(size_t update_count) const {
135  return updateParams_.force_relinearize ||
136  (params_.enableRelinearization &&
137  update_count % params_.relinearizeSkip == 0);
138  }
139 
140  // Add any new factors \Factors:=\Factors\cup\Factors'.
141  void pushBackFactors(const NonlinearFactorGraph& newFactors,
142  NonlinearFactorGraph* nonlinearFactors,
143  GaussianFactorGraph* linearFactors,
144  VariableIndex* variableIndex,
145  FactorIndices* newFactorsIndices,
146  KeySet* keysWithRemovedFactors) const {
147  gttic(pushBackFactors);
148 
149  // Perform the first part of the bookkeeping updates for adding new factors.
150  // Adds them to the complete list of nonlinear factors, and populates the
151  // list of new factor indices, both optionally finding and reusing empty
152  // factor slots.
153  *newFactorsIndices = nonlinearFactors->add_factors(
154  newFactors, params_.findUnusedFactorSlots);
155 
156  // Remove the removed factors
157  NonlinearFactorGraph removedFactors;
158  removedFactors.reserve(updateParams_.removeFactorIndices.size());
159  for (const auto index : updateParams_.removeFactorIndices) {
160  removedFactors.push_back(nonlinearFactors->at(index));
161  nonlinearFactors->remove(index);
162  if (params_.cacheLinearizedFactors) linearFactors->remove(index);
163  }
164 
165  // Remove removed factors from the variable index so we do not attempt to
166  // relinearize them
167  variableIndex->remove(updateParams_.removeFactorIndices.begin(),
168  updateParams_.removeFactorIndices.end(),
169  removedFactors);
170  *keysWithRemovedFactors = removedFactors.keys();
171  }
172 
173  // Get keys from removed factors and new factors, and compute unused keys,
174  // i.e., keys that are empty now and do not appear in the new factors.
175  void computeUnusedKeys(const NonlinearFactorGraph& newFactors,
176  const VariableIndex& variableIndex,
177  const KeySet& keysWithRemovedFactors,
178  KeySet* unusedKeys) const {
179  gttic(computeUnusedKeys);
180  KeySet removedAndEmpty;
181  for (Key key : keysWithRemovedFactors) {
182  if (variableIndex.empty(key))
183  removedAndEmpty.insert(removedAndEmpty.end(), key);
184  }
185  KeySet newFactorSymbKeys = newFactors.keys();
186  std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(),
187  newFactorSymbKeys.begin(), newFactorSymbKeys.end(),
188  std::inserter(*unusedKeys, unusedKeys->end()));
189  }
190 
191  // Calculate nonlinear error
192  void error(const NonlinearFactorGraph& nonlinearFactors,
193  const Values& estimate, std::optional<double>* result) const {
194  gttic(error);
195  *result = nonlinearFactors.error(estimate);
196  }
197 
198  // Mark linear update
199  void gatherInvolvedKeys(const NonlinearFactorGraph& newFactors,
200  const NonlinearFactorGraph& nonlinearFactors,
201  const KeySet& keysWithRemovedFactors,
202  KeySet* markedKeys) const {
203  gttic(gatherInvolvedKeys);
204  *markedKeys = newFactors.keys(); // Get keys from new factors
205  // Also mark keys involved in removed factors
206  markedKeys->insert(keysWithRemovedFactors.begin(),
207  keysWithRemovedFactors.end());
208 
209  // Also mark any provided extra re-eliminate keys
210  if (updateParams_.extraReelimKeys) {
211  for (Key key : *updateParams_.extraReelimKeys) {
212  markedKeys->insert(key);
213  }
214  }
215 
216  // Also, keys that were not observed in existing factors, but whose affected
217  // keys have been extended now (e.g. smart factors)
218  if (updateParams_.newAffectedKeys) {
219  for (const auto& factorAddedKeys : *updateParams_.newAffectedKeys) {
220  const auto factorIdx = factorAddedKeys.first;
221  const auto& affectedKeys = nonlinearFactors.at(factorIdx)->keys();
222  markedKeys->insert(affectedKeys.begin(), affectedKeys.end());
223  }
224  }
225  }
226 
227  // Update detail, unused, and observed keys from markedKeys
228  void updateKeys(const KeySet& markedKeys, ISAM2Result* result) const {
229  gttic(updateKeys);
230  // Observed keys for detailed results
231  if (result->detail && params_.enableDetailedResults) {
232  for (Key key : markedKeys) {
233  result->detail->variableStatus[key].isObserved = true;
234  }
235  }
236 
237  for (Key index : markedKeys) {
238  // Only add if not unused
239  if (result->unusedKeys.find(index) == result->unusedKeys.end())
240  // Make a copy of these, as we'll soon add to them
241  result->observedKeys.push_back(index);
242  }
243  }
244 
246  const FastMap<char, Vector>& thresholds, const VectorValues& delta,
247  const ISAM2::sharedClique& clique, KeySet* relinKeys) {
248  // Check the current clique for relinearization
249  bool relinearize = false;
250  for (Key var : *clique->conditional()) {
251  // Find the threshold for this variable type
252  const Vector& threshold = thresholds.find(Symbol(var).chr())->second;
253 
254  const Vector& deltaVar = delta[var];
255 
256  // Verify the threshold vector matches the actual variable size
257  if (threshold.rows() != deltaVar.rows())
258  throw std::invalid_argument(
259  "Relinearization threshold vector dimensionality for '" +
260  std::string(1, Symbol(var).chr()) +
261  "' passed into iSAM2 parameters does not match actual variable "
262  "dimensionality.");
263 
264  // Check for relinearization
265  if ((deltaVar.array().abs() > threshold.array()).any()) {
266  relinKeys->insert(var);
267  relinearize = true;
268  }
269  }
270 
271  // If this node was relinearized, also check its children
272  if (relinearize) {
273  for (const ISAM2::sharedClique& child : clique->children) {
274  CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys);
275  }
276  }
277  }
278 
280  double threshold, const VectorValues& delta,
281  const ISAM2::sharedClique& clique, KeySet* relinKeys) {
282  // Check the current clique for relinearization
283  bool relinearize = false;
284  for (Key var : *clique->conditional()) {
285  double maxDelta = delta[var].lpNorm<Eigen::Infinity>();
286  if (maxDelta >= threshold) {
287  relinKeys->insert(var);
288  relinearize = true;
289  }
290  }
291 
292  // If this node was relinearized, also check its children
293  if (relinearize) {
294  for (const ISAM2::sharedClique& child : clique->children) {
295  CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys);
296  }
297  }
298  }
299 
314  const ISAM2::Roots& roots, const VectorValues& delta,
315  const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
316  KeySet relinKeys;
317  for (const ISAM2::sharedClique& root : roots) {
318  if (std::holds_alternative<double>(relinearizeThreshold)) {
319  CheckRelinearizationRecursiveDouble(
320  std::get<double>(relinearizeThreshold), delta, root, &relinKeys);
321  } else if (std::holds_alternative<FastMap<char, Vector>>(relinearizeThreshold)) {
322  CheckRelinearizationRecursiveMap(
323  std::get<FastMap<char, Vector> >(relinearizeThreshold), delta,
324  root, &relinKeys);
325  }
326  }
327  return relinKeys;
328  }
329 
342  const VectorValues& delta,
343  const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) {
344  KeySet relinKeys;
345 
346  if (const double* threshold = std::get_if<double>(&relinearizeThreshold)) {
347  for (const VectorValues::KeyValuePair& key_delta : delta) {
348  double maxDelta = key_delta.second.lpNorm<Eigen::Infinity>();
349  if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
350  }
351  } else if (const FastMap<char, Vector>* thresholds =
352  std::get_if<FastMap<char, Vector> >(&relinearizeThreshold)) {
353  for (const VectorValues::KeyValuePair& key_delta : delta) {
354  const Vector& threshold =
355  thresholds->find(Symbol(key_delta.first).chr())->second;
356  if (threshold.rows() != key_delta.second.rows())
357  throw std::invalid_argument(
358  "Relinearization threshold vector dimensionality for '" +
359  std::string(1, Symbol(key_delta.first).chr()) +
360  "' passed into iSAM2 parameters does not match actual variable "
361  "dimensionality.");
362  if ((key_delta.second.array().abs() > threshold.array()).any())
363  relinKeys.insert(key_delta.first);
364  }
365  }
366 
367  return relinKeys;
368  }
369 
370  // Mark keys in \Delta above threshold \beta:
372  const VectorValues& delta,
373  const KeySet& fixedVariables,
374  KeySet* markedKeys) const {
375  gttic(gatherRelinearizeKeys);
376  // J=\{\Delta_{j}\in\Delta|\Delta_{j}\geq\beta\}.
377  KeySet relinKeys =
379  ? CheckRelinearizationPartial(roots, delta,
380  params_.relinearizeThreshold)
381  : CheckRelinearizationFull(delta, params_.relinearizeThreshold);
382  if (updateParams_.forceFullSolve)
383  relinKeys = CheckRelinearizationFull(delta, 0.0); // for debugging
384 
385  // Remove from relinKeys any keys whose linearization points are fixed
386  for (Key key : fixedVariables) {
387  relinKeys.erase(key);
388  }
389  if (updateParams_.noRelinKeys) {
390  for (Key key : *updateParams_.noRelinKeys) {
391  relinKeys.erase(key);
392  }
393  }
394 
395  // Add the variables being relinearized to the marked keys
396  markedKeys->insert(relinKeys.begin(), relinKeys.end());
397  return relinKeys;
398  }
399 
400  // Record relinerization threshold keys in detailed results
401  void recordRelinearizeDetail(const KeySet& relinKeys,
403  if (detail && params_.enableDetailedResults) {
404  for (Key key : relinKeys) {
405  detail->variableStatus[key].isAboveRelinThreshold = true;
406  detail->variableStatus[key].isRelinearized = true;
407  }
408  }
409  }
410 
411  // Mark all cliques that involve marked variables \Theta_{J} and all
412  // their ancestors.
413  void findFluid(const ISAM2::Roots& roots, const KeySet& relinKeys,
414  KeySet* markedKeys,
416  gttic(findFluid);
417  for (const auto& root : roots)
418  // add other cliques that have the marked ones in the separator
419  root->findAll(relinKeys, markedKeys);
420 
421  // Relinearization-involved keys for detailed results
422  if (detail && params_.enableDetailedResults) {
423  KeySet involvedRelinKeys;
424  for (const auto& root : roots)
425  root->findAll(relinKeys, &involvedRelinKeys);
426  for (Key key : involvedRelinKeys) {
427  if (!detail->variableStatus[key].isAboveRelinThreshold) {
428  detail->variableStatus[key].isRelinearizeInvolved = true;
429  detail->variableStatus[key].isRelinearized = true;
430  }
431  }
432  }
433  }
434 
435  // Linearize new factors
437  const Values& theta, size_t numNonlinearFactors,
438  const FactorIndices& newFactorsIndices,
439  GaussianFactorGraph* linearFactors) const {
440  gttic(linearizeNewFactors);
441  auto linearized = newFactors.linearize(theta);
442  if (params_.findUnusedFactorSlots) {
443  linearFactors->resize(numNonlinearFactors);
444  for (size_t i = 0; i < newFactors.size(); ++i)
445  (*linearFactors)[newFactorsIndices[i]] = (*linearized)[i];
446  } else {
447  linearFactors->push_back(*linearized);
448  }
449  assert(linearFactors->size() == numNonlinearFactors);
450  }
451 
453  const FactorIndices& newFactorsIndices,
454  VariableIndex* variableIndex) const {
455  gttic(augmentVariableIndex);
456  // Augment the variable index with the new factors
457  if (params_.findUnusedFactorSlots)
458  variableIndex->augment(newFactors, newFactorsIndices);
459  else
460  variableIndex->augment(newFactors);
461 
462  // Augment it with existing factors which now affect to more variables:
463  if (updateParams_.newAffectedKeys) {
464  for (const auto& factorAddedKeys : *updateParams_.newAffectedKeys) {
465  const auto factorIdx = factorAddedKeys.first;
466  variableIndex->augmentExistingFactor(factorIdx, factorAddedKeys.second);
467  }
468  }
469  }
470 
471  static void LogRecalculateKeys(const ISAM2Result& result) {
472  const bool debug = ISDEBUG("ISAM2 recalculate");
473 
474  if (debug) {
475  std::cout << "markedKeys: ";
476  for (const Key key : result.markedKeys) {
477  std::cout << key << " ";
478  }
479  std::cout << std::endl;
480  std::cout << "observedKeys: ";
481  for (const Key key : result.observedKeys) {
482  std::cout << key << " ";
483  }
484  std::cout << std::endl;
485  }
486  }
487 
489  const VariableIndex& variableIndex) {
490  gttic(GetAffectedFactors);
492  for (const Key key : keys) {
493  const FactorIndices& factors(variableIndex[key]);
494  indices.insert(factors.begin(), factors.end());
495  }
496  return indices;
497  }
498 
499  // find intermediate (linearized) factors from cache that are passed into
500  // the affected area
502  const ISAM2::Cliques& orphans) {
503  GaussianFactorGraph cachedBoundary;
504 
505  for (const auto& orphan : orphans) {
506  // retrieve the cached factor and add to boundary
507  cachedBoundary.push_back(orphan->cachedFactor());
508  }
509 
510  return cachedBoundary;
511  }
512 };
513 
514 } // namespace gtsam
gtsam::FactorGraph::add_factors
FactorIndices add_factors(const CONTAINER &factors, bool useEmptySlots=false)
Definition: FactorGraph-inst.h:109
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
gtsam::UpdateImpl::UpdateImpl
UpdateImpl(const ISAM2Params &params, const ISAM2UpdateParams &updateParams)
Definition: ISAM2-impl.h:112
gtsam::ISAM2Params::enableRelinearization
bool enableRelinearization
Definition: ISAM2Params.h:175
gtsam::UpdateImpl
Definition: ISAM2-impl.h:109
gtsam::ISAM2
Definition: ISAM2.h:45
gtsam::UpdateImpl::CheckRelinearizationFull
static KeySet CheckRelinearizationFull(const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
Definition: ISAM2-impl.h:341
gtsam::VariableIndex::augment
void augment(const FG &factors, const FactorIndices *newFactorIndices=nullptr)
Definition: VariableIndex-inl.h:27
keys
const KeyVector keys
Definition: testRegularImplicitSchurFactor.cpp:40
gtsam::ISAM2Params::enableDetailedResults
bool enableDetailedResults
Definition: ISAM2Params.h:207
gtsam::DeltaImpl::ReorderingMode::NO_CONSTRAINT
@ NO_CONSTRAINT
Definition: ISAM2-impl.h:75
simple_graph::factors
const GaussianFactorGraph factors
Definition: testJacobianFactor.cpp:213
gtsam::ISAM2UpdateParams::extraReelimKeys
std::optional< FastList< Key > > extraReelimKeys
Definition: ISAM2UpdateParams.h:49
gtsam::FastMap
Definition: FastMap.h:39
gtsam::ISAM2JunctionTree::ISAM2JunctionTree
ISAM2JunctionTree(const GaussianEliminationTree &eliminationTree)
Definition: ISAM2-impl.h:62
gtsam::ISAM2BayesTree::ISAM2BayesTree
ISAM2BayesTree()
Definition: ISAM2-impl.h:49
detail
Definition: testSerializationNonlinear.cpp:70
gtsam::NonlinearFactorGraph::linearize
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
Definition: NonlinearFactorGraph.cpp:239
gtsam::UpdateImpl::CheckRelinearizationPartial
static KeySet CheckRelinearizationPartial(const ISAM2::Roots &roots, const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
Definition: ISAM2-impl.h:313
gtsam::FastSet< Key >
gtsam::BayesTree::print
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Definition: BayesTree-inst.h:251
gtsam::ISAM2::sharedClique
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::ISAM2Params::enablePartialRelinearizationCheck
bool enablePartialRelinearizationCheck
Definition: ISAM2Params.h:219
gtsam::UpdateImpl::updateParams_
const ISAM2UpdateParams & updateParams_
Definition: ISAM2-impl.h:111
gtsam::ISAM2BayesTree
Definition: ISAM2-impl.h:43
gtsam::Vector
Eigen::VectorXd Vector
Definition: Vector.h:39
result
Values result
Definition: OdometryOptimize.cpp:8
gtsam::VariableIndex::remove
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
Definition: VariableIndex-inl.h:53
gtsam::UpdateImpl::CheckRelinearizationRecursiveMap
static void CheckRelinearizationRecursiveMap(const FastMap< char, Vector > &thresholds, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
Definition: ISAM2-impl.h:245
gtsam::ISAM2UpdateParams::noRelinKeys
std::optional< FastList< Key > > noRelinKeys
Definition: ISAM2UpdateParams.h:44
gtsam::UpdateImpl::error
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, std::optional< double > *result) const
Definition: ISAM2-impl.h:192
test_eigen_tensor.indices
indices
Definition: test_eigen_tensor.py:33
gtsam::Symbol::chr
unsigned char chr() const
Definition: inference/Symbol.h:75
gtsam::FactorGraph::at
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:306
gtsam::GaussianFactorGraph
Definition: GaussianFactorGraph.h:73
gtsam::NonlinearFactorGraph::error
double error(const Values &values) const
Definition: NonlinearFactorGraph.cpp:170
GaussianEliminationTree.h
ISDEBUG
#define ISDEBUG(S)
Definition: debug.h:60
gtsam::ISAM2UpdateParams::force_relinearize
bool force_relinearize
Definition: ISAM2UpdateParams.h:54
gtsam::VariableIndex::augmentExistingFactor
void augmentExistingFactor(const FactorIndex factorIndex, const KeySet &newKeys)
Definition: VariableIndex.cpp:59
gtsam::FactorGraph::resize
virtual void resize(size_t size)
Definition: FactorGraph.h:367
gtsam::ISAM2Params::relinearizeThreshold
RelinearizationThreshold relinearizeThreshold
Definition: ISAM2Params.h:169
gtsam::UpdateImpl::updateKeys
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
Definition: ISAM2-impl.h:228
gtsam.examples.PlanarManipulatorExample.delta
def delta(g0, g1)
Definition: PlanarManipulatorExample.py:45
gtsam::VectorValues
Definition: VectorValues.h:74
ISAM2Result.h
Class that stores detailed iSAM2 result.
gtsam::DeltaImpl
Definition: ISAM2-impl.h:67
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
debug
static constexpr bool debug
Definition: testDiscreteBayesTree.cpp:31
gtsam::ISAM2Result::DetailedResults
Definition: ISAM2Result.h:115
gtsam::UpdateImpl::recordRelinearizeDetail
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
Definition: ISAM2-impl.h:401
gtsam::FactorGraph::keys
KeySet keys() const
Definition: FactorGraph-inst.h:85
gtsam::UpdateImpl::GetAffectedFactors
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
Definition: ISAM2-impl.h:488
gtsam::UpdateImpl::computeUnusedKeys
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
Definition: ISAM2-impl.h:175
gtsam::ISAM2JunctionTree::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2-impl.h:60
Symbol.h
gtsam::FastList
Definition: FastList.h:43
gtsam::UpdateImpl::gatherRelinearizeKeys
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
Definition: ISAM2-impl.h:371
gtsam::VariableIndex
Definition: VariableIndex.h:41
gtsam::BayesTree< ISAM2Clique >::Roots
FastVector< sharedClique > Roots
Definition: BayesTree.h:95
gtsam::ISAM2BayesTree::This
ISAM2BayesTree This
Definition: ISAM2-impl.h:46
gtsam::DeltaImpl::PartialSolveResult
Definition: ISAM2-impl.h:68
gtsam::UpdateImpl::relinarizationNeeded
bool relinarizationNeeded(size_t update_count) const
Definition: ISAM2-impl.h:134
key
const gtsam::Symbol key('X', 0)
gtsam::ISAM2BayesTree::Base
ISAM2::Base Base
Definition: ISAM2-impl.h:45
gtsam::FactorGraph::remove
void remove(size_t i)
Definition: FactorGraph.h:371
gtsam::UpdateImpl::linearizeNewFactors
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
Definition: ISAM2-impl.h:436
gtsam::FactorGraph::size
size_t size() const
Definition: FactorGraph.h:297
ISAM2.h
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
gtsam::UpdateImpl::findFluid
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
Definition: ISAM2-impl.h:413
gtsam::UpdateImpl::GetCachedBoundaryFactors
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
Definition: ISAM2-impl.h:501
gtsam::ISAM2BayesTree::shared_ptr
std::shared_ptr< This > shared_ptr
Definition: ISAM2-impl.h:47
gtsam::ISAM2Params::RelinearizationThreshold
std::variant< double, FastMap< char, Vector > > RelinearizationThreshold
Definition: ISAM2Params.h:141
gtsam
traits
Definition: SFMdata.h:40
gtsam::BayesTree< ISAM2Clique >
error
static double error
Definition: testRot3.cpp:37
gtsam::FactorGraph::push_back
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:147
gtsam::Values
Definition: Values.h:65
gtsam::JunctionTree
Definition: JunctionTree.h:50
gtsam::ISAM2Params::findUnusedFactorSlots
bool findUnusedFactorSlots
Definition: ISAM2Params.h:225
gtsam::ISAM2UpdateParams
Definition: ISAM2UpdateParams.h:32
VariableIndex.h
gtsam::UpdateImpl::params_
const ISAM2Params & params_
Definition: ISAM2-impl.h:110
gtsam::UpdateImpl::pushBackFactors
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
Definition: ISAM2-impl.h:141
GaussianBayesTree.h
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
gtsam::UpdateImpl::LogRecalculateKeys
static void LogRecalculateKeys(const ISAM2Result &result)
Definition: ISAM2-impl.h:471
gtsam::GaussianEliminationTree
Definition: GaussianEliminationTree.h:27
gtsam::ISAM2JunctionTree
Definition: ISAM2-impl.h:55
gtsam::ISAM2Result
Definition: ISAM2Result.h:39
gtsam::FactorGraph::reserve
void reserve(size_t size)
Definition: FactorGraph.h:143
gtsam::UpdateImpl::gatherInvolvedKeys
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const
Definition: ISAM2-impl.h:199
JunctionTree-inst.h
The junction tree, template bodies.
gtsam::ISAM2JunctionTree::This
ISAM2JunctionTree This
Definition: ISAM2-impl.h:59
gtsam::ISAM2UpdateParams::forceFullSolve
bool forceFullSolve
Definition: ISAM2UpdateParams.h:71
gtsam::ISAM2JunctionTree::Base
JunctionTree< ISAM2BayesTree, GaussianFactorGraph > Base
Definition: ISAM2-impl.h:58
gtsam::DeltaImpl::ReorderingMode::nFullSystemVars
size_t nFullSystemVars
Definition: ISAM2-impl.h:73
gtsam::VariableIndex::empty
bool empty(Key variable) const
Return true if no factors associated with a variable.
Definition: VariableIndex.h:98
gtsam::VectorValues::KeyValuePair
value_type KeyValuePair
Typedef to pair<Key, Vector>
Definition: VectorValues.h:88
gtsam::DeltaImpl::ReorderingMode
Definition: ISAM2-impl.h:72
gtsam::Key
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:97
gtsam::ISAM2Params::relinearizeSkip
int relinearizeSkip
Definition: ISAM2Params.h:171
gtsam::ISAM2UpdateParams::newAffectedKeys
std::optional< FastMap< FactorIndex, KeySet > > newAffectedKeys
Definition: ISAM2UpdateParams.h:66
gtsam::ISAM2Params::cacheLinearizedFactors
bool cacheLinearizedFactors
Definition: ISAM2Params.h:201
get
Container::iterator get(Container &c, Position position)
Definition: stdlist_overload.cpp:29
Eigen::Infinity
const int Infinity
Definition: Constants.h:36
gtsam::ISAM2UpdateParams::removeFactorIndices
FactorIndices removeFactorIndices
Definition: ISAM2UpdateParams.h:36
i
int i
Definition: BiCGSTAB_step_by_step.cpp:9
gtsam::UpdateImpl::CheckRelinearizationRecursiveDouble
static void CheckRelinearizationRecursiveDouble(double threshold, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
Definition: ISAM2-impl.h:279
gtsam::UpdateImpl::LogStartingUpdate
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
Definition: ISAM2-impl.h:116
gttic
#define gttic(label)
Definition: timing.h:295
gtsam::DeltaImpl::PartialSolveResult::bayesTree
ISAM2::sharedClique bayesTree
Definition: ISAM2-impl.h:69
debug.h
Global debugging flags.
gtsam::UpdateImpl::augmentVariableIndex
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
Definition: ISAM2-impl.h:452
gtsam::Symbol
Definition: inference/Symbol.h:37
gtsam::FactorIndices
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:37
gtsam::DeltaImpl::ReorderingMode::constrainedKeys
std::optional< FastMap< Key, int > > constrainedKeys
Definition: ISAM2-impl.h:76
gtsam::NonlinearFactorGraph::print
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
Definition: NonlinearFactorGraph.cpp:55


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