26 #include <gtsam/inference/Symbol.h> 46 typedef std::shared_ptr<This> shared_ptr;
55 :
public JunctionTree<ISAM2BayesTree, GaussianFactorGraph> {
59 typedef std::shared_ptr<This> shared_ptr;
62 : Base(eliminationTree) {}
72 size_t nFullSystemVars;
73 enum { COLAMD } algorithm;
74 enum { NO_CONSTRAINT, CONSTRAIN_LAST } constrain;
75 std::optional<FastMap<Key, int> > constrainedKeys;
82 const KeySet& replacedKeys,
83 double wildfireThreshold,
91 const KeySet& replacedKeys,
112 : params_(params), updateParams_(updateParams) {}
116 const ISAM2& isam2) {
117 gttic(pushBackFactors);
118 const bool debug = ISDEBUG(
"ISAM2 update");
119 const bool verbose = ISDEBUG(
"ISAM2 update verbose");
122 std::cout <<
"ISAM2::update\n";
123 isam2.
print(
"ISAM2: ");
126 if (debug || verbose) {
127 newFactors.
print(
"The new factors are: ");
133 bool relinarizationNeeded(
size_t update_count)
const {
135 (params_.enableRelinearization &&
136 update_count % params_.relinearizeSkip == 0);
145 KeySet* keysWithRemovedFactors)
const {
146 gttic(pushBackFactors);
152 *newFactorsIndices = nonlinearFactors->
add_factors(
153 newFactors, params_.findUnusedFactorSlots);
159 removedFactors.
push_back(nonlinearFactors->
at(index));
160 nonlinearFactors->
remove(index);
161 if (params_.cacheLinearizedFactors) linearFactors->
remove(index);
169 *keysWithRemovedFactors = removedFactors.
keys();
176 const KeySet& keysWithRemovedFactors,
177 KeySet* unusedKeys)
const {
178 gttic(computeUnusedKeys);
180 for (
Key key : keysWithRemovedFactors) {
181 if (variableIndex.
empty(key))
182 removedAndEmpty.insert(removedAndEmpty.end(), key);
185 std::set_difference(removedAndEmpty.begin(), removedAndEmpty.end(),
186 newFactorSymbKeys.begin(), newFactorSymbKeys.end(),
187 std::inserter(*unusedKeys, unusedKeys->end()));
192 const Values& estimate, std::optional<double>* result)
const {
194 *result = nonlinearFactors.
error(estimate);
200 const KeySet& keysWithRemovedFactors,
201 KeySet* markedKeys)
const {
202 gttic(gatherInvolvedKeys);
203 *markedKeys = newFactors.
keys();
205 markedKeys->insert(keysWithRemovedFactors.begin(),
206 keysWithRemovedFactors.end());
211 markedKeys->insert(key);
219 const auto factorIdx = factorAddedKeys.first;
220 const auto& affectedKeys = nonlinearFactors.
at(factorIdx)->keys();
221 markedKeys->insert(affectedKeys.begin(), affectedKeys.end());
230 if (result->
detail && params_.enableDetailedResults) {
231 for (
Key key : markedKeys) {
232 result->
detail->variableStatus[key].isObserved =
true;
236 for (
Key index : markedKeys) {
244 static void CheckRelinearizationRecursiveMap(
248 bool relinearize =
false;
249 for (
Key var : *clique->conditional()) {
251 const Vector& threshold = thresholds.find(
Symbol(var).chr())->second;
253 const Vector& deltaVar = delta[var];
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 " 264 if ((deltaVar.array().abs() > threshold.array()).any()) {
265 relinKeys->insert(var);
273 CheckRelinearizationRecursiveMap(thresholds, delta, child, relinKeys);
278 static void CheckRelinearizationRecursiveDouble(
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);
294 CheckRelinearizationRecursiveDouble(threshold, delta, child, relinKeys);
317 if (std::holds_alternative<double>(relinearizeThreshold)) {
318 CheckRelinearizationRecursiveDouble(
319 std::get<double>(relinearizeThreshold), delta, root, &relinKeys);
321 CheckRelinearizationRecursiveMap(
345 if (
const double* threshold = std::get_if<double>(&relinearizeThreshold)) {
347 double maxDelta = key_delta.second.lpNorm<Eigen::Infinity>();
348 if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
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 " 361 if ((key_delta.second.array().abs() > threshold.array()).any())
362 relinKeys.insert(key_delta.first);
372 const KeySet& fixedVariables,
373 KeySet* markedKeys)
const {
374 gttic(gatherRelinearizeKeys);
377 params_.enablePartialRelinearizationCheck
378 ? CheckRelinearizationPartial(roots, delta,
379 params_.relinearizeThreshold)
380 : CheckRelinearizationFull(delta, params_.relinearizeThreshold);
382 relinKeys = CheckRelinearizationFull(delta, 0.0);
385 for (
Key key : fixedVariables) {
386 relinKeys.erase(key);
390 relinKeys.erase(key);
395 markedKeys->insert(relinKeys.begin(), relinKeys.end());
400 void recordRelinearizeDetail(
const KeySet& relinKeys,
402 if (detail && params_.enableDetailedResults) {
403 for (
Key key : relinKeys) {
416 for (
const auto& root : roots)
418 root->findAll(relinKeys, markedKeys);
421 if (detail && params_.enableDetailedResults) {
423 for (
const auto& root : roots)
424 root->findAll(relinKeys, &involvedRelinKeys);
425 for (
Key key : involvedRelinKeys) {
436 const Values& theta,
size_t numNonlinearFactors,
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];
448 assert(linearFactors->
size() == numNonlinearFactors);
454 gttic(augmentVariableIndex);
456 if (params_.findUnusedFactorSlots)
457 variableIndex->
augment(newFactors, newFactorsIndices);
459 variableIndex->
augment(newFactors);
464 const auto factorIdx = factorAddedKeys.first;
470 static void LogRecalculateKeys(
const ISAM2Result& result) {
471 const bool debug = ISDEBUG(
"ISAM2 recalculate");
474 std::cout <<
"markedKeys: ";
476 std::cout << key <<
" ";
478 std::cout << std::endl;
479 std::cout <<
"observedKeys: ";
481 std::cout << key <<
" ";
483 std::cout << std::endl;
489 gttic(GetAffectedFactors);
491 for (
const Key key : keys) {
493 indices.insert(factors.begin(), factors.end());
504 for (
const auto& orphan : orphans) {
506 cachedBoundary.
push_back(orphan->cachedFactor());
509 return cachedBoundary;
std::variant< double, FastMap< char, Vector > > RelinearizationThreshold
Definition: ISAM2Params.h:141
KeySet keys() const
Definition: FactorGraph-inst.h:85
Definition: ISAM2Params.h:136
Definition: ISAM2-impl.h:108
Definition: GaussianEliminationTree.h:27
A key-value pair, which you get by dereferencing iterators.
Definition: Values.h:90
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
Definition: FactorGraph.h:190
Definition: ISAM2-impl.h:66
FastVector< FactorIndex > FactorIndices
Define collection types:
Definition: Factor.h:36
FactorIndices add_factors(const CONTAINER &factors, bool useEmptySlots=false)
Definition: FactorGraph-inst.h:109
Definition: ISAM2-impl.h:42
void remove(size_t i)
Definition: FactorGraph.h:393
bool force_relinearize
Definition: ISAM2UpdateParams.h:54
Definition: VectorValues.h:74
void augment(const FG &factors, const FactorIndices *newFactorIndices=nullptr)
Definition: VariableIndex-inl.h:27
size_t size() const
Definition: FactorGraph.h:334
void augmentExistingFactor(const FactorIndex factorIndex, const KeySet &newKeys)
Definition: ISAM2-impl.h:67
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
Definition: VariableIndex-inl.h:53
std::optional< FastMap< FactorIndex, KeySet > > newAffectedKeys
Definition: ISAM2UpdateParams.h:66
KeyVector observedKeys
Definition: ISAM2Result.h:103
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
KeySet markedKeys
Definition: ISAM2Result.h:109
bool forceFullSolve
Definition: ISAM2UpdateParams.h:71
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
Definition: BayesTree-inst.h:251
Base::sharedClique sharedClique
Shared pointer to a clique.
Definition: ISAM2.h:103
double error(const Values &values) const
Definition: ISAM2-impl.h:71
Definition: NonlinearFactorGraph.h:55
Definition: FastList.h:43
Definition: chartTesting.h:28
std::optional< FastList< Key > > noRelinKeys
Definition: ISAM2UpdateParams.h:44
unsigned char chr() const
Definition: Symbol.h:75
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
Definition: VariableIndex.h:41
static KeySet CheckRelinearizationFull(const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
Definition: ISAM2-impl.h:340
const Roots & roots() const
Definition: BayesTree.h:152
KeySet unusedKeys
Definition: ISAM2Result.h:100
const sharedFactor at(size_t i) const
Definition: FactorGraph.h:343
FactorIndices removeFactorIndices
Definition: ISAM2UpdateParams.h:36
The junction tree, template bodies.
Definition: ISAM2Result.h:115
FastVector< sharedClique > Roots
Definition: BayesTree.h:95
void reserve(size_t size)
Definition: FactorGraph.h:186
Definition: JunctionTree.h:50
std::optional< FastList< Key > > extraReelimKeys
Definition: ISAM2UpdateParams.h:49
Definition: ISAM2UpdateParams.h:32
Definition: ISAM2-impl.h:54
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102
std::optional< DetailedResults > detail
Definition: ISAM2Result.h:156
Definition: GaussianFactorGraph.h:73
Definition: ISAM2Result.h:39
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
bool empty(Key variable) const
Return true if no factors associated with a variable.
Definition: VariableIndex.h:96