Values::keys now returns KeyVector instead of list. Corresponding fixes in Matlab wrapper.

release/4.3a0
cbeall3 2015-06-24 00:35:32 -04:00
parent 348e2144ce
commit 0e022b3b33
6 changed files with 16 additions and 16 deletions

16
gtsam.h
View File

@ -1654,12 +1654,12 @@ char symbolChr(size_t key);
size_t symbolIndex(size_t key);
// Default keyformatter
void printKeyList (const gtsam::KeyList& keys);
void printKeyList (const gtsam::KeyList& keys, string s);
void printKeyVector(const gtsam::KeyVector& keys);
void printKeyVector(const gtsam::KeyVector& keys, string s);
void printKeySet (const gtsam::KeySet& keys);
void printKeySet (const gtsam::KeySet& keys, string s);
void PrintKeyList (const gtsam::KeyList& keys);
void PrintKeyList (const gtsam::KeyList& keys, string s);
void PrintKeyVector(const gtsam::KeyVector& keys);
void PrintKeyVector(const gtsam::KeyVector& keys, string s);
void PrintKeySet (const gtsam::KeySet& keys);
void PrintKeySet (const gtsam::KeySet& keys, string s);
#include <gtsam/inference/LabeledSymbol.h>
class LabeledSymbol {
@ -1776,7 +1776,7 @@ class Values {
void swap(gtsam::Values& values);
bool exists(size_t j) const;
gtsam::KeyList keys() const;
gtsam::KeyVector keys() const;
gtsam::VectorValues zeroVectors() const;
@ -1893,8 +1893,6 @@ class KeySet {
class KeyVector {
KeyVector();
KeyVector(const gtsam::KeyVector& other);
KeyVector(const gtsam::KeySet& other);
KeyVector(const gtsam::KeyList& other);
// Note: no print function

View File

@ -210,8 +210,9 @@ namespace gtsam {
}
/* ************************************************************************* */
FastList<Key> Values::keys() const {
FastList<Key> result;
KeyVector Values::keys() const {
KeyVector result;
result.reserve(size());
for(const_iterator key_value = begin(); key_value != end(); ++key_value)
result.push_back(key_value->key);
return result;

View File

@ -291,7 +291,7 @@ namespace gtsam {
* Returns a set of keys in the config
* Note: by construction, the list is ordered
*/
KeyList keys() const;
KeyVector keys() const;
/** Replace all keys and variables */
Values& operator=(const Values& rhs);

View File

@ -26,6 +26,7 @@
#include <CppUnitLite/TestHarness.h>
#include <boost/assign/std/list.hpp> // for operator +=
#include <boost/assign/std/vector.hpp>
#include <boost/assign/list_of.hpp>
using namespace boost::assign;
#include <stdexcept>
@ -308,12 +309,12 @@ TEST(Values, extract_keys)
config.insert(key3, Pose2());
config.insert(key4, Pose2());
FastList<Key> expected, actual;
KeyVector expected, actual;
expected += key1, key2, key3, key4;
actual = config.keys();
CHECK(actual.size() == expected.size());
FastList<Key>::const_iterator itAct = actual.begin(), itExp = expected.begin();
KeyVector::const_iterator itAct = actual.begin(), itExp = expected.begin();
for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) {
EXPECT(*itExp == *itAct);
}

View File

@ -230,7 +230,7 @@ void ConcurrentBatchSmoother::reorder() {
// Recalculate the variable index
variableIndex_ = VariableIndex(factors_);
FastList<Key> separatorKeys = separatorValues_.keys();
KeyVector separatorKeys = separatorValues_.keys();
ordering_ = Ordering::colamdConstrainedLast(variableIndex_, std::vector<Key>(separatorKeys.begin(), separatorKeys.end()));
}

View File

@ -229,7 +229,7 @@ Values localToWorld(const Values& local, const Pose2& base,
// if no keys given, get all keys from local values
FastVector<Key> keys(user_keys);
if (keys.size()==0)
keys = FastVector<Key>(local.keys());
keys = local.keys();
// Loop over all keys
BOOST_FOREACH(Key key, keys) {