37 template class BayesTree<ISAM2Clique>;
69 gttic(affectedKeysSet);
72 affectedKeysSet.insert(affectedKeys.begin(), affectedKeys.end());
73 gttoc(affectedKeysSet);
75 gttic(check_candidates_and_linearize);
81 if (affectedKeysSet.find(
key) == affectedKeysSet.end()) {
85 if (useCachedLinear && relinKeys.find(
key) != relinKeys.end())
86 useCachedLinear =
false;
89 if (useCachedLinear) {
90 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 99 #ifdef GTSAM_EXTRA_CONSISTENCY_CHECKS 107 gttoc(check_candidates_and_linearize);
127 &affectedBayesNet, &orphans);
146 for (
const auto& conditional : affectedBayesNet)
147 affectedKeys.insert(affectedKeys.end(), conditional->beginFrontals(),
148 conditional->endFrontals());
152 static const double kBatchThreshold = 0.65;
153 if (affectedKeys.size() >=
theta_.
size() * kBatchThreshold) {
158 &affectedKeysSet, &orphans, result);
164 for (
Key var : *
root->conditional())
165 result->
detail->variableStatus[var].inRootClique =
true;
180 std::inserter(*affectedKeysSet, affectedKeysSet->end()));
189 affectedKeysSet->erase(key);
227 bayesTree->roots().end());
229 nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
238 result->
detail->variableStatus[
key].isReeliminated =
true;
254 affectedAndNewKeys.insert(affectedAndNewKeys.end(), affectedKeys.begin(),
256 affectedAndNewKeys.insert(affectedAndNewKeys.end(),
263 factors.
print(
"Relinearized factors: ");
264 std::cout <<
"Affected keys: ";
265 for (
const Key key : affectedKeys) {
266 std::cout <<
key <<
" ";
268 std::cout << std::endl;
273 for (
Key key : affectedAndNewKeys) {
274 result->
detail->variableStatus[
key].isReeliminated =
true;
285 if (debug) cachedBoundary.
print(
"Boundary factors: ");
291 for (
const auto& orphan : *orphans)
293 boost::make_shared<BayesTreeOrphanWrapper<ISAM2::Clique> >(orphan);
300 gttic(reorder_and_eliminate);
307 affectedKeysSet->insert(affectedKeys.begin(), affectedKeys.end());
312 gttic(ordering_constraints);
322 constraintGroups.insert(std::make_pair(var, group));
327 iter != constraintGroups.end();
331 constraintGroups.erase(
iter++);
335 gttoc(ordering_constraints);
348 gttoc(reorder_and_eliminate);
352 bayesTree->roots().end());
353 nodes_.insert(bayesTree->nodes().begin(), bayesTree->nodes().end());
362 gttic(addNewVariables);
365 if (
ISDEBUG(
"ISAM2 AddVariables")) newTheta.
print(
"The new variables are: ");
384 for (
Key key : unusedKeys) {
402 bool force_relinearize) {
410 return update(newFactors, newTheta, params);
452 if (!relinKeys.empty()) {
481 boost::optional<FactorIndices&> marginalFactorsIndices,
482 boost::optional<FactorIndices&> deletedFactorsIndices) {
484 KeySet leafKeys(leafKeysList.begin(), leafKeysList.end());
489 map<Key, vector<GaussianFactor::shared_ptr> > marginalFactors;
498 auto trackingRemoveSubtree = [&](
const sharedClique& subtreeRoot) {
500 for (
const sharedClique& removedClique : removedCliques) {
501 auto cg = removedClique->conditional();
502 marginalFactors.erase(cg->front());
503 leafKeysRemoved.insert(cg->beginFrontals(), cg->endFrontals());
504 for (
Key frontal : cg->frontals()) {
507 factorIndicesToRemove.insert(involved.begin(), involved.end());
510 if (!leafKeys.exists(frontal))
511 throw std::runtime_error(
512 "Requesting to marginalize variables that are not leaves, " 513 "the ISAM2 object is now in an inconsistent state so should " 514 "no longer be used.");
518 return removedCliques;
522 for (
Key j : leafKeys) {
523 if (!leafKeysRemoved.
exists(
j)) {
528 while (!clique->parent_._empty()) {
532 if (leafKeys.exists(parent->conditional()->front()))
539 bool marginalizeEntireClique =
true;
540 for (
Key frontal : clique->conditional()->frontals()) {
541 if (!leafKeys.exists(frontal)) {
542 marginalizeEntireClique =
false;
548 if (marginalizeEntireClique) {
556 marginalFactors[clique->parent()->conditional()->front()].push_back(
560 trackingRemoveSubtree(clique);
570 KeySet factorsInSubtreeRoot;
574 for (
Key parent : child->conditional()->parents()) {
575 if (leafKeys.exists(parent)) {
576 subtreesToRemove.push_back(child);
584 const Cliques removed = trackingRemoveSubtree(subtree);
585 childrenRemoved.insert(childrenRemoved.end(), removed.begin(),
594 KeySet factorsFromMarginalizedInClique_step1;
595 for (
Key frontal : clique->conditional()->frontals()) {
596 if (leafKeys.exists(frontal))
597 factorsFromMarginalizedInClique_step1.insert(
601 for (
const sharedClique& removedChild : childrenRemoved) {
602 for (
Key indexInClique : removedChild->conditional()->frontals()) {
604 factorsFromMarginalizedInClique_step1.erase(factorInvolving);
609 for (
const auto index : factorsFromMarginalizedInClique_step1) {
615 auto cg = clique->conditional();
616 const KeySet cliqueFrontals(cg->beginFrontals(), cg->endFrontals());
618 std::set_intersection(cliqueFrontals.begin(), cliqueFrontals.end(),
619 leafKeys.begin(), leafKeys.end(),
620 std::back_inserter(cliqueFrontalsToEliminate));
625 if (eliminationResult1.second)
626 marginalFactors[cg->front()].push_back(eliminationResult1.second);
631 while (leafKeys.exists(cg->keys()[nToRemove])) ++nToRemove;
634 const DenseIndex dimToRemove = cg->matrixObject().offset(nToRemove);
635 cg->matrixObject().firstBlock() = nToRemove;
636 cg->matrixObject().rowStart() = dimToRemove;
640 originalKeys.swap(cg->keys());
641 cg->keys().assign(originalKeys.begin() + nToRemove, originalKeys.end());
642 cg->nrFrontals() -= nToRemove;
646 for (
Key frontal : cliqueFrontalsToEliminate) {
648 factorIndicesToRemove.insert(involved.begin(), involved.end());
652 leafKeysRemoved.insert(cliqueFrontalsToEliminate.begin(),
653 cliqueFrontalsToEliminate.end());
663 for (
const auto& key_factors : marginalFactors) {
664 for (
const auto& factor : key_factors.second) {
667 if (marginalFactorsIndices)
670 boost::make_shared<LinearContainerFactor>(factor));
672 for (
Key factorKey : *factor) {
683 for (
const auto index : factorIndicesToRemove) {
689 factorIndicesToRemove.end(), removedFactors);
691 if (deletedFactorsIndices)
692 deletedFactorsIndices->assign(factorIndicesToRemove.begin(),
693 factorIndicesToRemove.end());
707 const double effectiveWildfireThreshold =
709 gttic(Wildfire_update);
711 effectiveWildfireThreshold, &
delta_);
713 gttoc(Wildfire_update);
719 const double effectiveWildfireThreshold =
723 gttic(Dogleg_Iterate);
726 gttic(Wildfire_update);
729 gttoc(Wildfire_update);
748 gttoc(Dogleg_Iterate);
758 throw std::runtime_error(
"iSAM2: unknown ISAM2Params type");
764 gttic(ISAM2_calculateEstimate);
774 return *
theta_.
at(key).retract_(delta);
807 for (
const auto&
root : this->
roots())
root->addGradientAtZero(&g);
GaussianFactorGraph::Eliminate getEliminationFunction() const
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)
static size_t UpdateGaussNewtonDelta(const ISAM2::Roots &roots, const KeySet &replacedKeys, double wildfireThreshold, VectorValues *delta)
boost::optional< FastList< Key > > extraReelimKeys
bool equals(const This &other, double tol=1e-9) const
VectorValues zeroVectors() const
Wrap Jacobian and Hessian linear factors to allow simple injection into a nonlinear graph...
Matrix marginalCovariance(Key key) const
size_t variablesReeliminated
const_iterator begin() const
Iterator to the first variable entry.
void augment(const FG &factors, boost::optional< const FactorIndices & > newFactorIndices=boost::none)
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)
void insert(Key j, const Value &val)
static enum @843 ordering
std::pair< boost::shared_ptr< BayesTreeType >, boost::shared_ptr< FactorGraphType > > eliminate(const Eliminate &function) const
static GaussianFactorGraph GetCachedBoundaryFactors(const ISAM2::Cliques &orphans)
FastVector< FactorIndex > FactorIndices
Define collection types:
static FactorIndexSet GetAffectedFactors(const KeyList &keys, const VariableIndex &variableIndex)
static VectorValues ComputeGradientSearch(const VectorValues &gradAtZero, const VectorValues &RgProd)
const Nodes & nodes() const
VariableIndex variableIndex_
void recalculateIncremental(const ISAM2UpdateParams &updateParams, const KeySet &relinKeys, const FastList< Key > &affectedKeys, KeySet *affectedKeysSet, Cliques *orphans, ISAM2Result *result)
Pose2_ Expmap(const Vector3_ &xi)
iterator iter(handle obj)
GaussianFactorGraph factors(list_of(factor1)(factor2)(factor3))
Values retract(const VectorValues &delta) const
IsDerived< DERIVEDFACTOR > push_back(boost::shared_ptr< DERIVEDFACTOR > factor)
Add a factor directly using a shared_ptr.
DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode
const mpreal root(const mpreal &x, unsigned long int k, mp_rnd_t r=mpreal::get_default_rnd())
NonlinearFactorGraph graph
bool exists(const VALUE &e) const
bool equals(const Values &other, double tol=1e-9) const
void computeUnusedKeys(const NonlinearFactorGraph &newFactors, const VariableIndex &variableIndex, const KeySet &keysWithRemovedFactors, KeySet *unusedKeys) const
Values calculateBestEstimate() const
ptrdiff_t DenseIndex
The index type for Eigen objects.
void g(const string &key, int i)
void error(const NonlinearFactorGraph &nonlinearFactors, const Values &estimate, boost::optional< double > *result) const
size_t size() const
The number of variable entries. This is equal to the number of unique variable Keys.
void pushBackFactors(const NonlinearFactorGraph &newFactors, NonlinearFactorGraph *nonlinearFactors, GaussianFactorGraph *linearFactors, VariableIndex *variableIndex, FactorIndices *newFactorsIndices, KeySet *keysWithRemovedFactors) const
sharedConditional marginalFactor(Key j, const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
double error(const VectorValues &x) const
static Ordering Colamd(const FACTOR_GRAPH &graph)
FactorIndices newFactorsIndices
Values calculateEstimate() const
bool equals(const NonlinearFactorGraph &other, double tol=1e-9) const
const sharedClique & clique(Key j) const
double error(const VectorValues &x) const
FastVector< Key > KeyVector
Define collection type once and for all - also used in wrappers.
Cliques removeSubtree(const sharedClique &subtree)
void remove(ITERATOR firstFactor, ITERATOR lastFactor, const FG &factors)
constexpr int first(int i)
Implementation details for constexpr functions.
void updateKeys(const KeySet &markedKeys, ISAM2Result *result) const
NonlinearFactorGraph nonlinearFactors_
const ValueType at(Key j) const
bool evaluateNonlinearError
virtual bool equals(const ISAM2 &other, double tol=1e-9) const
void marginalizeLeaves(const FastList< Key > &leafKeys, boost::optional< FactorIndices & > marginalFactorsIndices=boost::none, boost::optional< FactorIndices & > deletedFactorsIndices=boost::none)
Class that stores detailed iSAM2 result.
boost::optional< double > doglegDelta_
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
void recordRelinearizeDetail(const KeySet &relinKeys, ISAM2Result::DetailedResults *detail) const
boost::optional< double > errorAfter
GaussianFactorGraph linearFactors_
DetailedResults * details()
Return pointer to detail, 0 if no detail requested.
StatusMap variableStatus
The status of each variable during this update, see VariableStatus.
OptimizationParams optimizationParams
Base::sharedClique sharedClique
Shared pointer to a clique.
static SmartStereoProjectionParams params
const ISAM2Params & params() const
bool relinarizationNeeded(size_t update_count) const
VectorValues gradientAtZero() const
KeySet deltaReplacedMask_
const_iterator end() const
Iterator to the first variable entry.
static Ordering ColamdConstrained(const FACTOR_GRAPH &graph, const FastMap< Key, int > &groups)
boost::shared_ptr< This > shared_ptr
const VectorValues & getDelta() const
void unsafe_erase(typename Base::iterator position)
void print(const std::string &str="", const KeyFormatter &keyFormatter=DefaultKeyFormatter) const
virtual void print(const std::string &s="FactorGraph", const KeyFormatter &formatter=DefaultKeyFormatter) const
print out graph
static size_t UpdateRgProd(const ISAM2::Roots &roots, const KeySet &replacedKeys, const VectorValues &gradAtZero, VectorValues *RgProd)
Incremental update functionality (ISAM2) for BayesTree, with fluid relinearization.
FactorIndices removeFactorIndices
void addVariables(const Values &newTheta, ISAM2Result::DetailedResults *detail=0)
KeySet gatherRelinearizeKeys(const ISAM2::Roots &roots, const VectorValues &delta, const KeySet &fixedVariables, KeySet *markedKeys) const
void linearizeNewFactors(const NonlinearFactorGraph &newFactors, const Values &theta, size_t numNonlinearFactors, const FactorIndices &newFactorsIndices, GaussianFactorGraph *linearFactors) const
boost::optional< double > errorBefore
void findFluid(const ISAM2::Roots &roots, const KeySet &relinKeys, KeySet *markedKeys, ISAM2Result::DetailedResults *detail) const
virtual ISAM2Result update(const NonlinearFactorGraph &newFactors=NonlinearFactorGraph(), const Values &newTheta=Values(), const FactorIndices &removeFactorIndices=FactorIndices(), const boost::optional< FastMap< Key, int > > &constrainedKeys=boost::none, const boost::optional< FastList< Key > > &noRelinKeys=boost::none, const boost::optional< FastList< Key > > &extraReelimKeys=boost::none, bool force_relinearize=false)
static void ExpmapMasked(const VectorValues &delta, const KeySet &mask, Values *theta)
VectorValues deltaNewton_
double error(const Values &values) const
void augmentVariableIndex(const NonlinearFactorGraph &newFactors, const FactorIndices &newFactorsIndices, VariableIndex *variableIndex) const
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
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).
boost::optional< FastList< Key > > noRelinKeys
void updateDelta(bool forceFullSolve=false) const
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
iterator insert(const std::pair< Key, Vector > &key_value)
boost::optional< FastMap< Key, int > > constrainedKeys
const Roots & roots() const
std::uint64_t Key
Integer nonlinear key type.
boost::optional< DetailedResults > detail
bool cacheLinearizedFactors
size_t factorsRecalculated
static void LogStartingUpdate(const NonlinearFactorGraph &newFactors, const ISAM2 &isam2)
bool equals(const VariableIndex &other, double tol=0.0) const
Test for equality (for unit tests and debug assertions).
void gatherInvolvedKeys(const NonlinearFactorGraph &newFactors, const NonlinearFactorGraph &nonlinearFactors, const KeySet &keysWithRemovedFactors, KeySet *markedKeys) const