38 template class BayesTree<ISAM2Clique>;
72 gttic(affectedKeysSet);
75 affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end());
76 gttoc(affectedKeysSet);
78 gttic(check_candidates_and_linearize);
84 if (affectedKeysSet.find(
key) == affectedKeysSet.end()) {
88 if (useCachedLinear && relinKeys.find(
key) != relinKeys.end())
89 useCachedLinear =
false;
92 if (useCachedLinear) {
93 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 102 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 110 gttoc(check_candidates_and_linearize);
130 &affectedBayesNet, &orphans);
149 for (
const auto& conditional : affectedBayesNet)
150 affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(),
151 conditional->endFrontals());
155 static const double kBatchThreshold = 0.65;
156 if (affectedKeys.size() >=
theta_.
size() * kBatchThreshold) {
161 &affectedKeysSet, &orphans, result);
166 for (
const auto& root :
roots_)
167 for (
Key var : *root->conditional())
168 result->
detail->variableStatus[var].inRootClique =
true;
185 affectedKeysSet->insert(
key);
194 affectedKeysSet->erase(key);
232 bayesTree->roots().end());
234 nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
243 result->
detail->variableStatus[
key].isReeliminated =
true;
259 affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(),
261 affectedAndNewKeys.insert(affectedAndNewKeys.end(),
268 factors.
print(
"Relinearized factors: ");
269 std::cout <<
"Affected keys: ";
270 for (
const Key key : affectedKeys) {
271 std::cout <<
key <<
" ";
273 std::cout << std::endl;
278 for (
Key key : affectedAndNewKeys) {
279 result->
detail->variableStatus[
key].isReeliminated =
true;
290 if (debug) cachedBoundary.
print(
"Boundary factors: ");
296 for (
const auto& orphan : *orphans)
304 gttic(reorder_and_eliminate);
311 affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end());
316 gttic(ordering_constraints);
326 constraintGroups.emplace(var, group);
331 iter != constraintGroups.end();
335 constraintGroups.erase(
iter++);
339 gttoc(ordering_constraints);
352 gttoc(reorder_and_eliminate);
356 bayesTree->roots().end());
357 nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
366 gttic(addNewVariables);
369 if (
ISDEBUG(
"ISAM2 AddVariables")) newTheta.
print(
"The new variables are: ");
388 for (
Key key : unusedKeys) {
406 bool force_relinearize) {
414 return update(newFactors, newTheta, params);
456 if (!relinKeys.empty()) {
488 KeySet leafKeys(leafKeysList.begin(), leafKeysList.end());
493 map<Key, vector<GaussianFactor::shared_ptr> > marginalFactors;
502 auto trackingRemoveSubtree = [&](
const sharedClique& subtreeRoot) {
504 for (
const sharedClique& removedClique : removedCliques) {
505 auto cg = removedClique->conditional();
506 marginalFactors.erase(cg->front());
507 leafKeysRemoved.insert(cg->beginFrontals(), cg->endFrontals());
508 for (
Key frontal : cg->frontals()) {
511 factorIndicesToRemove.insert(involved.begin(), involved.end());
514 if (!leafKeys.exists(frontal))
515 throw std::runtime_error(
516 "Requesting to marginalize variables that are not leaves, " 517 "the ISAM2 object is now in an inconsistent state so should " 518 "no longer be used.");
522 return removedCliques;
526 for (
Key j : leafKeys) {
527 if (!leafKeysRemoved.
exists(
j)) {
532 while (clique->parent_.use_count() != 0) {
536 if (leafKeys.exists(parent->conditional()->front()))
543 bool marginalizeEntireClique =
true;
544 for (
Key frontal : clique->conditional()->frontals()) {
545 if (!leafKeys.exists(frontal)) {
546 marginalizeEntireClique =
false;
552 if (marginalizeEntireClique) {
560 marginalFactors[clique->parent()->conditional()->front()].push_back(
564 trackingRemoveSubtree(clique);
574 KeySet factorsInSubtreeRoot;
578 for (
Key parent : child->conditional()->parents()) {
579 if (leafKeys.exists(parent)) {
580 subtreesToRemove.push_back(child);
588 const Cliques removed = trackingRemoveSubtree(subtree);
589 childrenRemoved.insert(childrenRemoved.end(), removed.begin(),
598 KeySet factorsFromMarginalizedInClique_step1;
599 for (
Key frontal : clique->conditional()->frontals()) {
600 if (leafKeys.exists(frontal))
601 factorsFromMarginalizedInClique_step1.insert(
605 for (
const sharedClique& removedChild : childrenRemoved) {
606 for (
Key indexInClique : removedChild->conditional()->frontals()) {
608 factorsFromMarginalizedInClique_step1.erase(factorInvolving);
613 for (
const auto index : factorsFromMarginalizedInClique_step1) {
619 auto cg = clique->conditional();
620 const KeySet cliqueFrontals(cg->beginFrontals(), cg->endFrontals());
622 std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(),
623 leafKeys.begin(), leafKeys.end(),
624 std::back_inserter(cliqueFrontalsToEliminate));
629 if (eliminationResult1.second)
630 marginalFactors[cg->front()].push_back(eliminationResult1.second);
635 while (leafKeys.exists(cg->keys()[nToRemove])) ++nToRemove;
638 const DenseIndex dimToRemove = cg->matrixObject().offset(nToRemove);
639 cg->matrixObject().firstBlock() = nToRemove;
640 cg->matrixObject().rowStart() = dimToRemove;
644 originalKeys.swap(cg->keys());
645 cg->keys().assign(originalKeys.begin() + nToRemove, originalKeys.end());
646 cg->nrFrontals() -= nToRemove;
650 for (
Key frontal : cliqueFrontalsToEliminate) {
652 factorIndicesToRemove.insert(involved.begin(), involved.end());
656 leafKeysRemoved.insert(cliqueFrontalsToEliminate.begin(),
657 cliqueFrontalsToEliminate.end());
667 for (
const auto& key_factors : marginalFactors) {
668 for (
const auto& factor : key_factors.second) {
671 if (marginalFactorsIndices)
674 std::make_shared<LinearContainerFactor>(factor));
676 for (
Key factorKey : *factor) {
687 for (
const auto index : factorIndicesToRemove) {
693 factorIndicesToRemove.end(), removedFactors);
695 if (deletedFactorsIndices)
696 deletedFactorsIndices->assign(factorIndicesToRemove.begin(),
697 factorIndicesToRemove.end());
711 const double effectiveWildfireThreshold =
713 gttic(Wildfire_update);
715 effectiveWildfireThreshold, &
delta_);
717 gttoc(Wildfire_update);
722 const double effectiveWildfireThreshold =
726 gttic(Dogleg_Iterate);
729 gttic(Wildfire_update);
732 gttoc(Wildfire_update);
751 gttoc(Dogleg_Iterate);
761 throw std::runtime_error(
"iSAM2: unknown ISAM2Params type");
767 gttic(ISAM2_calculateEstimate);
777 return *
theta_.
at(key).retract_(delta);
810 for (
const auto& root : this->
roots()) root->addGradientAtZero(&g);
const gtsam::Symbol key('X', 0)
void removeVariables(const KeySet &unusedKeys)
GaussianFactorGraph relinearizeAffectedFactors(const ISAM2UpdateParams &updateParams, const FastList< Key > &affectedKeys, const KeySet &relinKeys)
static void LogRecalculateKeys(const ISAM2Result &result)
void removeTop(const KeyVector &keys, BayesNetType *bn, Cliques *orphans)
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const
static size_t UpdateGaussNewtonDelta(const ISAM2::Roots &roots, const KeySet &replacedKeys, double wildfireThreshold, VectorValues *delta)
Matrix marginalCovariance(Key key) const
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
size_t size() const
The number of variable entries. This is equal to the number of unique variable Keys.
size_t variablesReeliminated
const Nodes & nodes() const
std::pair< std::shared_ptr< BayesTreeType >, std::shared_ptr< FactorGraphType > > eliminate(const Eliminate &function) const
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)
const ValueType at(Key j) const
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
IsDerived< DERIVEDFACTOR > push_back(std::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
static VectorValues ComputeGradientSearch(const VectorValues &gradAtZero, const VectorValues &RgProd)
bool exists(const VALUE &e) const
const GaussianFactorGraph factors
VariableIndex variableIndex_
void recalculateIncremental(const ISAM2UpdateParams &updateParams, const KeySet &relinKeys, const FastList< Key > &affectedKeys, KeySet *affectedKeysSet, Cliques *orphans, ISAM2Result *result)
Perform an incremental update of the factor graph to return a new Bayes Tree with affected keys...
Pose2_ Expmap(const Vector3_ &xi)
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
bool equals(const This &other, double tol=1e-9) const
iterator iter(handle obj)
iterator insert(const std::pair< Key, Vector > &key_value)
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const std::optional< FastMap< Key, int > > &constrainedKeys={}, const std::optional< FastList< Key > > &noRelinKeys={}, const std::optional< FastList< Key > > &extraReelimKeys={}, bool force_relinearize=false)
double error(const VectorValues &x) const
virtual bool equals(const ISAM2 &other, double tol=1e-9) const
DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode
NonlinearFactorGraph graph
std::optional< double > doglegDelta_
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
static enum @1107 ordering
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
Print out graph to std::cout, with optional key formatter.
const_iterator end() const
Iterator to the first variable entry.
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
static constexpr bool debug
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
static const SmartProjectionParams params
Values retract(const VectorValues &delta) const
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
static Ordering Colamd(const FACTOR_GRAPH &graph)
FactorIndices newFactorsIndices
void augment(const FG &factors, const FactorIndices *newFactorIndices=nullptr)
FastVector< FactorIndex > FactorIndices
Define collection types:
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
Cliques removeSubtree(const sharedClique &subtree)
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
std::optional< FastMap< Key, int > > constrainedKeys
NonlinearFactorGraph nonlinearFactors_
VectorValues zeroVectors() const
bool evaluateNonlinearError
GaussianFactorGraph::Eliminate getEliminationFunction() const
Class that stores detailed iSAM2 result.
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
void recalculateBatch(const ISAM2UpdateParams &updateParams, KeySet *affectedKeysSet, ISAM2Result *result)
size_t variablesRelinearized
void recalculate(const ISAM2UpdateParams &updateParams, const KeySet &relinKeys, ISAM2Result *result)
Remove marked top and either recalculate in batch or incrementally.
KeySet keysWithRemovedFactors
GaussianFactorGraph linearFactors_
void retractMasked(const VectorValues &delta, const KeySet &mask)
VectorValues gradientAtZero() const
DetailedResults * details()
Return pointer to detail, 0 if no detail requested.
std::optional< double > errorBefore
StatusMap variableStatus
The status of each variable during this update, see VariableStatus.
OptimizationParams optimizationParams
Base::sharedClique sharedClique
Shared pointer to a clique.
bool equals(const Values &other, double tol=1e-9) const
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
double error(const Values &values) const
Bayes Tree is a tree of cliques of a Bayes Chain.
bool equals(const VariableIndex &other, double tol=0.0) const
Test for equality (for unit tests and debug assertions).
void marginalizeLeaves(const FastList< Key > &leafKeys, FactorIndices *marginalFactorsIndices=nullptr, FactorIndices *deletedFactorsIndices=nullptr)
KeySet deltaReplacedMask_
static Ordering ColamdConstrained(const FACTOR_GRAPH &graph, const FastMap< Key, int > &groups)
std::shared_ptr< This > shared_ptr
const_iterator begin() const
Iterator to the first variable entry.
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
std::optional< FastList< Key > > noRelinKeys
void unsafe_erase(typename Base::iterator position)
const sharedClique & clique(Key j) const
static size_t UpdateRgProd(const ISAM2::Roots &roots, const KeySet &replacedKeys, const VectorValues &gradAtZero, VectorValues *RgProd)
constexpr descr< N - 1 > _(char const (&text)[N])
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
const Roots & roots() const
std::optional< double > errorAfter
FactorIndices removeFactorIndices
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, std::optional< double > *result) const
const VectorValues & getDelta() const
void addVariables(const Values &newTheta, ISAM2Result::DetailedResults *detail=0)
Values calculateBestEstimate() const
void insert(Key j, const Value &val)
void updateDelta(bool forceFullSolve=false) const
std::optional< FastList< Key > > extraReelimKeys
VectorValues deltaNewton_
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
bool verbose
Whether Dogleg prints iteration and convergence information.
void removeUnusedVariables(ITERATOR firstKey, ITERATOR lastKey)
Remove unused empty variables (in debug mode verifies they are empty).
std::uint64_t FactorIndex
Integer nonlinear factor index type.
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
bool enableDetailedResults
double error(const VectorValues &x) const
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
std::uint64_t Key
Integer nonlinear key type.
Values calculateEstimate() const
std::optional< DetailedResults > detail
const ISAM2Params & params() const
bool cacheLinearizedFactors
size_t factorsRecalculated
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
bool relinarizationNeeded(size_t update_count) const