Go to the documentation of this file.
55 :
public JunctionTree<ISAM2BayesTree, GaussianFactorGraph> {
62 :
Base(eliminationTree) {}
73 enum { COLAMD } algorithm;
81 static size_t UpdateGaussNewtonDelta(
const ISAM2::Roots& roots,
82 const KeySet& replacedKeys,
83 double wildfireThreshold,
91 const KeySet& replacedKeys,
112 : params_(
params), updateParams_(updateParams) {}
116 const ISAM2& isam2) {
117 gttic(pushBackFactors);
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: ");
145 KeySet* keysWithRemovedFactors)
const {
146 gttic(pushBackFactors);
152 *newFactorsIndices = nonlinearFactors->
add_factors(
159 removedFactors.
push_back(nonlinearFactors->
at(index));
160 nonlinearFactors->
remove(index);
169 *keysWithRemovedFactors = removedFactors.
keys();
176 const KeySet& keysWithRemovedFactors,
177 KeySet* unusedKeys)
const {
178 gttic(computeUnusedKeys);
180 for (
Key key : keysWithRemovedFactors) {
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 {
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());
231 for (
Key key : markedKeys) {
232 result->detail->variableStatus[
key].isObserved =
true;
236 for (
Key index : markedKeys) {
238 if (
result->unusedKeys.find(index) ==
result->unusedKeys.end())
240 result->observedKeys.push_back(index);
248 bool relinearize =
false;
249 for (
Key var : *clique->conditional()) {
251 const Vector& threshold = thresholds.find(
Symbol(var).chr())->second;
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);
282 bool relinearize =
false;
283 for (
Key var : *clique->conditional()) {
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)) {
348 if (maxDelta >= *threshold) relinKeys.insert(key_delta.first);
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);
378 ? CheckRelinearizationPartial(roots,
delta,
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());
403 for (
Key key : relinKeys) {
404 detail->variableStatus[
key].isAboveRelinThreshold =
true;
405 detail->variableStatus[
key].isRelinearized =
true;
416 for (
const auto& root : roots)
418 root->findAll(relinKeys, markedKeys);
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;
436 const Values& theta,
size_t numNonlinearFactors,
439 gttic(linearizeNewFactors);
440 auto linearized = newFactors.
linearize(theta);
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);
457 variableIndex->
augment(newFactors, newFactorsIndices);
459 variableIndex->
augment(newFactors);
464 const auto factorIdx = factorAddedKeys.first;
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);
504 for (
const auto& orphan : orphans) {
506 cachedBoundary.
push_back(orphan->cachedFactor());
509 return cachedBoundary;
FactorIndices add_factors(const CONTAINER &factors, bool useEmptySlots=false)
UpdateImpl(const ISAM2Params ¶ms, const ISAM2UpdateParams &updateParams)
bool enableRelinearization
static KeySet CheckRelinearizationFull(const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
void augment(const FG &factors, const FactorIndices *newFactorIndices=nullptr)
bool enableDetailedResults
const GaussianFactorGraph factors
std::optional< FastList< Key > > extraReelimKeys
ISAM2JunctionTree(const GaussianEliminationTree &eliminationTree)
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
static KeySet CheckRelinearizationPartial(const ISAM2::Roots &roots, const VectorValues &delta, const ISAM2Params::RelinearizationThreshold &relinearizeThreshold)
void print(const std::string &s="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Base::sharedClique sharedClique
Shared pointer to a clique.
static const SmartProjectionParams params
bool enablePartialRelinearizationCheck
const ISAM2UpdateParams & updateParams_
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
static void CheckRelinearizationRecursiveMap(const FastMap< char, Vector > &thresholds, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
std::optional< FastList< Key > > noRelinKeys
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, std::optional< double > *result) const
unsigned char chr() const
const sharedFactor at(size_t i) const
double error(const Values &values) const
void augmentExistingFactor(const FactorIndex factorIndex, const KeySet &newKeys)
virtual void resize(size_t size)
RelinearizationThreshold relinearizeThreshold
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
Class that stores detailed iSAM2 result.
static constexpr bool debug
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
std::shared_ptr< This > shared_ptr
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
FastVector< sharedClique > Roots
bool relinarizationNeeded(size_t update_count) const
const gtsam::Symbol key('X', 0)
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
std::shared_ptr< This > shared_ptr
std::variant< double, FastMap< char, Vector > > RelinearizationThreshold
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
bool findUnusedFactorSlots
const ISAM2Params & params_
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.
static void LogRecalculateKeys(const ISAM2Result &result)
void reserve(size_t size)
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const
The junction tree, template bodies.
JunctionTree< ISAM2BayesTree, GaussianFactorGraph > Base
bool empty(Key variable) const
Return true if no factors associated with a variable.
value_type KeyValuePair
Typedef to pair<Key, Vector>
std::uint64_t Key
Integer nonlinear key type.
std::optional< FastMap< FactorIndex, KeySet > > newAffectedKeys
bool cacheLinearizedFactors
Container::iterator get(Container &c, Position position)
FactorIndices removeFactorIndices
static void CheckRelinearizationRecursiveDouble(double threshold, const VectorValues &delta, const ISAM2::sharedClique &clique, KeySet *relinKeys)
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
ISAM2::sharedClique bayesTree
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
FastVector< FactorIndex > FactorIndices
Define collection types:
std::optional< FastMap< Key, int > > constrainedKeys
void print(const std::string &str="NonlinearFactorGraph: ", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const override
gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:32