From d0b757da489f2410402025ff3e29957a5c21b5d7 Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Sun, 20 Dec 2009 21:21:01 +0000 Subject: [PATCH] remove method to set factor to NULL --- cpp/FactorGraph-inl.h | 2 +- cpp/FactorGraph.h | 13 ++++++++----- 2 files changed, 9 insertions(+), 6 deletions(-) diff --git a/cpp/FactorGraph-inl.h b/cpp/FactorGraph-inl.h index 0e7afdcd6..3f6217e08 100644 --- a/cpp/FactorGraph-inl.h +++ b/cpp/FactorGraph-inl.h @@ -245,7 +245,7 @@ FactorGraph::findAndRemoveFactors(const string& key) { BOOST_FOREACH(int i, *indices_ptr) { if(factors_[i] == NULL) continue; // skip NULL factors found.push_back(factors_[i]); // add to found - factors_[i].reset(); // set factor to NULL. + remove(i); // set factor to NULL. } return found; } diff --git a/cpp/FactorGraph.h b/cpp/FactorGraph.h index 2c6b64415..b1c4a6fa5 100644 --- a/cpp/FactorGraph.h +++ b/cpp/FactorGraph.h @@ -67,11 +67,14 @@ namespace gtsam { /** Get a specific factor by index */ inline sharedFactor operator[](size_t i) const {return factors_[i];} + /** delete factor without re-arranging indexes by inserting a NULL pointer */ + inline void remove(size_t i) { factors_[i].reset();} + /** return the number of factors and NULLS */ - inline size_t size() const { return factors_.size();} + inline size_t size() const { return factors_.size();} /** return the number valid factors */ - size_t nrFactors() const; + size_t nrFactors() const; /** Add a factor */ void push_back(sharedFactor factor); @@ -95,9 +98,9 @@ namespace gtsam { */ Ordering getOrdering() const; - /** - * shared pointer versions for MATLAB - */ + /** + * shared pointer versions for MATLAB + */ boost::shared_ptr getOrdering_() const; /**