diff --git a/gtsam.h b/gtsam.h index 2516cb202..171749a83 100644 --- a/gtsam.h +++ b/gtsam.h @@ -896,6 +896,7 @@ class SymbolicBayesNet { // Standard interface size_t size() const; void saveGraph(string s) const; + gtsam::SymbolicConditional* at(size_t idx) const; gtsam::SymbolicConditional* front() const; gtsam::SymbolicConditional* back() const; void push_back(gtsam::SymbolicConditional* conditional); @@ -947,7 +948,7 @@ class SymbolicBayesTree { // // BayesNet shortcut(derived_ptr root, Eliminate function) const; // // FactorGraph marginal(derived_ptr root, Eliminate function) const; // // FactorGraph joint(derived_ptr C2, derived_ptr root, Eliminate function) const; -// +// // void deleteCachedShortcuts(); // }; @@ -1317,13 +1318,19 @@ class GaussianFactorGraph { #include virtual class GaussianConditional : gtsam::GaussianFactor { - //Constructors + //Constructors GaussianConditional(size_t key, Vector d, Matrix R, const gtsam::noiseModel::Diagonal* sigmas); GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, const gtsam::noiseModel::Diagonal* sigmas); GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, size_t name2, Matrix T, const gtsam::noiseModel::Diagonal* sigmas); + //Constructors with no noise model + GaussianConditional(size_t key, Vector d, Matrix R); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S); + GaussianConditional(size_t key, Vector d, Matrix R, size_t name1, Matrix S, + size_t name2, Matrix T); + //Standard Interface void print(string s) const; bool equals(const gtsam::GaussianConditional &cg, double tol) const; @@ -1704,6 +1711,23 @@ class KeyVector { void serialize() const; }; +// Actually a FastMap +class KeyGroupMap { + KeyGroupMap(); + + // Note: no print function + + // common STL methods + size_t size() const; + bool empty() const; + void clear(); + + // structure specific methods + size_t at(size_t key) const; + int erase(size_t key); + bool insert2(size_t key, int val); +}; + #include class Marginals { Marginals(const gtsam::NonlinearFactorGraph& graph, @@ -1959,6 +1983,7 @@ class ISAM2 { gtsam::ISAM2Result update(); gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta); gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices); + gtsam::ISAM2Result update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, const gtsam::KeyGroupMap& constrainedKeys); // TODO: wrap the full version of update //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys); //void update(const gtsam::NonlinearFactorGraph& newFactors, const gtsam::Values& newTheta, const gtsam::KeyVector& removeFactorIndices, FastMap& constrainedKeys, bool force_relinearize); diff --git a/gtsam/base/FastMap.h b/gtsam/base/FastMap.h index 2ef201b9d..084919427 100644 --- a/gtsam/base/FastMap.h +++ b/gtsam/base/FastMap.h @@ -60,6 +60,8 @@ public: return std::map(this->begin(), this->end()); } + /** Handy 'insert' function for Matlab wrapper */ + bool insert2(const KEY& key, const VALUE& val) { return Base::insert(std::make_pair(key, val)).second; } /** Handy 'exists' function */ bool exists(const KEY& e) const { return this->find(e) != this->end(); } diff --git a/gtsam/inference/Key.h b/gtsam/inference/Key.h index 21f75e8d4..3f573fcce 100644 --- a/gtsam/inference/Key.h +++ b/gtsam/inference/Key.h @@ -24,6 +24,7 @@ #include #include #include +#include namespace gtsam { @@ -43,6 +44,7 @@ namespace gtsam { typedef FastList KeyList; typedef FastVector KeyVector; typedef FastSet KeySet; + typedef FastMap KeyGroupMap; /// Utility function to print sets of keys with optional prefix GTSAM_EXPORT void printKeySet(const KeySet& keys, const std::string& s = "",