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


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