diff --git a/cpp/ISAM2-inl.h b/cpp/ISAM2-inl.h index cc18f4131..24134536b 100644 --- a/cpp/ISAM2-inl.h +++ b/cpp/ISAM2-inl.h @@ -201,8 +201,14 @@ namespace gtsam { // todo - remerge in keys of new factors affectedKeys.insert(newKeys.begin(), newKeys.end()); + // Save number of affected variables + lastAffectedVariableCount = affectedKeys.size(); + factors = relinearizeAffectedFactors(affectedKeys); + // Save number of affected factors + lastAffectedFactorCount = factors.size(); + // add the cached intermediate results from the boundary of the orphans ... FactorGraph cachedBoundary = getCachedBoundaryFactors(orphans); factors.push_back(cachedBoundary); @@ -229,6 +235,9 @@ namespace gtsam { for ( rit=bayesNet.rbegin(); rit != bayesNet.rend(); ++rit ) this->insert(*rit, index); + // Save number of affectedCliques + lastAffectedCliqueCount = this->size(); + // add orphans to the bottom of the new tree BOOST_FOREACH(sharedClique orphan, orphans) { Symbol parentRepresentative = findParentClique(orphan->separator_, index); diff --git a/cpp/ISAM2.h b/cpp/ISAM2.h index b814279e9..8ef2a3259 100644 --- a/cpp/ISAM2.h +++ b/cpp/ISAM2.h @@ -81,7 +81,17 @@ namespace gtsam { // estimate based on full delta (note that this is based on the actual current linearization point) const Config calculateBestEstimate() const {return expmap(theta_, optimize2(*this, 0.));} - const std::list& getMarked() const { return marked_; } + const std::list& getMarkedUnsafe() const { return marked_; } + + const NonlinearFactorGraph& getFactorsUnsafe() const { return nonlinearFactors_; } + + const Config& getThetaUnsafe() const { return theta_; } + + const VectorConfig& getDeltaUnsafe() const { return delta_; } + + size_t lastAffectedVariableCount; + size_t lastAffectedFactorCount; + size_t lastAffectedCliqueCount; private: diff --git a/cpp/LieConfig-inl.h b/cpp/LieConfig-inl.h index d6193e4c1..148da90ef 100644 --- a/cpp/LieConfig-inl.h +++ b/cpp/LieConfig-inl.h @@ -20,6 +20,7 @@ /*INSTANTIATE_LIE(T);*/ \ template LieConfig expmap(const LieConfig&, const VectorConfig&); \ template LieConfig expmap(const LieConfig&, const Vector&); \ + template VectorConfig logmap(const LieConfig&, const LieConfig&); \ template class LieConfig; using namespace std; @@ -107,6 +108,20 @@ namespace gtsam { } return newConfig; } + + // todo: insert for every element is inefficient + // todo: currently only logmaps elements in both configs + template + VectorConfig logmap(const LieConfig& c0, const LieConfig& cp) { + VectorConfig delta; + typedef pair Value; + BOOST_FOREACH(const Value& value, cp) { + if(c0.exists(value.first)) + delta.insert(value.first, + logmap(c0[value.first], value.second)); + } + return delta; + } } diff --git a/cpp/LieConfig.h b/cpp/LieConfig.h index f3445d0e5..6900201c8 100644 --- a/cpp/LieConfig.h +++ b/cpp/LieConfig.h @@ -115,5 +115,9 @@ namespace gtsam { /** Add a delta vector, uses iterator order */ template LieConfig expmap(const LieConfig& c, const Vector& delta); + + /** Get a delta config about a linearization point c0 */ + template + VectorConfig logmap(const LieConfig& c0, const LieConfig& cp); } diff --git a/cpp/TupleConfig.h b/cpp/TupleConfig.h index 5f6195813..16b11ba50 100644 --- a/cpp/TupleConfig.h +++ b/cpp/TupleConfig.h @@ -6,6 +6,7 @@ */ #include "LieConfig.h" +#include "VectorConfig.h" #pragma once @@ -98,9 +99,18 @@ namespace gtsam { /** * expmap each element */ - PairConfig expmap(const VectorConfig& delta) { + PairConfig expmap(const VectorConfig& delta) const { return PairConfig(gtsam::expmap(first, delta), gtsam::expmap(second, delta)); } + /** + * logmap each element + */ + VectorConfig logmap(const PairConfig& cp) const { + VectorConfig ret(gtsam::logmap(first, cp.first)); + ret.insert(gtsam::logmap(second, cp.second)); + return ret; + } + /** * Insert a variable with the given j */ @@ -126,7 +136,9 @@ namespace gtsam { }; template - inline PairConfig expmap(PairConfig c, const VectorConfig& delta) { return c.expmap(delta); } + inline PairConfig expmap(const PairConfig c, const VectorConfig& delta) { return c.expmap(delta); } + template + inline VectorConfig logmap(const PairConfig c0, const PairConfig& cp) { return c0.logmap(cp); } }