Merged from branch 'branches/2.0_prep_intkeys'

release/4.3a0
Richard Roberts 2012-02-21 19:01:52 +00:00
commit 8638683951
72 changed files with 1897 additions and 1847 deletions

2002
.cproject

File diff suppressed because it is too large Load Diff

View File

@ -29,8 +29,8 @@ using namespace gtsam;
/** /**
* Unary factor for the pose. * Unary factor for the pose.
*/ */
class ResectioningFactor: public NonlinearFactor1<Pose3> { class ResectioningFactor: public NoiseModelFactor1<Pose3> {
typedef NonlinearFactor1<Pose3> Base; typedef NoiseModelFactor1<Pose3> Base;
shared_ptrK K_; // camera's intrinsic parameters shared_ptrK K_; // camera's intrinsic parameters
Point3 P_; // 3D point on the calibration rig Point3 P_; // 3D point on the calibration rig

View File

@ -23,7 +23,7 @@
* void print(const std::string& name) const = 0; * void print(const std::string& name) const = 0;
* *
* equality up to tolerance * equality up to tolerance
* tricky to implement, see NonlinearFactor1 for an example * tricky to implement, see NoiseModelFactor1 for an example
* equals is not supposed to print out *anything*, just return true|false * equals is not supposed to print out *anything*, just return true|false
* bool equals(const Derived& expected, double tol) const = 0; * bool equals(const Derived& expected, double tol) const = 0;
* *

View File

@ -46,7 +46,7 @@ private:
/** Create keys by adding key in front */ /** Create keys by adding key in front */
template<typename ITERATOR> template<typename ITERATOR>
static std::vector<KEY> MakeKeys(KEY key, ITERATOR firstParent, ITERATOR lastParent) { static std::vector<KEY> MakeKeys(KEY key, ITERATOR firstParent, ITERATOR lastParent) {
std::vector<Key> keys((lastParent - firstParent) + 1); std::vector<KeyType> keys((lastParent - firstParent) + 1);
std::copy(firstParent, lastParent, keys.begin() + 1); std::copy(firstParent, lastParent, keys.begin() + 1);
keys[0] = key; keys[0] = key;
return keys; return keys;
@ -62,16 +62,16 @@ protected:
public: public:
typedef KEY Key; typedef KEY KeyType;
typedef Conditional<Key> This; typedef Conditional<KeyType> This;
typedef Factor<Key> Base; typedef Factor<KeyType> Base;
/** /**
* Typedef to the factor type that produces this conditional and that this * Typedef to the factor type that produces this conditional and that this
* conditional can be converted to using a factor constructor. Derived * conditional can be converted to using a factor constructor. Derived
* classes must redefine this. * classes must redefine this.
*/ */
typedef gtsam::Factor<Key> FactorType; typedef gtsam::Factor<KeyType> FactorType;
/** A shared_ptr to this class. Derived classes must redefine this. */ /** A shared_ptr to this class. Derived classes must redefine this. */
typedef boost::shared_ptr<This> shared_ptr; typedef boost::shared_ptr<This> shared_ptr;
@ -95,23 +95,23 @@ public:
Conditional() : nrFrontals_(0) { assertInvariants(); } Conditional() : nrFrontals_(0) { assertInvariants(); }
/** No parents */ /** No parents */
Conditional(Key key) : FactorType(key), nrFrontals_(1) { assertInvariants(); } Conditional(KeyType key) : FactorType(key), nrFrontals_(1) { assertInvariants(); }
/** Single parent */ /** Single parent */
Conditional(Key key, Key parent) : FactorType(key, parent), nrFrontals_(1) { assertInvariants(); } Conditional(KeyType key, KeyType parent) : FactorType(key, parent), nrFrontals_(1) { assertInvariants(); }
/** Two parents */ /** Two parents */
Conditional(Key key, Key parent1, Key parent2) : FactorType(key, parent1, parent2), nrFrontals_(1) { assertInvariants(); } Conditional(KeyType key, KeyType parent1, KeyType parent2) : FactorType(key, parent1, parent2), nrFrontals_(1) { assertInvariants(); }
/** Three parents */ /** Three parents */
Conditional(Key key, Key parent1, Key parent2, Key parent3) : FactorType(key, parent1, parent2, parent3), nrFrontals_(1) { assertInvariants(); } Conditional(KeyType key, KeyType parent1, KeyType parent2, KeyType parent3) : FactorType(key, parent1, parent2, parent3), nrFrontals_(1) { assertInvariants(); }
/// @} /// @}
/// @name Advanced Constructors /// @name Advanced Constructors
/// @{ /// @{
/** Constructor from a frontal variable and a vector of parents */ /** Constructor from a frontal variable and a vector of parents */
Conditional(Key key, const std::vector<Key>& parents) : Conditional(KeyType key, const std::vector<KeyType>& parents) :
FactorType(MakeKeys(key, parents.begin(), parents.end())), nrFrontals_(1) { FactorType(MakeKeys(key, parents.begin(), parents.end())), nrFrontals_(1) {
assertInvariants(); assertInvariants();
} }
@ -145,8 +145,8 @@ public:
size_t nrParents() const { return FactorType::size() - nrFrontals_; } size_t nrParents() const { return FactorType::size() - nrFrontals_; }
/** Special accessor when there is only one frontal variable. */ /** Special accessor when there is only one frontal variable. */
Key firstFrontalKey() const { assert(nrFrontals_>0); return FactorType::front(); } KeyType firstFrontalKey() const { assert(nrFrontals_>0); return FactorType::front(); }
Key lastFrontalKey() const { assert(nrFrontals_>0); return *(endFrontals()-1); } KeyType lastFrontalKey() const { assert(nrFrontals_>0); return *(endFrontals()-1); }
/** return a view of the frontal keys */ /** return a view of the frontal keys */
Frontals frontals() const { Frontals frontals() const {
@ -198,9 +198,9 @@ private:
template<typename KEY> template<typename KEY>
void Conditional<KEY>::print(const std::string& s) const { void Conditional<KEY>::print(const std::string& s) const {
std::cout << s << " P("; std::cout << s << " P(";
BOOST_FOREACH(Key key, frontals()) std::cout << " " << key; BOOST_FOREACH(KeyType key, frontals()) std::cout << " " << key;
if (nrParents()>0) std::cout << " |"; if (nrParents()>0) std::cout << " |";
BOOST_FOREACH(Key parent, parents()) std::cout << " " << parent; BOOST_FOREACH(KeyType parent, parents()) std::cout << " " << parent;
std::cout << ")" << std::endl; std::cout << ")" << std::endl;
} }

View File

@ -45,8 +45,8 @@ namespace gtsam {
void Factor<KEY>::assertInvariants() const { void Factor<KEY>::assertInvariants() const {
#ifndef NDEBUG #ifndef NDEBUG
// Check that keys are all unique // Check that keys are all unique
std::multiset < Key > nonunique(keys_.begin(), keys_.end()); std::multiset < KeyType > nonunique(keys_.begin(), keys_.end());
std::set < Key > unique(keys_.begin(), keys_.end()); std::set < KeyType > unique(keys_.begin(), keys_.end());
bool correct = (nonunique.size() == unique.size()) bool correct = (nonunique.size() == unique.size())
&& std::equal(nonunique.begin(), nonunique.end(), unique.begin()); && std::equal(nonunique.begin(), nonunique.end(), unique.begin());
if (!correct) throw std::logic_error( if (!correct) throw std::logic_error(

View File

@ -55,28 +55,28 @@ class Factor {
public: public:
typedef KEY Key; ///< The KEY template parameter typedef KEY KeyType; ///< The KEY template parameter
typedef Factor<Key> This; ///< This class typedef Factor<KeyType> This; ///< This class
/** /**
* Typedef to the conditional type obtained by eliminating this factor, * Typedef to the conditional type obtained by eliminating this factor,
* derived classes must redefine this. * derived classes must redefine this.
*/ */
typedef Conditional<Key> ConditionalType; typedef Conditional<KeyType> ConditionalType;
/// A shared_ptr to this class, derived classes must redefine this. /// A shared_ptr to this class, derived classes must redefine this.
typedef boost::shared_ptr<Factor> shared_ptr; typedef boost::shared_ptr<Factor> shared_ptr;
/// Iterator over keys /// Iterator over keys
typedef typename std::vector<Key>::iterator iterator; typedef typename std::vector<KeyType>::iterator iterator;
/// Const iterator over keys /// Const iterator over keys
typedef typename std::vector<Key>::const_iterator const_iterator; typedef typename std::vector<KeyType>::const_iterator const_iterator;
protected: protected:
/// The keys involved in this factor /// The keys involved in this factor
std::vector<Key> keys_; std::vector<KeyType> keys_;
friend class JacobianFactor; friend class JacobianFactor;
friend class HessianFactor; friend class HessianFactor;
@ -102,19 +102,19 @@ public:
Factor() {} Factor() {}
/** Construct unary factor */ /** Construct unary factor */
Factor(Key key) : keys_(1) { Factor(KeyType key) : keys_(1) {
keys_[0] = key; assertInvariants(); } keys_[0] = key; assertInvariants(); }
/** Construct binary factor */ /** Construct binary factor */
Factor(Key key1, Key key2) : keys_(2) { Factor(KeyType key1, KeyType key2) : keys_(2) {
keys_[0] = key1; keys_[1] = key2; assertInvariants(); } keys_[0] = key1; keys_[1] = key2; assertInvariants(); }
/** Construct ternary factor */ /** Construct ternary factor */
Factor(Key key1, Key key2, Key key3) : keys_(3) { Factor(KeyType key1, KeyType key2, KeyType key3) : keys_(3) {
keys_[0] = key1; keys_[1] = key2; keys_[2] = key3; assertInvariants(); } keys_[0] = key1; keys_[1] = key2; keys_[2] = key3; assertInvariants(); }
/** Construct 4-way factor */ /** Construct 4-way factor */
Factor(Key key1, Key key2, Key key3, Key key4) : keys_(4) { Factor(KeyType key1, KeyType key2, KeyType key3, KeyType key4) : keys_(4) {
keys_[0] = key1; keys_[1] = key2; keys_[2] = key3; keys_[3] = key4; assertInvariants(); } keys_[0] = key1; keys_[1] = key2; keys_[2] = key3; keys_[3] = key4; assertInvariants(); }
/// @} /// @}
@ -122,13 +122,13 @@ public:
/// @{ /// @{
/** Construct n-way factor */ /** Construct n-way factor */
Factor(const std::set<Key>& keys) { Factor(const std::set<KeyType>& keys) {
BOOST_FOREACH(const Key& key, keys) keys_.push_back(key); BOOST_FOREACH(const KeyType& key, keys) keys_.push_back(key);
assertInvariants(); assertInvariants();
} }
/** Construct n-way factor */ /** Construct n-way factor */
Factor(const std::vector<Key>& keys) : keys_(keys) { Factor(const std::vector<KeyType>& keys) : keys_(keys) {
assertInvariants(); assertInvariants();
} }
@ -157,16 +157,16 @@ public:
/// @{ /// @{
/// First key /// First key
Key front() const { return keys_.front(); } KeyType front() const { return keys_.front(); }
/// Last key /// Last key
Key back() const { return keys_.back(); } KeyType back() const { return keys_.back(); }
/// find /// find
const_iterator find(Key key) const { return std::find(begin(), end(), key); } const_iterator find(KeyType key) const { return std::find(begin(), end(), key); }
///TODO: comment ///TODO: comment
const std::vector<Key>& keys() const { return keys_; } const std::vector<KeyType>& keys() const { return keys_; }
/** iterators */ /** iterators */
const_iterator begin() const { return keys_.begin(); } ///TODO: comment const_iterator begin() const { return keys_.begin(); } ///TODO: comment
@ -194,7 +194,7 @@ public:
/** /**
* @return keys involved in this factor * @return keys involved in this factor
*/ */
std::vector<Key>& keys() { return keys_; } std::vector<KeyType>& keys() { return keys_; }
/** mutable iterators */ /** mutable iterators */
iterator begin() { return keys_.begin(); } ///TODO: comment iterator begin() { return keys_.begin(); } ///TODO: comment

View File

@ -43,11 +43,11 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
bool IndexConditional::permuteSeparatorWithInverse(const Permutation& inversePermutation) { bool IndexConditional::permuteSeparatorWithInverse(const Permutation& inversePermutation) {
#ifndef NDEBUG #ifndef NDEBUG
BOOST_FOREACH(Key key, frontals()) { assert(key == inversePermutation[key]); } BOOST_FOREACH(KeyType key, frontals()) { assert(key == inversePermutation[key]); }
#endif #endif
bool parentChanged = false; bool parentChanged = false;
BOOST_FOREACH(Key& parent, parents()) { BOOST_FOREACH(KeyType& parent, parents()) {
Key newParent = inversePermutation[parent]; KeyType newParent = inversePermutation[parent];
if(parent != newParent) { if(parent != newParent) {
parentChanged = true; parentChanged = true;
parent = newParent; parent = newParent;
@ -61,8 +61,8 @@ namespace gtsam {
void IndexConditional::permuteWithInverse(const Permutation& inversePermutation) { void IndexConditional::permuteWithInverse(const Permutation& inversePermutation) {
// The permutation may not move the separators into the frontals // The permutation may not move the separators into the frontals
#ifndef NDEBUG #ifndef NDEBUG
BOOST_FOREACH(const Key frontal, this->frontals()) { BOOST_FOREACH(const KeyType frontal, this->frontals()) {
BOOST_FOREACH(const Key separator, this->parents()) { BOOST_FOREACH(const KeyType separator, this->parents()) {
assert(inversePermutation[frontal] < inversePermutation[separator]); assert(inversePermutation[frontal] < inversePermutation[separator]);
} }
} }

View File

@ -24,10 +24,6 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
#include <gtsam/base/TestableAssertions.h> #include <gtsam/base/TestableAssertions.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/inference/SymbolicFactorGraph.h> #include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/inference/JunctionTree.h> #include <gtsam/inference/JunctionTree.h>
#include <gtsam/inference/ClusterTree.h> #include <gtsam/inference/ClusterTree.h>

View File

@ -16,12 +16,9 @@
* @date Feb 7, 2012 * @date Feb 7, 2012
*/ */
#define GTSAM_MAGIC_KEY
#include <gtsam/inference/IndexConditional.h> #include <gtsam/inference/IndexConditional.h>
#include <gtsam/inference/SymbolicFactorGraph.h> #include <gtsam/inference/SymbolicFactorGraph.h>
#include <gtsam/inference/BayesTree.h> #include <gtsam/inference/BayesTree.h>
#include <gtsam/nonlinear/Ordering.h>
#include <gtsam/base/serializationTestHelpers.h> #include <gtsam/base/serializationTestHelpers.h>
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
@ -32,13 +29,12 @@ using namespace gtsam::serializationTestHelpers;
/* ************************************************************************* */ /* ************************************************************************* */
TEST (Serialization, symbolic_graph) { TEST (Serialization, symbolic_graph) {
Ordering o; o += "x1","l1","x2";
// construct expected symbolic graph // construct expected symbolic graph
SymbolicFactorGraph sfg; SymbolicFactorGraph sfg;
sfg.push_factor(o["x1"]); sfg.push_factor(0);
sfg.push_factor(o["x1"],o["x2"]); sfg.push_factor(0,1);
sfg.push_factor(o["x1"],o["l1"]); sfg.push_factor(0,2);
sfg.push_factor(o["l1"],o["x2"]); sfg.push_factor(2,1);
EXPECT(equalsObj(sfg)); EXPECT(equalsObj(sfg));
EXPECT(equalsXML(sfg)); EXPECT(equalsXML(sfg));
@ -46,11 +42,9 @@ TEST (Serialization, symbolic_graph) {
/* ************************************************************************* */ /* ************************************************************************* */
TEST (Serialization, symbolic_bn) { TEST (Serialization, symbolic_bn) {
Ordering o; o += "x2","l1","x1"; IndexConditional::shared_ptr x2(new IndexConditional(1, 2, 0));
IndexConditional::shared_ptr l1(new IndexConditional(2, 0));
IndexConditional::shared_ptr x2(new IndexConditional(o["x2"], o["l1"], o["x1"])); IndexConditional::shared_ptr x1(new IndexConditional(0));
IndexConditional::shared_ptr l1(new IndexConditional(o["l1"], o["x1"]));
IndexConditional::shared_ptr x1(new IndexConditional(o["x1"]));
SymbolicBayesNet sbn; SymbolicBayesNet sbn;
sbn.push_back(x2); sbn.push_back(x2);

View File

@ -37,11 +37,11 @@ private:
Map values_; Map values_;
public: public:
typedef pair<Symbol, T> value_type; typedef pair<Key, T> value_type;
SymbolMapExp() {} SymbolMapExp() {}
T& at(const Symbol& key) { T& at(Key key) {
typename Map::iterator it = values_.find(key.chr()); typename Map::iterator it = values_.find(key.chr());
if(it != values_.end()) if(it != values_.end())
return it->second.at(key.index()); return it->second.at(key.index());
@ -49,7 +49,7 @@ public:
throw invalid_argument("Key " + (string)key + " not present"); throw invalid_argument("Key " + (string)key + " not present");
} }
void set(const Symbol& key, const T& value) { void set(Key key, const T& value) {
Vec& vec(values_[key.chr()]); Vec& vec(values_[key.chr()]);
//vec.reserve(10000); //vec.reserve(10000);
if(key.index() >= vec.size()) { if(key.index() >= vec.size()) {
@ -62,13 +62,13 @@ public:
}; };
template<class T> template<class T>
class SymbolMapBinary : public std::map<Symbol, T> { class SymbolMapBinary : public std::map<Key, T> {
private: private:
typedef std::map<Symbol, T> Base; typedef std::map<Key, T> Base;
public: public:
SymbolMapBinary() : std::map<Symbol, T>() {} SymbolMapBinary() : std::map<Key, T>() {}
T& at(const Symbol& key) { T& at(Key key) {
typename Base::iterator it = Base::find(key); typename Base::iterator it = Base::find(key);
if (it == Base::end()) if (it == Base::end())
throw(std::invalid_argument("SymbolMap::[] invalid key: " + (std::string)key)); throw(std::invalid_argument("SymbolMap::[] invalid key: " + (std::string)key));
@ -76,8 +76,8 @@ public:
} }
}; };
struct SymbolHash : public std::unary_function<Symbol, std::size_t> { struct SymbolHash : public std::unary_function<Key, std::size_t> {
std::size_t operator()(Symbol const& x) const { std::size_t operator()(Key const& x) const {
std::size_t seed = 0; std::size_t seed = 0;
boost::hash_combine(seed, x.chr()); boost::hash_combine(seed, x.chr());
boost::hash_combine(seed, x.index()); boost::hash_combine(seed, x.index());
@ -86,9 +86,9 @@ struct SymbolHash : public std::unary_function<Symbol, std::size_t> {
}; };
template<class T> template<class T>
class SymbolMapHash : public boost::unordered_map<Symbol, T, SymbolHash> { class SymbolMapHash : public boost::unordered_map<Key, T, SymbolHash> {
public: public:
SymbolMapHash() : boost::unordered_map<Symbol, T, SymbolHash>(60000) {} SymbolMapHash() : boost::unordered_map<Key, T, SymbolHash>(60000) {}
}; };
struct Value { struct Value {
@ -107,7 +107,7 @@ int main(int argc, char *argv[]) {
// pre-allocate // pre-allocate
cout << "Generating test data ..." << endl; cout << "Generating test data ..." << endl;
vector<pair<Symbol, Value> > values; vector<pair<Key, Value> > values;
for(size_t i=0; i<ELEMS; i++) { for(size_t i=0; i<ELEMS; i++) {
values.push_back(make_pair(Symbol('a',i), (double)i)); values.push_back(make_pair(Symbol('a',i), (double)i));
values.push_back(make_pair(Symbol('b',i), (double)i)); values.push_back(make_pair(Symbol('b',i), (double)i));

View File

@ -67,14 +67,14 @@ void SubgraphSolver<GRAPH,LINEAR,KEY>::initialize(const GRAPH& G, const Values&
// make the ordering // make the ordering
list<KEY> keys = predecessorMap2Keys(tree_); list<KEY> keys = predecessorMap2Keys(tree_);
ordering_ = boost::make_shared<Ordering>(list<Symbol>(keys.begin(), keys.end())); ordering_ = boost::make_shared<Ordering>(list<Key>(keys.begin(), keys.end()));
// build factor pairs // build factor pairs
pairs_.clear(); pairs_.clear();
typedef pair<KEY,KEY> EG ; typedef pair<KEY,KEY> EG ;
BOOST_FOREACH( const EG &eg, tree_ ) { BOOST_FOREACH( const EG &eg, tree_ ) {
Symbol key1 = Symbol(eg.first), Key key1 = Key(eg.first),
key2 = Symbol(eg.second) ; key2 = Key(eg.second) ;
pairs_.insert(pair<Index, Index>((*ordering_)[key1], (*ordering_)[key2])) ; pairs_.insert(pair<Index, Index>((*ordering_)[key1], (*ordering_)[key2])) ;
} }
} }

View File

@ -30,7 +30,7 @@ namespace gtsam {
template<class VALUE> template<class VALUE>
typename ExtendedKalmanFilter<VALUE>::T ExtendedKalmanFilter<VALUE>::solve_( typename ExtendedKalmanFilter<VALUE>::T ExtendedKalmanFilter<VALUE>::solve_(
const GaussianFactorGraph& linearFactorGraph, const Ordering& ordering, const GaussianFactorGraph& linearFactorGraph, const Ordering& ordering,
const Values& linearizationPoints, const Symbol& lastKey, const Values& linearizationPoints, Key lastKey,
JacobianFactor::shared_ptr& newPrior) const { JacobianFactor::shared_ptr& newPrior) const {
// Extract the Index of the provided last key // Extract the Index of the provided last key
@ -91,8 +91,8 @@ namespace gtsam {
// different keys will still compute as if a common key-set was used // different keys will still compute as if a common key-set was used
// Create Keys // Create Keys
Symbol x0 = motionFactor.key1(); Key x0 = motionFactor.key1();
Symbol x1 = motionFactor.key2(); Key x1 = motionFactor.key2();
// Create an elimination ordering // Create an elimination ordering
Ordering ordering; Ordering ordering;
@ -131,7 +131,7 @@ namespace gtsam {
// different keys will still compute as if a common key-set was used // different keys will still compute as if a common key-set was used
// Create Keys // Create Keys
Symbol x0 = measurementFactor.key(); Key x0 = measurementFactor.key();
// Create an elimination ordering // Create an elimination ordering
Ordering ordering; Ordering ordering;

View File

@ -46,8 +46,8 @@ namespace gtsam {
typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr; typedef boost::shared_ptr<ExtendedKalmanFilter<VALUE> > shared_ptr;
typedef VALUE T; typedef VALUE T;
typedef NonlinearFactor2<VALUE, VALUE> MotionFactor; typedef NoiseModelFactor2<VALUE, VALUE> MotionFactor;
typedef NonlinearFactor1<VALUE> MeasurementFactor; typedef NoiseModelFactor1<VALUE> MeasurementFactor;
protected: protected:
T x_; // linearization point T x_; // linearization point
@ -55,7 +55,7 @@ namespace gtsam {
T solve_(const GaussianFactorGraph& linearFactorGraph, T solve_(const GaussianFactorGraph& linearFactorGraph,
const Ordering& ordering, const Values& linearizationPoints, const Ordering& ordering, const Values& linearizationPoints,
const Symbol& x, JacobianFactor::shared_ptr& newPrior) const; Key x, JacobianFactor::shared_ptr& newPrior) const;
public: public:

View File

@ -121,7 +121,7 @@ namespace gtsam {
///* ************************************************************************* */ ///* ************************************************************************* */
//boost::shared_ptr<VectorValues> optimize2(const GaussianISAM2::sharedClique& root) { //boost::shared_ptr<VectorValues> optimize2(const GaussianISAM2::sharedClique& root) {
// boost::shared_ptr<VectorValues> delta(new VectorValues()); // boost::shared_ptr<VectorValues> delta(new VectorValues());
// set<Symbol> changed; // set<Key> changed;
// // starting from the root, call optimize on each conditional // // starting from the root, call optimize on each conditional
// optimize2(root, delta); // optimize2(root, delta);
// return delta; // return delta;

View File

@ -44,8 +44,10 @@ struct ISAM2<CONDITIONAL, GRAPH>::Impl {
* @param delta Current linear delta to be augmented with zeros * @param delta Current linear delta to be augmented with zeros
* @param ordering Current ordering to be augmented with new variables * @param ordering Current ordering to be augmented with new variables
* @param nodes Current BayesTree::Nodes index to be augmented with slots for new variables * @param nodes Current BayesTree::Nodes index to be augmented with slots for new variables
* @param keyFormatter Formatter for printing nonlinear keys during debugging
*/ */
static void AddVariables(const Values& newTheta, Values& theta, Permuted<VectorValues>& delta, Ordering& ordering, typename Base::Nodes& nodes); static void AddVariables(const Values& newTheta, Values& theta, Permuted<VectorValues>& delta, Ordering& ordering,
typename Base::Nodes& nodes, const KeyFormatter& keyFormatter = DefaultKeyFormatter);
/** /**
* Extract the set of variable indices from a NonlinearFactorGraph. For each Symbol * Extract the set of variable indices from a NonlinearFactorGraph. For each Symbol
@ -61,10 +63,12 @@ struct ISAM2<CONDITIONAL, GRAPH>::Impl {
* Any variables in the VectorValues delta whose vector magnitude is greater than * Any variables in the VectorValues delta whose vector magnitude is greater than
* or equal to relinearizeThreshold are returned. * or equal to relinearizeThreshold are returned.
* @param delta The linear delta to check against the threshold * @param delta The linear delta to check against the threshold
* @param keyFormatter Formatter for printing nonlinear keys during debugging
* @return The set of variable indices in delta whose magnitude is greater than or * @return The set of variable indices in delta whose magnitude is greater than or
* equal to relinearizeThreshold * equal to relinearizeThreshold
*/ */
static FastSet<Index> CheckRelinearization(const Permuted<VectorValues>& delta, const Ordering& ordering, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold); static FastSet<Index> CheckRelinearization(const Permuted<VectorValues>& delta, const Ordering& ordering,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter = DefaultKeyFormatter);
/** /**
* Recursively search this clique and its children for marked keys appearing * Recursively search this clique and its children for marked keys appearing
@ -94,10 +98,12 @@ struct ISAM2<CONDITIONAL, GRAPH>::Impl {
* expmapped deltas will be set to an invalid value (infinity) to catch bugs * expmapped deltas will be set to an invalid value (infinity) to catch bugs
* where we might expmap something twice, or expmap it but then not * where we might expmap something twice, or expmap it but then not
* recalculate its delta. * recalculate its delta.
* @param keyFormatter Formatter for printing nonlinear keys during debugging
*/ */
static void ExpmapMasked(Values& values, const Permuted<VectorValues>& delta, static void ExpmapMasked(Values& values, const Permuted<VectorValues>& delta,
const Ordering& ordering, const std::vector<bool>& mask, const Ordering& ordering, const std::vector<bool>& mask,
boost::optional<Permuted<VectorValues>&> invalidateIfDebug = boost::optional<Permuted<VectorValues>&>()); boost::optional<Permuted<VectorValues>&> invalidateIfDebug = boost::optional<Permuted<VectorValues>&>(),
const KeyFormatter& keyFormatter = DefaultKeyFormatter);
/** /**
* Reorder and eliminate factors. These factors form a subset of the full * Reorder and eliminate factors. These factors form a subset of the full
@ -120,7 +126,7 @@ struct ISAM2<CONDITIONAL, GRAPH>::Impl {
/* ************************************************************************* */ /* ************************************************************************* */
template<class CONDITIONAL, class GRAPH> template<class CONDITIONAL, class GRAPH>
void ISAM2<CONDITIONAL,GRAPH>::Impl::AddVariables( void ISAM2<CONDITIONAL,GRAPH>::Impl::AddVariables(
const Values& newTheta, Values& theta, Permuted<VectorValues>& delta, Ordering& ordering, typename Base::Nodes& nodes) { const Values& newTheta, Values& theta, Permuted<VectorValues>& delta, Ordering& ordering, typename Base::Nodes& nodes, const KeyFormatter& keyFormatter) {
const bool debug = ISDEBUG("ISAM2 AddVariables"); const bool debug = ISDEBUG("ISAM2 AddVariables");
theta.insert(newTheta); theta.insert(newTheta);
@ -139,7 +145,7 @@ void ISAM2<CONDITIONAL,GRAPH>::Impl::AddVariables(
BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, newTheta) { BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, newTheta) {
delta.permutation()[nextVar] = nextVar; delta.permutation()[nextVar] = nextVar;
ordering.insert(key_value.first, nextVar); ordering.insert(key_value.first, nextVar);
if(debug) cout << "Adding variable " << (string)key_value.first << " with order " << nextVar << endl; if(debug) cout << "Adding variable " << keyFormatter(key_value.first) << " with order " << nextVar << endl;
++ nextVar; ++ nextVar;
} }
assert(delta.permutation().size() == delta.container().size()); assert(delta.permutation().size() == delta.container().size());
@ -155,7 +161,7 @@ template<class CONDITIONAL, class GRAPH>
FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::IndicesFromFactors(const Ordering& ordering, const GRAPH& factors) { FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::IndicesFromFactors(const Ordering& ordering, const GRAPH& factors) {
FastSet<Index> indices; FastSet<Index> indices;
BOOST_FOREACH(const typename NonlinearFactor::shared_ptr& factor, factors) { BOOST_FOREACH(const typename NonlinearFactor::shared_ptr& factor, factors) {
BOOST_FOREACH(const Symbol& key, factor->keys()) { BOOST_FOREACH(Key key, factor->keys()) {
indices.insert(ordering[key]); indices.insert(ordering[key]);
} }
} }
@ -164,7 +170,8 @@ FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::IndicesFromFactors(const Ordering
/* ************************************************************************* */ /* ************************************************************************* */
template<class CONDITIONAL, class GRAPH> template<class CONDITIONAL, class GRAPH>
FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::CheckRelinearization(const Permuted<VectorValues>& delta, const Ordering& ordering, const ISAM2Params::RelinearizationThreshold& relinearizeThreshold) { FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::CheckRelinearization(const Permuted<VectorValues>& delta, const Ordering& ordering,
const ISAM2Params::RelinearizationThreshold& relinearizeThreshold, const KeyFormatter& keyFormatter) {
FastSet<Index> relinKeys; FastSet<Index> relinKeys;
if(relinearizeThreshold.type() == typeid(double)) { if(relinearizeThreshold.type() == typeid(double)) {
@ -178,7 +185,7 @@ FastSet<Index> ISAM2<CONDITIONAL,GRAPH>::Impl::CheckRelinearization(const Permut
} else if(relinearizeThreshold.type() == typeid(FastMap<char,Vector>)) { } else if(relinearizeThreshold.type() == typeid(FastMap<char,Vector>)) {
const FastMap<char,Vector>& thresholds = boost::get<FastMap<char,Vector> >(relinearizeThreshold); const FastMap<char,Vector>& thresholds = boost::get<FastMap<char,Vector> >(relinearizeThreshold);
BOOST_FOREACH(const Ordering::value_type& key_index, ordering) { BOOST_FOREACH(const Ordering::value_type& key_index, ordering) {
const Vector& threshold = thresholds.find(key_index.first.chr())->second; const Vector& threshold = thresholds.find(Symbol(key_index.first).chr())->second;
Index j = key_index.second; Index j = key_index.second;
if(threshold.rows() != delta[j].rows()) if(threshold.rows() != delta[j].rows())
throw std::invalid_argument("Relinearization threshold vector dimensionality passed into iSAM2 parameters does not match actual variable dimensionality"); throw std::invalid_argument("Relinearization threshold vector dimensionality passed into iSAM2 parameters does not match actual variable dimensionality");
@ -213,8 +220,8 @@ void ISAM2<CONDITIONAL,GRAPH>::Impl::FindAll(typename ISAM2Clique<CONDITIONAL>::
/* ************************************************************************* */ /* ************************************************************************* */
template<class CONDITIONAL, class GRAPH> template<class CONDITIONAL, class GRAPH>
void ISAM2<CONDITIONAL, GRAPH>::Impl::ExpmapMasked(Values& values, const Permuted<VectorValues>& delta, void ISAM2<CONDITIONAL, GRAPH>::Impl::ExpmapMasked(Values& values, const Permuted<VectorValues>& delta, const Ordering& ordering,
const Ordering& ordering, const vector<bool>& mask, boost::optional<Permuted<VectorValues>&> invalidateIfDebug) { const vector<bool>& mask, boost::optional<Permuted<VectorValues>&> invalidateIfDebug, const KeyFormatter& keyFormatter) {
// If debugging, invalidate if requested, otherwise do not invalidate. // If debugging, invalidate if requested, otherwise do not invalidate.
// Invalidating means setting expmapped entries to Inf, to trigger assertions // Invalidating means setting expmapped entries to Inf, to trigger assertions
// if we try to re-use them. // if we try to re-use them.
@ -231,9 +238,9 @@ void ISAM2<CONDITIONAL, GRAPH>::Impl::ExpmapMasked(Values& values, const Permute
const Index var = key_index->second; const Index var = key_index->second;
if(ISDEBUG("ISAM2 update verbose")) { if(ISDEBUG("ISAM2 update verbose")) {
if(mask[var]) if(mask[var])
cout << "expmap " << (string)key_value->first << " (j = " << var << "), delta = " << delta[var].transpose() << endl; cout << "expmap " << keyFormatter(key_value->first) << " (j = " << var << "), delta = " << delta[var].transpose() << endl;
else else
cout << " " << (string)key_value->first << " (j = " << var << "), delta = " << delta[var].transpose() << endl; cout << " " << keyFormatter(key_value->first) << " (j = " << var << "), delta = " << delta[var].transpose() << endl;
} }
assert(delta[var].size() == (int)key_value->second.dim()); assert(delta[var].size() == (int)key_value->second.dim());
assert(delta[var].unaryExpr(&isfinite<double>).all()); assert(delta[var].unaryExpr(&isfinite<double>).all());

View File

@ -105,7 +105,7 @@ ISAM2<CONDITIONAL, GRAPH>::relinearizeAffectedFactors(const FastList<Index>& aff
tic(3,"check candidates"); tic(3,"check candidates");
BOOST_FOREACH(size_t idx, candidates) { BOOST_FOREACH(size_t idx, candidates) {
bool inside = true; bool inside = true;
BOOST_FOREACH(const Symbol& key, nonlinearFactors_[idx]->keys()) { BOOST_FOREACH(Key key, nonlinearFactors_[idx]->keys()) {
Index var = ordering_[key]; Index var = ordering_[key];
if (affectedKeysSet.find(var) == affectedKeysSet.end()) { if (affectedKeysSet.find(var) == affectedKeysSet.end()) {
inside = false; inside = false;
@ -398,7 +398,7 @@ boost::shared_ptr<FastSet<Index> > ISAM2<CONDITIONAL, GRAPH>::recalculate(
template<class CONDITIONAL, class GRAPH> template<class CONDITIONAL, class GRAPH>
ISAM2Result ISAM2<CONDITIONAL, GRAPH>::update( ISAM2Result ISAM2<CONDITIONAL, GRAPH>::update(
const GRAPH& newFactors, const Values& newTheta, const FastVector<size_t>& removeFactorIndices, const GRAPH& newFactors, const Values& newTheta, const FastVector<size_t>& removeFactorIndices,
const boost::optional<FastSet<Symbol> >& constrainedKeys, bool force_relinearize) { const boost::optional<FastSet<Key> >& constrainedKeys, bool force_relinearize) {
static const bool debug = ISDEBUG("ISAM2 update"); static const bool debug = ISDEBUG("ISAM2 update");
static const bool verbose = ISDEBUG("ISAM2 update verbose"); static const bool verbose = ISDEBUG("ISAM2 update verbose");
@ -519,7 +519,7 @@ ISAM2Result ISAM2<CONDITIONAL, GRAPH>::update(
boost::optional<FastSet<Index> > constrainedIndices; boost::optional<FastSet<Index> > constrainedIndices;
if(constrainedKeys) { if(constrainedKeys) {
constrainedIndices.reset(FastSet<Index>()); constrainedIndices.reset(FastSet<Index>());
BOOST_FOREACH(const Symbol& key, *constrainedKeys) { BOOST_FOREACH(Key key, *constrainedKeys) {
constrainedIndices->insert(ordering_[key]); constrainedIndices->insert(ordering_[key]);
} }
} }

View File

@ -106,16 +106,19 @@ struct ISAM2Params {
bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error before and after the update, to return in ISAM2Result from update() bool evaluateNonlinearError; ///< Whether to evaluate the nonlinear error before and after the update, to return in ISAM2Result from update()
KeyFormatter keyFormatter; ///< A KeyFormatter for when keys are printed during debugging (default: DefaultKeyFormatter)
/** Specify parameters as constructor arguments */ /** Specify parameters as constructor arguments */
ISAM2Params( ISAM2Params(
OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), ///< see ISAM2Params public variables, ISAM2Params::optimizationParams OptimizationParams _optimizationParams = ISAM2GaussNewtonParams(), ///< see ISAM2Params::optimizationParams
RelinearizationThreshold _relinearizeThreshold = 0.1, ///< see ISAM2Params public variables, ISAM2Params::relinearizeThreshold RelinearizationThreshold _relinearizeThreshold = 0.1, ///< see ISAM2Params::relinearizeThreshold
int _relinearizeSkip = 10, ///< see ISAM2Params public variables, ISAM2Params::relinearizeSkip int _relinearizeSkip = 10, ///< see ISAM2Params::relinearizeSkip
bool _enableRelinearization = true, ///< see ISAM2Params public variables, ISAM2Params::enableRelinearization bool _enableRelinearization = true, ///< see ISAM2Params::enableRelinearization
bool _evaluateNonlinearError = false ///< see ISAM2Params public variables, ISAM2Params::evaluateNonlinearError bool _evaluateNonlinearError = false, ///< see ISAM2Params::evaluateNonlinearError
const KeyFormatter& _keyFormatter = DefaultKeyFormatter ///< see ISAM2::Params::keyFormatter
) : optimizationParams(_optimizationParams), relinearizeThreshold(_relinearizeThreshold), ) : optimizationParams(_optimizationParams), relinearizeThreshold(_relinearizeThreshold),
relinearizeSkip(_relinearizeSkip), enableRelinearization(_enableRelinearization), relinearizeSkip(_relinearizeSkip), enableRelinearization(_enableRelinearization),
evaluateNonlinearError(_evaluateNonlinearError) {} evaluateNonlinearError(_evaluateNonlinearError), keyFormatter(_keyFormatter) {}
}; };
/** /**
@ -369,7 +372,7 @@ public:
*/ */
ISAM2Result update(const GRAPH& newFactors = GRAPH(), const Values& newTheta = Values(), ISAM2Result update(const GRAPH& newFactors = GRAPH(), const Values& newTheta = Values(),
const FastVector<size_t>& removeFactorIndices = FastVector<size_t>(), const FastVector<size_t>& removeFactorIndices = FastVector<size_t>(),
const boost::optional<FastSet<Symbol> >& constrainedKeys = boost::none, const boost::optional<FastSet<Key> >& constrainedKeys = boost::none,
bool force_relinearize = false); bool force_relinearize = false);
/** Access the current linearization point */ /** Access the current linearization point */

34
gtsam/nonlinear/Key.cpp Normal file
View File

@ -0,0 +1,34 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Key.h
* @brief
* @author Richard Roberts
* @date Feb 20, 2012
*/
#include <gtsam/nonlinear/Key.h>
#include <boost/lexical_cast.hpp>
#include <gtsam/nonlinear/Symbol.h>
namespace gtsam {
std::string _defaultKeyFormatter(Key key) {
const Symbol asSymbol(key);
if(asSymbol.chr() > 0)
return (std::string)asSymbol;
else
return boost::lexical_cast<std::string>(key);
}
}

40
gtsam/nonlinear/Key.h Normal file
View File

@ -0,0 +1,40 @@
/* ----------------------------------------------------------------------------
* GTSAM Copyright 2010, Georgia Tech Research Corporation,
* Atlanta, Georgia 30332-0415
* All Rights Reserved
* Authors: Frank Dellaert, et al. (see THANKS for the full author list)
* See LICENSE for the license information
* -------------------------------------------------------------------------- */
/**
* @file Key.h
* @brief
* @author Richard Roberts
* @date Feb 20, 2012
*/
#pragma once
#include <boost/function.hpp>
#include <string>
namespace gtsam {
/// Integer nonlinear key type
typedef size_t Key;
/// Typedef for a function to format a key, i.e. to convert it to a string
typedef boost::function<std::string(Key)> KeyFormatter;
// Helper function for DefaultKeyFormatter
std::string _defaultKeyFormatter(Key key);
/// The default KeyFormatter, which is used if no KeyFormatter is passed to
/// a nonlinear 'print' function. Automatically detects plain integer keys
/// and Symbol keys.
static const KeyFormatter DefaultKeyFormatter = &_defaultKeyFormatter;
}

View File

@ -48,7 +48,7 @@ namespace gtsam {
* \nosubgrouping * \nosubgrouping
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality: public NonlinearFactor1<VALUE> { class NonlinearEquality: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
@ -68,7 +68,7 @@ namespace gtsam {
typedef NonlinearEquality<VALUE> This; typedef NonlinearEquality<VALUE> This;
// typedef to base class // typedef to base class
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
public: public:
@ -89,7 +89,7 @@ namespace gtsam {
/** /**
* Constructor - forces exact evaluation * Constructor - forces exact evaluation
*/ */
NonlinearEquality(const Symbol& j, const T& feasible, bool (*_compare)(const T&, const T&) = compare<T>) : NonlinearEquality(Key j, const T& feasible, bool (*_compare)(const T&, const T&) = compare<T>) :
Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible), Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible),
allow_error_(false), error_gain_(0.0), allow_error_(false), error_gain_(0.0),
compare_(_compare) { compare_(_compare) {
@ -98,7 +98,7 @@ namespace gtsam {
/** /**
* Constructor - allows inexact evaluation * Constructor - allows inexact evaluation
*/ */
NonlinearEquality(const Symbol& j, const T& feasible, double error_gain, bool (*_compare)(const T&, const T&) = compare<T>) : NonlinearEquality(Key j, const T& feasible, double error_gain, bool (*_compare)(const T&, const T&) = compare<T>) :
Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible), Base(noiseModel::Constrained::All(feasible.dim()), j), feasible_(feasible),
allow_error_(true), error_gain_(error_gain), allow_error_(true), error_gain_(error_gain),
compare_(_compare) { compare_(_compare) {
@ -108,8 +108,8 @@ namespace gtsam {
/// @name Testable /// @name Testable
/// @{ /// @{
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << "Constraint: " << s << " on [" << (std::string)(this->key()) << "]\n"; std::cout << "Constraint: " << s << " on [" << keyFormatter(this->key()) << "]\n";
gtsam::print(feasible_,"Feasible Point"); gtsam::print(feasible_,"Feasible Point");
std::cout << "Variable Dimension: " << feasible_.dim() << std::endl; std::cout << "Variable Dimension: " << feasible_.dim() << std::endl;
} }
@ -147,7 +147,7 @@ namespace gtsam {
return zero(nj); // set error to zero if equal return zero(nj); // set error to zero if equal
} else { } else {
if (H) throw std::invalid_argument( if (H) throw std::invalid_argument(
"Linearization point not feasible for " + (std::string)(this->key()) + "!"); "Linearization point not feasible for " + DefaultKeyFormatter(this->key()) + "!");
return repeat(nj, std::numeric_limits<double>::infinity()); // set error to infinity if not equal return repeat(nj, std::numeric_limits<double>::infinity()); // set error to infinity if not equal
} }
} }
@ -169,7 +169,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(feasible_); ar & BOOST_SERIALIZATION_NVP(feasible_);
ar & BOOST_SERIALIZATION_NVP(allow_error_); ar & BOOST_SERIALIZATION_NVP(allow_error_);
@ -183,13 +183,13 @@ namespace gtsam {
* Simple unary equality constraint - fixes a value for a variable * Simple unary equality constraint - fixes a value for a variable
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality1 : public NonlinearFactor1<VALUE> { class NonlinearEquality1 : public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE X; typedef VALUE X;
protected: protected:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
/** default constructor to allow for serialization */ /** default constructor to allow for serialization */
NonlinearEquality1() {} NonlinearEquality1() {}
@ -204,7 +204,7 @@ namespace gtsam {
typedef boost::shared_ptr<NonlinearEquality1<VALUE> > shared_ptr; typedef boost::shared_ptr<NonlinearEquality1<VALUE> > shared_ptr;
///TODO: comment ///TODO: comment
NonlinearEquality1(const X& value, const Symbol& key1, double mu = 1000.0) NonlinearEquality1(const X& value, Key key1, double mu = 1000.0)
: Base(noiseModel::Constrained::All(value.dim(), fabs(mu)), key1), value_(value) {} : Base(noiseModel::Constrained::All(value.dim(), fabs(mu)), key1), value_(value) {}
virtual ~NonlinearEquality1() {} virtual ~NonlinearEquality1() {}
@ -217,9 +217,9 @@ namespace gtsam {
} }
/** Print */ /** Print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << ": NonlinearEquality1(" std::cout << s << ": NonlinearEquality1("
<< (std::string) this->key() << "),"<< "\n"; << keyFormatter(this->key()) << "),"<< "\n";
this->noiseModel_->print(); this->noiseModel_->print();
value_.print("Value"); value_.print("Value");
} }
@ -230,7 +230,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(value_); ar & BOOST_SERIALIZATION_NVP(value_);
} }
@ -242,12 +242,12 @@ namespace gtsam {
* be the same. * be the same.
*/ */
template<class VALUE> template<class VALUE>
class NonlinearEquality2 : public NonlinearFactor2<VALUE, VALUE> { class NonlinearEquality2 : public NoiseModelFactor2<VALUE, VALUE> {
public: public:
typedef VALUE X; typedef VALUE X;
protected: protected:
typedef NonlinearFactor2<VALUE, VALUE> Base; typedef NoiseModelFactor2<VALUE, VALUE> Base;
GTSAM_CONCEPT_MANIFOLD_TYPE(X); GTSAM_CONCEPT_MANIFOLD_TYPE(X);
@ -259,7 +259,7 @@ namespace gtsam {
typedef boost::shared_ptr<NonlinearEquality2<VALUE> > shared_ptr; typedef boost::shared_ptr<NonlinearEquality2<VALUE> > shared_ptr;
///TODO: comment ///TODO: comment
NonlinearEquality2(const Symbol& key1, const Symbol& key2, double mu = 1000.0) NonlinearEquality2(Key key1, Key key2, double mu = 1000.0)
: Base(noiseModel::Constrained::All(X::Dim(), fabs(mu)), key1, key2) {} : Base(noiseModel::Constrained::All(X::Dim(), fabs(mu)), key1, key2) {}
virtual ~NonlinearEquality2() {} virtual ~NonlinearEquality2() {}
@ -279,7 +279,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \NonlinearEquality2 }; // \NonlinearEquality2

View File

@ -24,6 +24,7 @@
#include <limits> #include <limits>
#include <boost/serialization/base_object.hpp> #include <boost/serialization/base_object.hpp>
#include <boost/function.hpp>
#include <gtsam/inference/Factor-inl.h> #include <gtsam/inference/Factor-inl.h>
#include <gtsam/inference/IndexFactor.h> #include <gtsam/inference/IndexFactor.h>
@ -32,6 +33,7 @@
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
#include <gtsam/nonlinear/Symbol.h>
namespace gtsam { namespace gtsam {
@ -44,12 +46,12 @@ namespace gtsam {
* which are objects in non-linear manifolds (Lie groups). * which are objects in non-linear manifolds (Lie groups).
* \nosubgrouping * \nosubgrouping
*/ */
class NonlinearFactor: public Factor<Symbol> { class NonlinearFactor: public Factor<Key> {
protected: protected:
// Some handy typedefs // Some handy typedefs
typedef Factor<Symbol> Base; typedef Factor<Key> Base;
typedef NonlinearFactor This; typedef NonlinearFactor This;
public: public:
@ -77,8 +79,10 @@ public:
/// @{ /// @{
/** print */ /** print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << ": NonlinearFactor\n"; std::cout << s << "keys = { ";
BOOST_FOREACH(Key key, this->keys()) { std::cout << keyFormatter(key) << " "; }
std::cout << "}" << endl;
} }
/** Check if two factors are equal */ /** Check if two factors are equal */
@ -184,11 +188,8 @@ protected:
public: public:
/** Print */ /** Print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << ": NoiseModelFactor\n"; Base::print(s, keyFormatter);
std::cout << " ";
BOOST_FOREACH(const Symbol& key, this->keys()) { std::cout << (std::string)key << " "; }
std::cout << "\n";
this->noiseModel_->print(" noise model: "); this->noiseModel_->print(" noise model: ");
} }
@ -291,7 +292,7 @@ private:
/** A convenient base class for creating your own NoiseModelFactor with 1 /** A convenient base class for creating your own NoiseModelFactor with 1
* variable. To derive from this class, implement evaluateError(). */ * variable. To derive from this class, implement evaluateError(). */
template<class VALUE> template<class VALUE>
class NonlinearFactor1: public NoiseModelFactor { class NoiseModelFactor1: public NoiseModelFactor {
public: public:
@ -301,23 +302,23 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor1<VALUE> This; typedef NoiseModelFactor1<VALUE> This;
public: public:
/** Default constructor for I/O only */ /** Default constructor for I/O only */
NonlinearFactor1() {} NoiseModelFactor1() {}
virtual ~NonlinearFactor1() {} virtual ~NoiseModelFactor1() {}
inline const Symbol& key() const { return keys_[0]; } inline Key key() const { return keys_[0]; }
/** /**
* Constructor * Constructor
* @param z measurement * @param z measurement
* @param key by which to look up X value in Values * @param key by which to look up X value in Values
*/ */
NonlinearFactor1(const SharedNoiseModel& noiseModel, const Symbol& key1) : NoiseModelFactor1(const SharedNoiseModel& noiseModel, Key key1) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(1); keys_.resize(1);
keys_[0] = key1; keys_[0] = key1;
@ -338,12 +339,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor1(" << (std::string) keys_[0] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a unary factor. * Override this method to finish implementing a unary factor.
* If the optional Matrix reference argument is specified, it should compute * If the optional Matrix reference argument is specified, it should compute
@ -361,14 +356,14 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
};// \class NonlinearFactor1 };// \class NoiseModelFactor1
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 2 /** A convenient base class for creating your own NoiseModelFactor with 2
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2> template<class VALUE1, class VALUE2>
class NonlinearFactor2: public NoiseModelFactor { class NoiseModelFactor2: public NoiseModelFactor {
public: public:
@ -379,32 +374,32 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor2<VALUE1, VALUE2> This; typedef NoiseModelFactor2<VALUE1, VALUE2> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor2() {} NoiseModelFactor2() {}
/** /**
* Constructor * Constructor
* @param j1 key of the first variable * @param j1 key of the first variable
* @param j2 key of the second variable * @param j2 key of the second variable
*/ */
NonlinearFactor2(const SharedNoiseModel& noiseModel, const Symbol& j1, const Symbol& j2) : NoiseModelFactor2(const SharedNoiseModel& noiseModel, Key j1, Key j2) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(2); keys_.resize(2);
keys_[0] = j1; keys_[0] = j1;
keys_[1] = j2; keys_[1] = j2;
} }
virtual ~NonlinearFactor2() {} virtual ~NoiseModelFactor2() {}
/** methods to retrieve both keys */ /** methods to retrieve both keys */
inline const Symbol& key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
inline const Symbol& key2() const { return keys_[1]; } inline Key key2() const { return keys_[1]; }
/** Calls the 2-key specific version of evaluateError, which is pure virtual /** Calls the 2-key specific version of evaluateError, which is pure virtual
* so must be implemented in the derived class. */ * so must be implemented in the derived class. */
@ -422,14 +417,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor2("
<< (std::string) keys_[0] << ","
<< (std::string) keys_[1] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a binary factor. * Override this method to finish implementing a binary factor.
* If any of the optional Matrix reference arguments are specified, it should compute * If any of the optional Matrix reference arguments are specified, it should compute
@ -448,13 +435,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor2 }; // \class NoiseModelFactor2
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 3 /** A convenient base class for creating your own NoiseModelFactor with 3
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3> template<class VALUE1, class VALUE2, class VALUE3>
class NonlinearFactor3: public NoiseModelFactor { class NoiseModelFactor3: public NoiseModelFactor {
public: public:
@ -466,14 +453,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor3<VALUE1, VALUE2, VALUE3> This; typedef NoiseModelFactor3<VALUE1, VALUE2, VALUE3> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor3() {} NoiseModelFactor3() {}
/** /**
* Constructor * Constructor
@ -481,7 +468,7 @@ public:
* @param j2 key of the second variable * @param j2 key of the second variable
* @param j3 key of the third variable * @param j3 key of the third variable
*/ */
NonlinearFactor3(const SharedNoiseModel& noiseModel, const Symbol& j1, const Symbol& j2, const Symbol& j3) : NoiseModelFactor3(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(3); keys_.resize(3);
keys_[0] = j1; keys_[0] = j1;
@ -489,12 +476,12 @@ public:
keys_[2] = j3; keys_[2] = j3;
} }
virtual ~NonlinearFactor3() {} virtual ~NoiseModelFactor3() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline const Symbol& key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
inline const Symbol& key2() const { return keys_[1]; } inline Key key2() const { return keys_[1]; }
inline const Symbol& key3() const { return keys_[2]; } inline Key key3() const { return keys_[2]; }
/** Calls the 3-key specific version of evaluateError, which is pure virtual /** Calls the 3-key specific version of evaluateError, which is pure virtual
* so must be implemented in the derived class. */ * so must be implemented in the derived class. */
@ -509,16 +496,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor3("
<< (std::string) this->keys_[0] << ","
<< (std::string) this->keys_[1] << ","
<< (std::string) this->keys_[2] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a trinary factor. * Override this method to finish implementing a trinary factor.
* If any of the optional Matrix reference arguments are specified, it should compute * If any of the optional Matrix reference arguments are specified, it should compute
@ -539,13 +516,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor3 }; // \class NoiseModelFactor3
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 4 /** A convenient base class for creating your own NoiseModelFactor with 4
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4>
class NonlinearFactor4: public NoiseModelFactor { class NoiseModelFactor4: public NoiseModelFactor {
public: public:
@ -558,14 +535,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor4<VALUE1, VALUE2, VALUE3, VALUE4> This; typedef NoiseModelFactor4<VALUE1, VALUE2, VALUE3, VALUE4> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor4() {} NoiseModelFactor4() {}
/** /**
* Constructor * Constructor
@ -574,7 +551,7 @@ public:
* @param j3 key of the third variable * @param j3 key of the third variable
* @param j4 key of the fourth variable * @param j4 key of the fourth variable
*/ */
NonlinearFactor4(const SharedNoiseModel& noiseModel, const Symbol& j1, const Symbol& j2, const Symbol& j3, const Symbol& j4) : NoiseModelFactor4(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(4); keys_.resize(4);
keys_[0] = j1; keys_[0] = j1;
@ -583,13 +560,13 @@ public:
keys_[3] = j4; keys_[3] = j4;
} }
virtual ~NonlinearFactor4() {} virtual ~NoiseModelFactor4() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline const Symbol& key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
inline const Symbol& key2() const { return keys_[1]; } inline Key key2() const { return keys_[1]; }
inline const Symbol& key3() const { return keys_[2]; } inline Key key3() const { return keys_[2]; }
inline const Symbol& key4() const { return keys_[3]; } inline Key key4() const { return keys_[3]; }
/** Calls the 4-key specific version of evaluateError, which is pure virtual /** Calls the 4-key specific version of evaluateError, which is pure virtual
* so must be implemented in the derived class. */ * so must be implemented in the derived class. */
@ -604,16 +581,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor4("
<< (std::string) this->keys_[0] << ","
<< (std::string) this->keys_[1] << ","
<< (std::string) this->keys_[2] << ","
<< (std::string) this->keys_[3] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a 4-way factor. * Override this method to finish implementing a 4-way factor.
* If any of the optional Matrix reference arguments are specified, it should compute * If any of the optional Matrix reference arguments are specified, it should compute
@ -635,13 +602,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor4 }; // \class NoiseModelFactor4
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 5 /** A convenient base class for creating your own NoiseModelFactor with 5
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5>
class NonlinearFactor5: public NoiseModelFactor { class NoiseModelFactor5: public NoiseModelFactor {
public: public:
@ -655,14 +622,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor5<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5> This; typedef NoiseModelFactor5<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor5() {} NoiseModelFactor5() {}
/** /**
* Constructor * Constructor
@ -672,7 +639,7 @@ public:
* @param j4 key of the fourth variable * @param j4 key of the fourth variable
* @param j5 key of the fifth variable * @param j5 key of the fifth variable
*/ */
NonlinearFactor5(const SharedNoiseModel& noiseModel, const Symbol& j1, const Symbol& j2, const Symbol& j3, const Symbol& j4, const Symbol& j5) : NoiseModelFactor5(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(5); keys_.resize(5);
keys_[0] = j1; keys_[0] = j1;
@ -682,14 +649,14 @@ public:
keys_[4] = j5; keys_[4] = j5;
} }
virtual ~NonlinearFactor5() {} virtual ~NoiseModelFactor5() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline const Symbol& key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
inline const Symbol& key2() const { return keys_[1]; } inline Key key2() const { return keys_[1]; }
inline const Symbol& key3() const { return keys_[2]; } inline Key key3() const { return keys_[2]; }
inline const Symbol& key4() const { return keys_[3]; } inline Key key4() const { return keys_[3]; }
inline const Symbol& key5() const { return keys_[4]; } inline Key key5() const { return keys_[4]; }
/** Calls the 5-key specific version of evaluateError, which is pure virtual /** Calls the 5-key specific version of evaluateError, which is pure virtual
* so must be implemented in the derived class. */ * so must be implemented in the derived class. */
@ -704,17 +671,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor5("
<< (std::string) this->keys_[0] << ","
<< (std::string) this->keys_[1] << ","
<< (std::string) this->keys_[2] << ","
<< (std::string) this->keys_[3] << ","
<< (std::string) this->keys_[4] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a 5-way factor. * Override this method to finish implementing a 5-way factor.
* If any of the optional Matrix reference arguments are specified, it should compute * If any of the optional Matrix reference arguments are specified, it should compute
@ -737,13 +693,13 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor5 }; // \class NoiseModelFactor5
/* ************************************************************************* */ /* ************************************************************************* */
/** A convenient base class for creating your own NoiseModelFactor with 6 /** A convenient base class for creating your own NoiseModelFactor with 6
* variables. To derive from this class, implement evaluateError(). */ * variables. To derive from this class, implement evaluateError(). */
template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6> template<class VALUE1, class VALUE2, class VALUE3, class VALUE4, class VALUE5, class VALUE6>
class NonlinearFactor6: public NoiseModelFactor { class NoiseModelFactor6: public NoiseModelFactor {
public: public:
@ -758,14 +714,14 @@ public:
protected: protected:
typedef NoiseModelFactor Base; typedef NoiseModelFactor Base;
typedef NonlinearFactor6<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6> This; typedef NoiseModelFactor6<VALUE1, VALUE2, VALUE3, VALUE4, VALUE5, VALUE6> This;
public: public:
/** /**
* Default Constructor for I/O * Default Constructor for I/O
*/ */
NonlinearFactor6() {} NoiseModelFactor6() {}
/** /**
* Constructor * Constructor
@ -776,7 +732,7 @@ public:
* @param j5 key of the fifth variable * @param j5 key of the fifth variable
* @param j6 key of the fifth variable * @param j6 key of the fifth variable
*/ */
NonlinearFactor6(const SharedNoiseModel& noiseModel, const Symbol& j1, const Symbol& j2, const Symbol& j3, const Symbol& j4, const Symbol& j5, const Symbol& j6) : NoiseModelFactor6(const SharedNoiseModel& noiseModel, Key j1, Key j2, Key j3, Key j4, Key j5, Key j6) :
Base(noiseModel) { Base(noiseModel) {
keys_.resize(6); keys_.resize(6);
keys_[0] = j1; keys_[0] = j1;
@ -787,15 +743,15 @@ public:
keys_[5] = j6; keys_[5] = j6;
} }
virtual ~NonlinearFactor6() {} virtual ~NoiseModelFactor6() {}
/** methods to retrieve keys */ /** methods to retrieve keys */
inline const Symbol& key1() const { return keys_[0]; } inline Key key1() const { return keys_[0]; }
inline const Symbol& key2() const { return keys_[1]; } inline Key key2() const { return keys_[1]; }
inline const Symbol& key3() const { return keys_[2]; } inline Key key3() const { return keys_[2]; }
inline const Symbol& key4() const { return keys_[3]; } inline Key key4() const { return keys_[3]; }
inline const Symbol& key5() const { return keys_[4]; } inline Key key5() const { return keys_[4]; }
inline const Symbol& key6() const { return keys_[5]; } inline Key key6() const { return keys_[5]; }
/** Calls the 6-key specific version of evaluateError, which is pure virtual /** Calls the 6-key specific version of evaluateError, which is pure virtual
* so must be implemented in the derived class. */ * so must be implemented in the derived class. */
@ -810,18 +766,6 @@ public:
} }
} }
/** Print */
virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearFactor6("
<< (std::string) this->keys_[0] << ","
<< (std::string) this->keys_[1] << ","
<< (std::string) this->keys_[2] << ","
<< (std::string) this->keys_[3] << ","
<< (std::string) this->keys_[4] << ","
<< (std::string) this->keys_[5] << ")\n";
this->noiseModel_->print(" noise model: ");
}
/** /**
* Override this method to finish implementing a 6-way factor. * Override this method to finish implementing a 6-way factor.
* If any of the optional Matrix reference arguments are specified, it should compute * If any of the optional Matrix reference arguments are specified, it should compute
@ -845,7 +789,7 @@ private:
ar & boost::serialization::make_nvp("NoiseModelFactor", ar & boost::serialization::make_nvp("NoiseModelFactor",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
} }
}; // \class NonlinearFactor6 }; // \class NoiseModelFactor6
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -33,8 +33,13 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void NonlinearFactorGraph::print(const std::string& str) const { void NonlinearFactorGraph::print(const std::string& str, const KeyFormatter& keyFormatter) const {
Base::print(str); cout << str << "size: " << size() << endl;
for (size_t i = 0; i < factors_.size(); i++) {
stringstream ss;
ss << "factor " << i << ": ";
if (factors_[i] != NULL) factors_[i]->print(ss.str(), keyFormatter);
}
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -49,8 +54,8 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
std::set<Symbol> NonlinearFactorGraph::keys() const { std::set<Key> NonlinearFactorGraph::keys() const {
std::set<Symbol> keys; std::set<Key> keys;
BOOST_FOREACH(const sharedFactor& factor, this->factors_) { BOOST_FOREACH(const sharedFactor& factor, this->factors_) {
if(factor) if(factor)
keys.insert(factor->begin(), factor->end()); keys.insert(factor->begin(), factor->end());

View File

@ -44,10 +44,10 @@ namespace gtsam {
typedef boost::shared_ptr<NonlinearFactor> sharedFactor; typedef boost::shared_ptr<NonlinearFactor> sharedFactor;
/** print just calls base class */ /** print just calls base class */
void print(const std::string& str = "NonlinearFactorGraph: ") const; void print(const std::string& str = "NonlinearFactorGraph: ", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/** return keys in some random order */ /** return keys in some random order */
std::set<Symbol> keys() const; std::set<Key> keys() const;
/** unnormalized error */ /** unnormalized error */
double error(const Values& c) const; double error(const Values& c) const;

View File

@ -50,7 +50,7 @@ void NonlinearISAM<GRAPH>::update(const Factors& newFactors,
// Augment ordering // Augment ordering
// FIXME: should just loop over new values // FIXME: should just loop over new values
BOOST_FOREACH(const typename Factors::sharedFactor& factor, newFactors) BOOST_FOREACH(const typename Factors::sharedFactor& factor, newFactors)
BOOST_FOREACH(const Symbol& key, factor->keys()) BOOST_FOREACH(Key key, factor->keys())
ordering_.tryInsert(key, ordering_.nVars()); // will do nothing if already present ordering_.tryInsert(key, ordering_.nVars()); // will do nothing if already present
boost::shared_ptr<GaussianFactorGraph> linearizedNewFactors( boost::shared_ptr<GaussianFactorGraph> linearizedNewFactors(
@ -99,7 +99,7 @@ Values NonlinearISAM<GRAPH>::estimate() const {
/* ************************************************************************* */ /* ************************************************************************* */
template<class GRAPH> template<class GRAPH>
Matrix NonlinearISAM<GRAPH>::marginalCovariance(const Symbol& key) const { Matrix NonlinearISAM<GRAPH>::marginalCovariance(Key key) const {
return isam_.marginalCovariance(ordering_[key]); return isam_.marginalCovariance(ordering_[key]);
} }

View File

@ -70,7 +70,7 @@ public:
Values estimate() const; Values estimate() const;
/** find the marginal covariance for a single variable */ /** find the marginal covariance for a single variable */
Matrix marginalCovariance(const Symbol& key) const; Matrix marginalCovariance(Key key) const;
// access // access
@ -104,7 +104,7 @@ public:
void reorder_relinearize(); void reorder_relinearize();
/** manually add a key to the end of the ordering */ /** manually add a key to the end of the ordering */
void addKey(const Symbol& key) { ordering_.push_back(key); } void addKey(Key key) { ordering_.push_back(key); }
/** replace the current ordering */ /** replace the current ordering */
void setOrdering(const Ordering& new_ordering) { ordering_ = new_ordering; } void setOrdering(const Ordering& new_ordering) { ordering_ = new_ordering; }

View File

@ -242,7 +242,7 @@ public:
/** /**
* Return mean and covariance on a single variable * Return mean and covariance on a single variable
*/ */
Matrix marginalCovariance(Symbol j) const { Matrix marginalCovariance(Key j) const {
return createSolver()->marginalCovariance((*ordering_)[j]); return createSolver()->marginalCovariance((*ordering_)[j]);
} }

View File

@ -26,9 +26,9 @@ using namespace std;
namespace gtsam { namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
Ordering::Ordering(const std::list<Symbol> & L):nVars_(0) { Ordering::Ordering(const std::list<Key> & L):nVars_(0) {
int i = 0; int i = 0;
BOOST_FOREACH( const Symbol& s, L ) BOOST_FOREACH( Key s, L )
insert(s, i++) ; insert(s, i++) ;
} }
@ -40,12 +40,12 @@ void Ordering::permuteWithInverse(const Permutation& inversePermutation) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Ordering::print(const string& str) const { void Ordering::print(const string& str, const KeyFormatter& keyFormatter) const {
cout << str << " "; cout << str << " ";
BOOST_FOREACH(const Ordering::value_type& key_order, *this) { BOOST_FOREACH(const Ordering::value_type& key_order, *this) {
if(key_order != *begin()) if(key_order != *begin())
cout << ", "; cout << ", ";
cout << (string)key_order.first << ":" << key_order.second; cout << keyFormatter(key_order.first) << ":" << key_order.second;
} }
cout << endl; cout << endl;
} }
@ -70,7 +70,7 @@ Ordering::value_type Ordering::pop_back() {
} }
/* ************************************************************************* */ /* ************************************************************************* */
Index Ordering::pop_back(const Symbol& key) { Index Ordering::pop_back(Key key) {
Map::iterator item = order_.find(key); Map::iterator item = order_.find(key);
if(item == order_.end()) { if(item == order_.end()) {
throw invalid_argument("Attempting to remove a key from an ordering that does not contain that key"); throw invalid_argument("Attempting to remove a key from an ordering that does not contain that key");

View File

@ -17,10 +17,10 @@
#pragma once #pragma once
#include <map>
#include <set> #include <set>
#include <gtsam/nonlinear/Symbol.h> #include <gtsam/base/FastMap.h>
#include <gtsam/inference/inference.h> #include <gtsam/inference/inference.h>
#include <gtsam/nonlinear/Symbol.h>
#include <boost/foreach.hpp> #include <boost/foreach.hpp>
#include <boost/assign/list_inserter.hpp> #include <boost/assign/list_inserter.hpp>
@ -34,8 +34,7 @@ namespace gtsam {
*/ */
class Ordering { class Ordering {
protected: protected:
typedef boost::fast_pool_allocator<std::pair<const Symbol, Index> > Allocator; typedef FastMap<Key, Index> Map;
typedef std::map<Symbol, Index, std::less<Symbol>, Allocator> Map;
Map order_; Map order_;
Index nVars_; Index nVars_;
@ -43,7 +42,7 @@ public:
typedef boost::shared_ptr<Ordering> shared_ptr; typedef boost::shared_ptr<Ordering> shared_ptr;
typedef std::pair<const Symbol, Index> value_type; typedef std::pair<const Key, Index> value_type;
typedef Map::iterator iterator; typedef Map::iterator iterator;
typedef Map::const_iterator const_iterator; typedef Map::const_iterator const_iterator;
@ -54,7 +53,7 @@ public:
Ordering() : nVars_(0) {} Ordering() : nVars_(0) {}
/// Construct from list, assigns order indices sequentially to list items. /// Construct from list, assigns order indices sequentially to list items.
Ordering(const std::list<Symbol> & L) ; Ordering(const std::list<Key> & L) ;
/// @} /// @}
/// @name Standard Interface /// @name Standard Interface
@ -69,7 +68,7 @@ public:
const_iterator begin() const { return order_.begin(); } /**< Iterator in order of sorted symbols, not in elimination/index order! */ const_iterator begin() const { return order_.begin(); } /**< Iterator in order of sorted symbols, not in elimination/index order! */
const_iterator end() const { return order_.end(); } /**< Iterator in order of sorted symbols, not in elimination/index order! */ const_iterator end() const { return order_.end(); } /**< Iterator in order of sorted symbols, not in elimination/index order! */
Index at(const Symbol& key) const { return operator[](key); } ///< Synonym for operator[](const Symbol&) const Index at(Key key) const { return operator[](key); } ///< Synonym for operator[](Key) const
/** Assigns the ordering index of the requested \c key into \c index if the symbol /** Assigns the ordering index of the requested \c key into \c index if the symbol
* is present in the ordering, otherwise does not modify \c index. The * is present in the ordering, otherwise does not modify \c index. The
@ -79,7 +78,7 @@ public:
* @param [out] index Reference into which to write the index of the requested key, if the key is present. * @param [out] index Reference into which to write the index of the requested key, if the key is present.
* @return true if the key is present and \c index was modified, false otherwise. * @return true if the key is present and \c index was modified, false otherwise.
*/ */
bool tryAt(const Symbol& key, Index& index) const { bool tryAt(Key key, Index& index) const {
const_iterator i = order_.find(key); const_iterator i = order_.find(key);
if(i != order_.end()) { if(i != order_.end()) {
index = i->second; index = i->second;
@ -91,7 +90,7 @@ public:
/// Access the index for the requested key, throws std::out_of_range if the /// Access the index for the requested key, throws std::out_of_range if the
/// key is not present in the ordering (note that this differs from the /// key is not present in the ordering (note that this differs from the
/// behavior of std::map) /// behavior of std::map)
Index& operator[](const Symbol& key) { Index& operator[](Key key) {
iterator i=order_.find(key); iterator i=order_.find(key);
if(i == order_.end()) throw std::out_of_range(std::string()); if(i == order_.end()) throw std::out_of_range(std::string());
else return i->second; } else return i->second; }
@ -99,7 +98,7 @@ public:
/// Access the index for the requested key, throws std::out_of_range if the /// Access the index for the requested key, throws std::out_of_range if the
/// key is not present in the ordering (note that this differs from the /// key is not present in the ordering (note that this differs from the
/// behavior of std::map) /// behavior of std::map)
Index operator[](const Symbol& key) const { Index operator[](Key key) const {
const_iterator i=order_.find(key); const_iterator i=order_.find(key);
if(i == order_.end()) throw std::out_of_range(std::string()); if(i == order_.end()) throw std::out_of_range(std::string());
else return i->second; } else return i->second; }
@ -110,7 +109,7 @@ public:
* @return An iterator pointing to the symbol/index pair with the requested, * @return An iterator pointing to the symbol/index pair with the requested,
* or the end iterator if it does not exist. * or the end iterator if it does not exist.
*/ */
iterator find(const Symbol& key) { return order_.find(key); } iterator find(Key key) { return order_.find(key); }
/** Returns an iterator pointing to the symbol/index pair with the requested, /** Returns an iterator pointing to the symbol/index pair with the requested,
* or the end iterator if it does not exist. * or the end iterator if it does not exist.
@ -118,7 +117,7 @@ public:
* @return An iterator pointing to the symbol/index pair with the requested, * @return An iterator pointing to the symbol/index pair with the requested,
* or the end iterator if it does not exist. * or the end iterator if it does not exist.
*/ */
const_iterator find(const Symbol& key) const { return order_.find(key); } const_iterator find(Key key) const { return order_.find(key); }
/** /**
* Attempts to insert a symbol/order pair with same semantics as stl::Map::insert(), * Attempts to insert a symbol/order pair with same semantics as stl::Map::insert(),
@ -153,22 +152,22 @@ public:
iterator end() { return order_.end(); } iterator end() { return order_.end(); }
/// Test if the key exists in the ordering. /// Test if the key exists in the ordering.
bool exists(const Symbol& key) const { return order_.count(key); } bool exists(Key key) const { return order_.count(key); }
///TODO: comment ///TODO: comment
std::pair<iterator,bool> tryInsert(const Symbol& key, Index order) { return tryInsert(std::make_pair(key,order)); } std::pair<iterator,bool> tryInsert(Key key, Index order) { return tryInsert(std::make_pair(key,order)); }
///TODO: comment ///TODO: comment
iterator insert(const Symbol& key, Index order) { return insert(std::make_pair(key,order)); } iterator insert(Key key, Index order) { return insert(std::make_pair(key,order)); }
/// Adds a new key to the ordering with an index of one greater than the current highest index. /// Adds a new key to the ordering with an index of one greater than the current highest index.
Index push_back(const Symbol& key) { return insert(std::make_pair(key, nVars_))->second; } Index push_back(Key key) { return insert(std::make_pair(key, nVars_))->second; }
/** Remove the last (last-ordered, not highest-sorting key) symbol/index pair /** Remove the last (last-ordered, not highest-sorting key) symbol/index pair
* from the ordering (this version is \f$ O(n) \f$, use it when you do not * from the ordering (this version is \f$ O(n) \f$, use it when you do not
* know the last-ordered key). * know the last-ordered key).
* *
* If you already know the last-ordered symbol, call popback(const Symbol&) * If you already know the last-ordered symbol, call popback(Key)
* that accepts this symbol as an argument. * that accepts this symbol as an argument.
* *
* @return The symbol and index that were removed. * @return The symbol and index that were removed.
@ -183,15 +182,15 @@ public:
* *
* @return The index of the symbol that was removed. * @return The index of the symbol that was removed.
*/ */
Index pop_back(const Symbol& key); Index pop_back(Key key);
/** /**
* += operator allows statements like 'ordering += x0,x1,x2,x3;', which are * += operator allows statements like 'ordering += x0,x1,x2,x3;', which are
* very useful for unit tests. This functionality is courtesy of * very useful for unit tests. This functionality is courtesy of
* boost::assign. * boost::assign.
*/ */
inline boost::assign::list_inserter<boost::assign_detail::call_push_back<Ordering>, Symbol> inline boost::assign::list_inserter<boost::assign_detail::call_push_back<Ordering>, Key>
operator+=(const Symbol& key) { operator+=(Key key) {
return boost::assign::make_list_inserter(boost::assign_detail::call_push_back<Ordering>(*this))(key); } return boost::assign::make_list_inserter(boost::assign_detail::call_push_back<Ordering>(*this))(key); }
/** /**
@ -201,15 +200,15 @@ public:
*/ */
void permuteWithInverse(const Permutation& inversePermutation); void permuteWithInverse(const Permutation& inversePermutation);
/// Synonym for operator[](const Symbol&) /// Synonym for operator[](Key)
Index& at(const Symbol& key) { return operator[](key); } Index& at(Key key) { return operator[](key); }
/// @} /// @}
/// @name Testable /// @name Testable
/// @{ /// @{
/** print (from Testable) for testing and debugging */ /** print (from Testable) for testing and debugging */
void print(const std::string& str = "Ordering:") const; void print(const std::string& str = "Ordering:", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/** equals (from Testable) for testing and debugging */ /** equals (from Testable) for testing and debugging */
bool equals(const Ordering& rhs, double tol = 0.0) const; bool equals(const Ordering& rhs, double tol = 0.0) const;

View File

@ -27,6 +27,8 @@
#include <boost/lexical_cast.hpp> #include <boost/lexical_cast.hpp>
#endif #endif
#include <gtsam/nonlinear/Key.h>
#define ALPHA '\224' #define ALPHA '\224'
namespace gtsam { namespace gtsam {
@ -87,6 +89,30 @@ public:
} }
#endif #endif
/** Constructor that decodes an integer Key */
Symbol(Key key) {
const size_t keyBytes = sizeof(Key);
const size_t chrBytes = sizeof(unsigned char);
const size_t indexBytes = keyBytes - chrBytes;
const Key chrMask = std::numeric_limits<unsigned char>::max() << indexBytes;
const Key indexMask = ~chrMask;
c_ = (key & chrMask) >> indexBytes;
j_ = key & indexMask;
}
/** Cast to integer */
operator Key() const {
const size_t keyBytes = sizeof(Key);
const size_t chrBytes = sizeof(unsigned char);
const size_t indexBytes = keyBytes - chrBytes;
const Key chrMask = std::numeric_limits<unsigned char>::max() << indexBytes;
const Key indexMask = ~chrMask;
if(j_ > indexMask)
throw std::invalid_argument("Symbol index is too large");
Key key = (c_ << indexBytes) | j_;
return key;
}
// Testable Requirements // Testable Requirements
void print(const std::string& s = "") const { void print(const std::string& s = "") const {
std::cout << s << ": " << (std::string) (*this) << std::endl; std::cout << s << ": " << (std::string) (*this) << std::endl;

View File

@ -43,11 +43,11 @@ namespace gtsam {
#if 0 #if 0
/* ************************************************************************* */ /* ************************************************************************* */
class ValueAutomaticCasting { class ValueAutomaticCasting {
const Symbol& key_; Key key_;
const Value& value_; const Value& value_;
public: public:
ValueAutomaticCasting(const Symbol& key, const Value& value) : key_(key), value_(value) {} ValueAutomaticCasting(Key key, const Value& value) : key_(key), value_(value) {}
template<class ValueType> template<class ValueType>
class ConvertibleToValue : public ValueType { class ConvertibleToValue : public ValueType {
@ -67,7 +67,7 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
template<typename ValueType> template<typename ValueType>
const ValueType& Values::at(const Symbol& j) const { const ValueType& Values::at(Key j) const {
// Find the item // Find the item
KeyValueMap::const_iterator item = values_.find(j); KeyValueMap::const_iterator item = values_.find(j);
@ -85,7 +85,7 @@ namespace gtsam {
#if 0 #if 0
/* ************************************************************************* */ /* ************************************************************************* */
inline ValueAutomaticCasting Values::at(const Symbol& j) const { inline ValueAutomaticCasting Values::at(Key j) const {
// Find the item // Find the item
KeyValueMap::const_iterator item = values_.find(j); KeyValueMap::const_iterator item = values_.find(j);
@ -97,26 +97,16 @@ namespace gtsam {
} }
#endif #endif
/* ************************************************************************* */
template<typename TypedKey>
const typename TypedKey::Value& Values::at(const TypedKey& j) const {
// Convert to Symbol
const Symbol symbol(j.symbol());
// Call at with the Value type from the key
return at<typename TypedKey::Value>(symbol);
}
#if 0 #if 0
/* ************************************************************************* */ /* ************************************************************************* */
inline ValueAutomaticCasting Values::operator[](const Symbol& j) const { inline ValueAutomaticCasting Values::operator[](Key j) const {
return at(j); return at(j);
} }
#endif #endif
/* ************************************************************************* */ /* ************************************************************************* */
template<typename ValueType> template<typename ValueType>
boost::optional<const ValueType&> Values::exists(const Symbol& j) const { boost::optional<const ValueType&> Values::exists(Key j) const {
// Find the item // Find the item
KeyValueMap::const_iterator item = values_.find(j); KeyValueMap::const_iterator item = values_.find(j);
@ -132,14 +122,4 @@ namespace gtsam {
} }
} }
/* ************************************************************************* */
template<class TypedKey>
boost::optional<const typename TypedKey::Value&> Values::exists(const TypedKey& j) const {
// Convert to Symbol
const Symbol symbol(j.symbol());
// Call exists with the Value type from the key
return exists<typename TypedKey::Value>(symbol);
}
} }

View File

@ -40,10 +40,10 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Values::print(const string& str) const { void Values::print(const string& str, const KeyFormatter& keyFormatter) const {
cout << str << "Values with " << size() << " values:\n" << endl; cout << str << "Values with " << size() << " values:\n" << endl;
for(const_iterator key_value = begin(); key_value != end(); ++key_value) { for(const_iterator key_value = begin(); key_value != end(); ++key_value) {
cout << " " << (string)key_value->first << ": "; cout << " " << keyFormatter(key_value->first) << ": ";
key_value->second.print(""); key_value->second.print("");
} }
} }
@ -64,7 +64,7 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
bool Values::exists(const Symbol& j) const { bool Values::exists(Key j) const {
return values_.find(j) != values_.end(); return values_.find(j) != values_.end();
} }
@ -79,7 +79,7 @@ namespace gtsam {
for(const_iterator key_value = begin(); key_value != end(); ++key_value) { for(const_iterator key_value = begin(); key_value != end(); ++key_value) {
const SubVector& singleDelta = delta[ordering[key_value->first]]; // Delta for this value const SubVector& singleDelta = delta[ordering[key_value->first]]; // Delta for this value
Symbol key = key_value->first; // Non-const duplicate to deal with non-const insert argument Key key = key_value->first; // Non-const duplicate to deal with non-const insert argument
Value* retractedValue(key_value->second.retract_(singleDelta)); // Retract Value* retractedValue(key_value->second.retract_(singleDelta)); // Retract
result.values_.insert(key, retractedValue); // Add retracted result directly to result values result.values_.insert(key, retractedValue); // Add retracted result directly to result values
} }
@ -107,8 +107,8 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Values::insert(const Symbol& j, const Value& val) { void Values::insert(Key j, const Value& val) {
Symbol key = j; // Non-const duplicate to deal with non-const insert argument Key key = j; // Non-const duplicate to deal with non-const insert argument
std::pair<iterator,bool> insertResult = values_.insert(key, val.clone_()); std::pair<iterator,bool> insertResult = values_.insert(key, val.clone_());
if(!insertResult.second) if(!insertResult.second)
throw ValuesKeyAlreadyExists(j); throw ValuesKeyAlreadyExists(j);
@ -117,13 +117,13 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
void Values::insert(const Values& values) { void Values::insert(const Values& values) {
for(const_iterator key_value = values.begin(); key_value != values.end(); ++key_value) { for(const_iterator key_value = values.begin(); key_value != values.end(); ++key_value) {
Symbol key = key_value->first; // Non-const duplicate to deal with non-const insert argument Key key = key_value->first; // Non-const duplicate to deal with non-const insert argument
insert(key, key_value->second); insert(key, key_value->second);
} }
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Values::update(const Symbol& j, const Value& val) { void Values::update(Key j, const Value& val) {
// Find the value to update // Find the value to update
KeyValueMap::iterator item = values_.find(j); KeyValueMap::iterator item = values_.find(j);
if(item == values_.end()) if(item == values_.end())
@ -144,7 +144,7 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
void Values::erase(const Symbol& j) { void Values::erase(Key j) {
KeyValueMap::iterator item = values_.find(j); KeyValueMap::iterator item = values_.find(j);
if(item == values_.end()) if(item == values_.end())
throw ValuesKeyDoesNotExist("erase", j); throw ValuesKeyDoesNotExist("erase", j);
@ -152,8 +152,8 @@ namespace gtsam {
} }
/* ************************************************************************* */ /* ************************************************************************* */
FastList<Symbol> Values::keys() const { FastList<Key> Values::keys() const {
FastList<Symbol> result; FastList<Key> result;
for(const_iterator key_value = begin(); key_value != end(); ++key_value) for(const_iterator key_value = begin(); key_value != end(); ++key_value)
result.push_back(key_value->first); result.push_back(key_value->first);
return result; return result;
@ -197,7 +197,7 @@ namespace gtsam {
const char* ValuesKeyAlreadyExists::what() const throw() { const char* ValuesKeyAlreadyExists::what() const throw() {
if(message_.empty()) if(message_.empty())
message_ = message_ =
"Attempting to add a key-value pair with key \"" + (std::string)key_ + "\", key already exists."; "Attempting to add a key-value pair with key \"" + DefaultKeyFormatter(key_) + "\", key already exists.";
return message_.c_str(); return message_.c_str();
} }
@ -206,7 +206,7 @@ namespace gtsam {
if(message_.empty()) if(message_.empty())
message_ = message_ =
"Attempting to " + std::string(operation_) + " the key \"" + "Attempting to " + std::string(operation_) + " the key \"" +
(std::string)key_ + "\", which does not exist in the Values."; DefaultKeyFormatter(key_) + "\", which does not exist in the Values.";
return message_.c_str(); return message_.c_str();
} }
@ -214,7 +214,7 @@ namespace gtsam {
const char* ValuesIncorrectType::what() const throw() { const char* ValuesIncorrectType::what() const throw() {
if(message_.empty()) if(message_.empty())
message_ = message_ =
"Attempting to retrieve value with key \"" + (std::string)key_ + "\", type stored in Values is " + "Attempting to retrieve value with key \"" + DefaultKeyFormatter(key_) + "\", type stored in Values is " +
std::string(storedTypeId_.name()) + " but requested type was " + std::string(requestedTypeId_.name()); std::string(storedTypeId_.name()) + " but requested type was " + std::string(requestedTypeId_.name());
return message_.c_str(); return message_.c_str();
} }

View File

@ -37,7 +37,6 @@
#include <gtsam/base/Value.h> #include <gtsam/base/Value.h>
#include <gtsam/base/FastMap.h> #include <gtsam/base/FastMap.h>
#include <gtsam/linear/VectorValues.h> #include <gtsam/linear/VectorValues.h>
#include <gtsam/nonlinear/Symbol.h>
#include <gtsam/nonlinear/Ordering.h> #include <gtsam/nonlinear/Ordering.h>
namespace gtsam { namespace gtsam {
@ -64,11 +63,11 @@ namespace gtsam {
// fast_pool_allocator to allocate map nodes. In this way, all memory is // fast_pool_allocator to allocate map nodes. In this way, all memory is
// allocated in a boost memory pool. // allocated in a boost memory pool.
typedef boost::ptr_map< typedef boost::ptr_map<
Symbol, Key,
Value, Value,
std::less<Symbol>, std::less<Key>,
ValueCloneAllocator, ValueCloneAllocator,
boost::fast_pool_allocator<std::pair<const Symbol, void*> > > KeyValueMap; boost::fast_pool_allocator<std::pair<const Key, void*> > > KeyValueMap;
// The member to store the values, see just above // The member to store the values, see just above
KeyValueMap values_; KeyValueMap values_;
@ -84,16 +83,16 @@ namespace gtsam {
/// A pair of const references to the key and value, the dereferenced type of the const_iterator and const_reverse_iterator /// A pair of const references to the key and value, the dereferenced type of the const_iterator and const_reverse_iterator
struct ConstKeyValuePair { struct ConstKeyValuePair {
const Symbol& first; const Key first;
const Value& second; const Value& second;
ConstKeyValuePair(const Symbol& key, const Value& value) : first(key), second(value) {} ConstKeyValuePair(Key key, const Value& value) : first(key), second(value) {}
}; };
/// A pair of references to the key and value, the dereferenced type of the iterator and reverse_iterator /// A pair of references to the key and value, the dereferenced type of the iterator and reverse_iterator
struct KeyValuePair { struct KeyValuePair {
const Symbol& first; const Key first;
Value& second; Value& second;
KeyValuePair(const Symbol& key, Value& value) : first(key), second(value) {} KeyValuePair(Key key, Value& value) : first(key), second(value) {}
}; };
/// Mutable forward iterator, with value type KeyValuePair /// Mutable forward iterator, with value type KeyValuePair
@ -122,7 +121,7 @@ namespace gtsam {
/// @{ /// @{
/** print method for testing and debugging */ /** print method for testing and debugging */
void print(const std::string& str = "") const; void print(const std::string& str = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const;
/** Test whether the sets of keys and values are identical */ /** Test whether the sets of keys and values are identical */
bool equals(const Values& other, double tol=1e-9) const; bool equals(const Values& other, double tol=1e-9) const;
@ -137,7 +136,7 @@ namespace gtsam {
* @return A const reference to the stored value * @return A const reference to the stored value
*/ */
template<typename ValueType> template<typename ValueType>
const ValueType& at(const Symbol& j) const; const ValueType& at(Key j) const;
#if 0 #if 0
/** Retrieve a variable by key \c j. This non-templated version returns a /** Retrieve a variable by key \c j. This non-templated version returns a
@ -147,51 +146,25 @@ namespace gtsam {
* @return A ValueAutomaticCasting object that may be assignmed to a Value * @return A ValueAutomaticCasting object that may be assignmed to a Value
* of the proper type. * of the proper type.
*/ */
ValueAutomaticCasting at(const Symbol& j) const; ValueAutomaticCasting at(Key j) const;
#endif #endif
/** Retrieve a variable using a special key (typically TypedSymbol), which
* contains the type of the value associated with the key, and which must
* be conversion constructible to a Symbol, e.g.
* <tt>Symbol(const TypedKey&)</tt>. Throws DynamicValuesKeyDoesNotExist
* the key is not found, and DynamicValuesIncorrectType if the value type
* associated with the requested key does not match the stored value type.
*/
template<class TypedKey>
const typename TypedKey::Value& at(const TypedKey& j) const;
/** operator[] syntax for at(const TypedKey& j) */
template<class TypedKey>
const typename TypedKey::Value& operator[](const TypedKey& j) const {
return at(j); }
#if 0 #if 0
/** operator[] syntax for at(const Symbol& j) */ /** operator[] syntax for at(Key j) */
ValueAutomaticCasting operator[](const Symbol& j) const; ValueAutomaticCasting operator[](Key j) const;
#endif #endif
/** Check if a value exists with key \c j. See exists<>(const Symbol& j) /** Check if a value exists with key \c j. See exists<>(Key j)
* and exists(const TypedKey& j) for versions that return the value if it * and exists(const TypedKey& j) for versions that return the value if it
* exists. */ * exists. */
bool exists(const Symbol& j) const; bool exists(Key j) const;
/** Check if a value with key \c j exists, returns the value with type /** Check if a value with key \c j exists, returns the value with type
* \c Value if the key does exist, or boost::none if it does not exist. * \c Value if the key does exist, or boost::none if it does not exist.
* Throws DynamicValuesIncorrectType if the value type associated with the * Throws DynamicValuesIncorrectType if the value type associated with the
* requested key does not match the stored value type. */ * requested key does not match the stored value type. */
template<typename ValueType> template<typename ValueType>
boost::optional<const ValueType&> exists(const Symbol& j) const; boost::optional<const ValueType&> exists(Key j) const;
/** Check if a value with key \c j exists, returns the value with type
* \c Value if the key does exist, or boost::none if it does not exist.
* Uses a special key (typically TypedSymbol), which contains the type of
* the value associated with the key, and which must be conversion
* constructible to a Symbol, e.g. <tt>Symbol(const TypedKey&)</tt>. Throws
* DynamicValuesIncorrectType if the value type associated with the
* requested key does not match the stored value type.
*/
template<class TypedKey>
boost::optional<const typename TypedKey::Value&> exists(const TypedKey& j) const;
/** The number of variables in this config */ /** The number of variables in this config */
size_t size() const { return values_.size(); } size_t size() const { return values_.size(); }
@ -233,25 +206,25 @@ namespace gtsam {
///@} ///@}
/** Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present */ /** Add a variable with the given j, throws KeyAlreadyExists<J> if j is already present */
void insert(const Symbol& j, const Value& val); void insert(Key j, const Value& val);
/** Add a set of variables, throws KeyAlreadyExists<J> if a key is already present */ /** Add a set of variables, throws KeyAlreadyExists<J> if a key is already present */
void insert(const Values& values); void insert(const Values& values);
/** single element change of existing element */ /** single element change of existing element */
void update(const Symbol& j, const Value& val); void update(Key j, const Value& val);
/** update the current available values without adding new ones */ /** update the current available values without adding new ones */
void update(const Values& values); void update(const Values& values);
/** Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present */ /** Remove a variable from the config, throws KeyDoesNotExist<J> if j is not present */
void erase(const Symbol& j); void erase(Key j);
/** /**
* Returns a set of keys in the config * Returns a set of keys in the config
* Note: by construction, the list is ordered * Note: by construction, the list is ordered
*/ */
FastList<Symbol> keys() const; FastList<Key> keys() const;
/** Replace all keys and variables */ /** Replace all keys and variables */
Values& operator=(const Values& rhs); Values& operator=(const Values& rhs);
@ -286,20 +259,20 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
class ValuesKeyAlreadyExists : public std::exception { class ValuesKeyAlreadyExists : public std::exception {
protected: protected:
const Symbol key_; ///< The key that already existed const Key key_; ///< The key that already existed
private: private:
mutable std::string message_; mutable std::string message_;
public: public:
/// Construct with the key-value pair attemped to be added /// Construct with the key-value pair attemped to be added
ValuesKeyAlreadyExists(const Symbol& key) throw() : ValuesKeyAlreadyExists(Key key) throw() :
key_(key) {} key_(key) {}
virtual ~ValuesKeyAlreadyExists() throw() {} virtual ~ValuesKeyAlreadyExists() throw() {}
/// The duplicate key that was attemped to be added /// The duplicate key that was attemped to be added
const Symbol& key() const throw() { return key_; } Key key() const throw() { return key_; }
/// The message to be displayed to the user /// The message to be displayed to the user
virtual const char* what() const throw(); virtual const char* what() const throw();
@ -309,20 +282,20 @@ namespace gtsam {
class ValuesKeyDoesNotExist : public std::exception { class ValuesKeyDoesNotExist : public std::exception {
protected: protected:
const char* operation_; ///< The operation that attempted to access the key const char* operation_; ///< The operation that attempted to access the key
const Symbol key_; ///< The key that does not exist const Key key_; ///< The key that does not exist
private: private:
mutable std::string message_; mutable std::string message_;
public: public:
/// Construct with the key that does not exist in the values /// Construct with the key that does not exist in the values
ValuesKeyDoesNotExist(const char* operation, const Symbol& key) throw() : ValuesKeyDoesNotExist(const char* operation, Key key) throw() :
operation_(operation), key_(key) {} operation_(operation), key_(key) {}
virtual ~ValuesKeyDoesNotExist() throw() {} virtual ~ValuesKeyDoesNotExist() throw() {}
/// The key that was attempted to be accessed that does not exist /// The key that was attempted to be accessed that does not exist
const Symbol& key() const throw() { return key_; } Key key() const throw() { return key_; }
/// The message to be displayed to the user /// The message to be displayed to the user
virtual const char* what() const throw(); virtual const char* what() const throw();
@ -331,7 +304,7 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
class ValuesIncorrectType : public std::exception { class ValuesIncorrectType : public std::exception {
protected: protected:
const Symbol key_; ///< The key requested const Key key_; ///< The key requested
const std::type_info& storedTypeId_; const std::type_info& storedTypeId_;
const std::type_info& requestedTypeId_; const std::type_info& requestedTypeId_;
@ -340,14 +313,14 @@ namespace gtsam {
public: public:
/// Construct with the key that does not exist in the values /// Construct with the key that does not exist in the values
ValuesIncorrectType(const Symbol& key, ValuesIncorrectType(Key key,
const std::type_info& storedTypeId, const std::type_info& requestedTypeId) throw() : const std::type_info& storedTypeId, const std::type_info& requestedTypeId) throw() :
key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {} key_(key), storedTypeId_(storedTypeId), requestedTypeId_(requestedTypeId) {}
virtual ~ValuesIncorrectType() throw() {} virtual ~ValuesIncorrectType() throw() {}
/// The key that was attempted to be accessed that does not exist /// The key that was attempted to be accessed that does not exist
const Symbol& key() const throw() { return key_; } Key key() const throw() { return key_; }
/// The typeid of the value stores in the Values /// The typeid of the value stores in the Values
const std::type_info& storedTypeId() const { return storedTypeId_; } const std::type_info& storedTypeId() const { return storedTypeId_; }

View File

@ -24,6 +24,15 @@ using namespace boost::assign;
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
/* ************************************************************************* */
TEST(Key, KeySymbolConversion) {
Symbol expected('j', 4);
Key key(expected);
Symbol actual(key);
EXPECT(assert_equal(expected, actual))
}
/* ************************************************************************* */ /* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr); } int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
/* ************************************************************************* */ /* ************************************************************************* */

View File

@ -23,6 +23,7 @@ using namespace boost::assign;
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
#include <gtsam/base/TestableAssertions.h>
#include <gtsam/base/LieVector.h> #include <gtsam/base/LieVector.h>
#include <gtsam/geometry/Pose2.h> #include <gtsam/geometry/Pose2.h>
#include <gtsam/nonlinear/Values.h> #include <gtsam/nonlinear/Values.h>
@ -31,7 +32,7 @@ using namespace gtsam;
using namespace std; using namespace std;
static double inf = std::numeric_limits<double>::infinity(); static double inf = std::numeric_limits<double>::infinity();
Symbol key1("v1"), key2("v2"), key3("v3"), key4("v4"); Key key1(Symbol("v1")), key2(Symbol("v2")), key3(Symbol("v3")), key4(Symbol("v4"));
/* ************************************************************************* */ /* ************************************************************************* */
TEST( Values, equals1 ) TEST( Values, equals1 )
@ -201,8 +202,8 @@ TEST(Values, expmap_d)
CHECK(config0.equals(config0)); CHECK(config0.equals(config0));
Values poseconfig; Values poseconfig;
poseconfig.insert("p1", Pose2(1,2,3)); poseconfig.insert(key1, Pose2(1,2,3));
poseconfig.insert("p2", Pose2(0.3, 0.4, 0.5)); poseconfig.insert(key2, Pose2(0.3, 0.4, 0.5));
CHECK(equal(config0, config0)); CHECK(equal(config0, config0));
CHECK(config0.equals(config0)); CHECK(config0.equals(config0));
@ -213,19 +214,19 @@ TEST(Values, extract_keys)
{ {
Values config; Values config;
config.insert("x1", Pose2()); config.insert(key1, Pose2());
config.insert("x2", Pose2()); config.insert(key2, Pose2());
config.insert("x4", Pose2()); config.insert(key3, Pose2());
config.insert("x5", Pose2()); config.insert(key4, Pose2());
FastList<Symbol> expected, actual; FastList<Key> expected, actual;
expected += "x1", "x2", "x4", "x5"; expected += key1, key2, key3, key4;
actual = config.keys(); actual = config.keys();
CHECK(actual.size() == expected.size()); CHECK(actual.size() == expected.size());
FastList<Symbol>::const_iterator itAct = actual.begin(), itExp = expected.begin(); FastList<Key>::const_iterator itAct = actual.begin(), itExp = expected.begin();
for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) { for (; itAct != actual.end() && itExp != expected.end(); ++itAct, ++itExp) {
CHECK(assert_equal(*itExp, *itAct)); LONGS_EQUAL(*itExp, *itAct);
} }
} }

View File

@ -53,9 +53,9 @@ namespace gtsam {
/** implement functions needed for Testable */ /** implement functions needed for Testable */
/** print */ /** print */
virtual void print(const std::string& s) const { virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "AntiFactor version of:" << std::endl; std::cout << s << "AntiFactor version of:" << std::endl;
factor_->print(s); factor_->print(s, keyFormatter);
} }
/** equals */ /** equals */

View File

@ -26,7 +26,7 @@ namespace gtsam {
* Binary factor for a bearing measurement * Binary factor for a bearing measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class BearingFactor: public NonlinearFactor2<POSE, POINT> { class BearingFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
typedef POSE Pose; typedef POSE Pose;
@ -34,7 +34,7 @@ namespace gtsam {
typedef POINT Point; typedef POINT Point;
typedef BearingFactor<POSE, POINT> This; typedef BearingFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
Rot measured_; /** measurement */ Rot measured_; /** measurement */
@ -48,7 +48,7 @@ namespace gtsam {
BearingFactor() {} BearingFactor() {}
/** primary constructor */ /** primary constructor */
BearingFactor(const Symbol& poseKey, const Symbol& pointKey, const Rot& measured, BearingFactor(Key poseKey, Key pointKey, const Rot& measured,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
Base(model, poseKey, pointKey), measured_(measured) { Base(model, poseKey, pointKey), measured_(measured) {
} }
@ -79,7 +79,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }

View File

@ -28,7 +28,7 @@ namespace gtsam {
* Binary factor for a bearing measurement * Binary factor for a bearing measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class BearingRangeFactor: public NonlinearFactor2<POSE, POINT> { class BearingRangeFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
typedef POSE Pose; typedef POSE Pose;
@ -36,7 +36,7 @@ namespace gtsam {
typedef POINT Point; typedef POINT Point;
typedef BearingRangeFactor<POSE, POINT> This; typedef BearingRangeFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
// the measurement // the measurement
Rot measuredBearing_; Rot measuredBearing_;
@ -50,7 +50,7 @@ namespace gtsam {
public: public:
BearingRangeFactor() {} /* Default constructor */ BearingRangeFactor() {} /* Default constructor */
BearingRangeFactor(const Symbol& poseKey, const Symbol& pointKey, const Rot& measuredBearing, const double measuredRange, BearingRangeFactor(Key poseKey, Key pointKey, const Rot& measuredBearing, const double measuredRange,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
Base(model, poseKey, pointKey), measuredBearing_(measuredBearing), measuredRange_(measuredRange) { Base(model, poseKey, pointKey), measuredBearing_(measuredBearing), measuredRange_(measuredRange) {
} }
@ -58,10 +58,10 @@ namespace gtsam {
virtual ~BearingRangeFactor() {} virtual ~BearingRangeFactor() {}
/** Print */ /** Print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << ": BearingRangeFactor(" std::cout << s << ": BearingRangeFactor("
<< (std::string) this->key1() << "," << keyFormatter(this->key1()) << ","
<< (std::string) this->key2() << ")\n"; << keyFormatter(this->key2()) << ")\n";
measuredBearing_.print(" measured bearing"); measuredBearing_.print(" measured bearing");
std::cout << " measured range: " << measuredRange_ << std::endl; std::cout << " measured range: " << measuredRange_ << std::endl;
this->noiseModel_->print(" noise model"); this->noiseModel_->print(" noise model");
@ -106,7 +106,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measuredBearing_); ar & BOOST_SERIALIZATION_NVP(measuredBearing_);
ar & BOOST_SERIALIZATION_NVP(measuredRange_); ar & BOOST_SERIALIZATION_NVP(measuredRange_);

View File

@ -29,7 +29,7 @@ namespace gtsam {
* @tparam VALUE the Value type * @tparam VALUE the Value type
*/ */
template<class VALUE> template<class VALUE>
class BetweenFactor: public NonlinearFactor2<VALUE, VALUE> { class BetweenFactor: public NoiseModelFactor2<VALUE, VALUE> {
public: public:
@ -38,7 +38,7 @@ namespace gtsam {
private: private:
typedef BetweenFactor<VALUE> This; typedef BetweenFactor<VALUE> This;
typedef NonlinearFactor2<VALUE, VALUE> Base; typedef NoiseModelFactor2<VALUE, VALUE> Base;
VALUE measured_; /** The measurement */ VALUE measured_; /** The measurement */
@ -55,7 +55,7 @@ namespace gtsam {
BetweenFactor() {} BetweenFactor() {}
/** Constructor */ /** Constructor */
BetweenFactor(const Symbol& key1, const Symbol& key2, const VALUE& measured, BetweenFactor(Key key1, Key key2, const VALUE& measured,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
Base(model, key1, key2), measured_(measured) { Base(model, key1, key2), measured_(measured) {
} }
@ -65,10 +65,10 @@ namespace gtsam {
/** implement functions needed for Testable */ /** implement functions needed for Testable */
/** print */ /** print */
virtual void print(const std::string& s) const { virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "BetweenFactor(" std::cout << s << "BetweenFactor("
<< (std::string) this->key1() << "," << keyFormatter(this->key1()) << ","
<< (std::string) this->key2() << ")\n"; << keyFormatter(this->key2()) << ")\n";
measured_.print(" measured"); measured_.print(" measured");
this->noiseModel_->print(" noise model"); this->noiseModel_->print(" noise model");
} }
@ -106,7 +106,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }
@ -123,7 +123,7 @@ namespace gtsam {
typedef boost::shared_ptr<BetweenConstraint<VALUE> > shared_ptr; typedef boost::shared_ptr<BetweenConstraint<VALUE> > shared_ptr;
/** Syntactic sugar for constrained version */ /** Syntactic sugar for constrained version */
BetweenConstraint(const VALUE& measured, const Symbol& key1, const Symbol& key2, double mu = 1000.0) : BetweenConstraint(const VALUE& measured, Key key1, Key key2, double mu = 1000.0) :
BetweenFactor<VALUE>(key1, key2, measured, noiseModel::Constrained::All(VALUE::Dim(), fabs(mu))) {} BetweenFactor<VALUE>(key1, key2, measured, noiseModel::Constrained::All(VALUE::Dim(), fabs(mu))) {}
private: private:

View File

@ -29,15 +29,15 @@ namespace gtsam {
* a scalar for comparison. * a scalar for comparison.
*/ */
template<class VALUE> template<class VALUE>
struct BoundingConstraint1: public NonlinearFactor1<VALUE> { struct BoundingConstraint1: public NoiseModelFactor1<VALUE> {
typedef VALUE X; typedef VALUE X;
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
typedef boost::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr; typedef boost::shared_ptr<BoundingConstraint1<VALUE> > shared_ptr;
double threshold_; double threshold_;
bool isGreaterThan_; /// flag for greater/less than bool isGreaterThan_; /// flag for greater/less than
BoundingConstraint1(const Symbol& key, double threshold, BoundingConstraint1(Key key, double threshold,
bool isGreaterThan, double mu = 1000.0) : bool isGreaterThan, double mu = 1000.0) :
Base(noiseModel::Constrained::All(1, mu), key), Base(noiseModel::Constrained::All(1, mu), key),
threshold_(threshold), isGreaterThan_(isGreaterThan) { threshold_(threshold), isGreaterThan_(isGreaterThan) {
@ -84,7 +84,7 @@ private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);
ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);
@ -96,17 +96,17 @@ private:
* to implement for specific systems * to implement for specific systems
*/ */
template<class VALUE1, class VALUE2> template<class VALUE1, class VALUE2>
struct BoundingConstraint2: public NonlinearFactor2<VALUE1, VALUE2> { struct BoundingConstraint2: public NoiseModelFactor2<VALUE1, VALUE2> {
typedef VALUE1 X1; typedef VALUE1 X1;
typedef VALUE2 X2; typedef VALUE2 X2;
typedef NonlinearFactor2<VALUE1, VALUE2> Base; typedef NoiseModelFactor2<VALUE1, VALUE2> Base;
typedef boost::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr; typedef boost::shared_ptr<BoundingConstraint2<VALUE1, VALUE2> > shared_ptr;
double threshold_; double threshold_;
bool isGreaterThan_; /// flag for greater/less than bool isGreaterThan_; /// flag for greater/less than
BoundingConstraint2(const Symbol& key1, const Symbol& key2, double threshold, BoundingConstraint2(Key key1, Key key2, double threshold,
bool isGreaterThan, double mu = 1000.0) bool isGreaterThan, double mu = 1000.0)
: Base(noiseModel::Constrained::All(1, mu), key1, key2), : Base(noiseModel::Constrained::All(1, mu), key1, key2),
threshold_(threshold), isGreaterThan_(isGreaterThan) {} threshold_(threshold), isGreaterThan_(isGreaterThan) {}
@ -157,7 +157,7 @@ private:
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(threshold_); ar & BOOST_SERIALIZATION_NVP(threshold_);
ar & BOOST_SERIALIZATION_NVP(isGreaterThan_); ar & BOOST_SERIALIZATION_NVP(isGreaterThan_);

View File

@ -31,7 +31,7 @@ namespace gtsam {
*/ */
template <class CAMERA, class LANDMARK> template <class CAMERA, class LANDMARK>
class GeneralSFMFactor: class GeneralSFMFactor:
public NonlinearFactor2<CAMERA, LANDMARK> { public NoiseModelFactor2<CAMERA, LANDMARK> {
protected: protected:
Point2 measured_; ///< the 2D measurement Point2 measured_; ///< the 2D measurement
@ -39,7 +39,7 @@ namespace gtsam {
typedef CAMERA Cam; ///< typedef for camera type typedef CAMERA Cam; ///< typedef for camera type
typedef GeneralSFMFactor<CAMERA, LANDMARK> This; ///< typedef for this object typedef GeneralSFMFactor<CAMERA, LANDMARK> This; ///< typedef for this object
typedef NonlinearFactor2<CAMERA, LANDMARK> Base; ///< typedef for the base class typedef NoiseModelFactor2<CAMERA, LANDMARK> Base; ///< typedef for the base class
typedef Point2 Measurement; ///< typedef for the measurement typedef Point2 Measurement; ///< typedef for the measurement
// shorthand for a smart pointer to a factor // shorthand for a smart pointer to a factor
@ -52,7 +52,7 @@ namespace gtsam {
* @param i is basically the frame number * @param i is basically the frame number
* @param j is the index of the landmark * @param j is the index of the landmark
*/ */
GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model, const Symbol& cameraKey, const Symbol& landmarkKey) : GeneralSFMFactor(const Point2& measured, const SharedNoiseModel& model, Key cameraKey, Key landmarkKey) :
Base(model, cameraKey, landmarkKey), measured_(measured) {} Base(model, cameraKey, landmarkKey), measured_(measured) {}
GeneralSFMFactor():measured_(0.0,0.0) {} ///< default constructor GeneralSFMFactor():measured_(0.0,0.0) {} ///< default constructor
@ -65,8 +65,8 @@ namespace gtsam {
* print * print
* @param s optional string naming the factor * @param s optional string naming the factor
*/ */
void print(const std::string& s = "SFMFactor") const { void print(const std::string& s = "SFMFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
Base::print(s); Base::print(s, keyFormatter);
measured_.print(s + ".z"); measured_.print(s + ".z");
} }

View File

@ -39,14 +39,14 @@ namespace gtsam {
* construct the mask. * construct the mask.
*/ */
template<class VALUE> template<class VALUE>
class PartialPriorFactor: public NonlinearFactor1<VALUE> { class PartialPriorFactor: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
protected: protected:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
typedef PartialPriorFactor<VALUE> This; typedef PartialPriorFactor<VALUE> This;
Vector prior_; ///< measurement on logmap parameters, in compressed form Vector prior_; ///< measurement on logmap parameters, in compressed form
@ -60,7 +60,7 @@ namespace gtsam {
* constructor with just minimum requirements for a factor - allows more * constructor with just minimum requirements for a factor - allows more
* computation in the constructor. This should only be used by subclasses * computation in the constructor. This should only be used by subclasses
*/ */
PartialPriorFactor(const Symbol& key, const SharedNoiseModel& model) PartialPriorFactor(Key key, const SharedNoiseModel& model)
: Base(model, key) {} : Base(model, key) {}
public: public:
@ -71,14 +71,14 @@ namespace gtsam {
virtual ~PartialPriorFactor() {} virtual ~PartialPriorFactor() {}
/** Single Element Constructor: acts on a single parameter specified by idx */ /** Single Element Constructor: acts on a single parameter specified by idx */
PartialPriorFactor(const Symbol& key, size_t idx, double prior, const SharedNoiseModel& model) : PartialPriorFactor(Key key, size_t idx, double prior, const SharedNoiseModel& model) :
Base(model, key), prior_(Vector_(1, prior)), mask_(1, idx), H_(zeros(1, T::Dim())) { Base(model, key), prior_(Vector_(1, prior)), mask_(1, idx), H_(zeros(1, T::Dim())) {
assert(model->dim() == 1); assert(model->dim() == 1);
this->fillH(); this->fillH();
} }
/** Indices Constructor: specify the mask with a set of indices */ /** Indices Constructor: specify the mask with a set of indices */
PartialPriorFactor(const Symbol& key, const std::vector<size_t>& mask, const Vector& prior, PartialPriorFactor(Key key, const std::vector<size_t>& mask, const Vector& prior,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
Base(model, key), prior_(prior), mask_(mask), H_(zeros(mask.size(), T::Dim())) { Base(model, key), prior_(prior), mask_(mask), H_(zeros(mask.size(), T::Dim())) {
assert((size_t)prior_.size() == mask.size()); assert((size_t)prior_.size() == mask.size());
@ -89,8 +89,8 @@ namespace gtsam {
/** implement functions needed for Testable */ /** implement functions needed for Testable */
/** print */ /** print */
virtual void print(const std::string& s) const { virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
Base::print(s); Base::print(s, keyFormatter);
gtsam::print(prior_, "prior"); gtsam::print(prior_, "prior");
} }
@ -133,7 +133,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);
ar & BOOST_SERIALIZATION_NVP(mask_); ar & BOOST_SERIALIZATION_NVP(mask_);

View File

@ -24,14 +24,14 @@ namespace gtsam {
* A class for a soft prior on any Value type * A class for a soft prior on any Value type
*/ */
template<class VALUE> template<class VALUE>
class PriorFactor: public NonlinearFactor1<VALUE> { class PriorFactor: public NoiseModelFactor1<VALUE> {
public: public:
typedef VALUE T; typedef VALUE T;
private: private:
typedef NonlinearFactor1<VALUE> Base; typedef NoiseModelFactor1<VALUE> Base;
VALUE prior_; /** The measurement */ VALUE prior_; /** The measurement */
@ -52,15 +52,15 @@ namespace gtsam {
virtual ~PriorFactor() {} virtual ~PriorFactor() {}
/** Constructor */ /** Constructor */
PriorFactor(const Symbol& key, const VALUE& prior, const SharedNoiseModel& model) : PriorFactor(Key key, const VALUE& prior, const SharedNoiseModel& model) :
Base(model, key), prior_(prior) { Base(model, key), prior_(prior) {
} }
/** implement functions needed for Testable */ /** implement functions needed for Testable */
/** print */ /** print */
virtual void print(const std::string& s) const { virtual void print(const std::string& s, const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
std::cout << s << "PriorFactor(" << (std::string) this->key() << ")\n"; std::cout << s << "PriorFactor(" << keyFormatter(this->key()) << ")\n";
prior_.print(" prior"); prior_.print(" prior");
this->noiseModel_->print(" noise model"); this->noiseModel_->print(" noise model");
} }
@ -86,7 +86,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor1", ar & boost::serialization::make_nvp("NoiseModelFactor1",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(prior_); ar & BOOST_SERIALIZATION_NVP(prior_);
} }

View File

@ -30,7 +30,7 @@ namespace gtsam {
* i.e. the main building block for visual SLAM. * i.e. the main building block for visual SLAM.
*/ */
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericProjectionFactor: public NonlinearFactor2<POSE, LANDMARK> { class GenericProjectionFactor: public NoiseModelFactor2<POSE, LANDMARK> {
protected: protected:
// Keep a copy of measurement and calibration for I/O // Keep a copy of measurement and calibration for I/O
@ -40,7 +40,7 @@ namespace gtsam {
public: public:
/// shorthand for base class type /// shorthand for base class type
typedef NonlinearFactor2<POSE, LANDMARK> Base; typedef NoiseModelFactor2<POSE, LANDMARK> Base;
/// shorthand for this class /// shorthand for this class
typedef GenericProjectionFactor<POSE, LANDMARK> This; typedef GenericProjectionFactor<POSE, LANDMARK> This;
@ -63,7 +63,7 @@ namespace gtsam {
* @param K shared pointer to the constant calibration * @param K shared pointer to the constant calibration
*/ */
GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model, GenericProjectionFactor(const Point2& measured, const SharedNoiseModel& model,
const Symbol poseKey, const Symbol& pointKey, const shared_ptrK& K) : const Symbol poseKey, Key pointKey, const shared_ptrK& K) :
Base(model, poseKey, pointKey), measured_(measured), K_(K) { Base(model, poseKey, pointKey), measured_(measured), K_(K) {
} }
@ -71,8 +71,8 @@ namespace gtsam {
* print * print
* @param s optional string naming the factor * @param s optional string naming the factor
*/ */
void print(const std::string& s = "ProjectionFactor") const { void print(const std::string& s = "ProjectionFactor", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
Base::print(s); Base::print(s, keyFormatter);
measured_.print(s + ".z"); measured_.print(s + ".z");
} }
@ -92,8 +92,8 @@ namespace gtsam {
} catch( CheiralityException& e) { } catch( CheiralityException& e) {
if (H1) *H1 = zeros(2,6); if (H1) *H1 = zeros(2,6);
if (H2) *H2 = zeros(2,3); if (H2) *H2 = zeros(2,3);
cout << e.what() << ": Landmark "<< this->key2().index() << cout << e.what() << ": Landmark "<< DefaultKeyFormatter(this->key2()) <<
" moved behind camera " << this->key1().index() << endl; " moved behind camera " << DefaultKeyFormatter(this->key1()) << endl;
return ones(2) * 2.0 * K_->fx(); return ones(2) * 2.0 * K_->fx();
} }
} }

View File

@ -26,13 +26,13 @@ namespace gtsam {
* Binary factor for a range measurement * Binary factor for a range measurement
*/ */
template<class POSE, class POINT> template<class POSE, class POINT>
class RangeFactor: public NonlinearFactor2<POSE, POINT> { class RangeFactor: public NoiseModelFactor2<POSE, POINT> {
private: private:
double measured_; /** measurement */ double measured_; /** measurement */
typedef RangeFactor<POSE, POINT> This; typedef RangeFactor<POSE, POINT> This;
typedef NonlinearFactor2<POSE, POINT> Base; typedef NoiseModelFactor2<POSE, POINT> Base;
typedef POSE Pose; typedef POSE Pose;
typedef POINT Point; typedef POINT Point;
@ -44,7 +44,7 @@ namespace gtsam {
RangeFactor() {} /* Default constructor */ RangeFactor() {} /* Default constructor */
RangeFactor(const Symbol& poseKey, const Symbol& pointKey, double measured, RangeFactor(Key poseKey, Key pointKey, double measured,
const SharedNoiseModel& model) : const SharedNoiseModel& model) :
Base(model, poseKey, pointKey), measured_(measured) { Base(model, poseKey, pointKey), measured_(measured) {
} }
@ -69,8 +69,8 @@ namespace gtsam {
} }
/** print contents */ /** print contents */
void print(const std::string& s="") const { void print(const std::string& s="", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
Base::print(s + std::string(" range: ") + boost::lexical_cast<std::string>(measured_)); Base::print(s + std::string(" range: ") + boost::lexical_cast<std::string>(measured_), keyFormatter);
} }
private: private:
@ -79,7 +79,7 @@ namespace gtsam {
friend class boost::serialization::access; friend class boost::serialization::access;
template<class ARCHIVE> template<class ARCHIVE>
void serialize(ARCHIVE & ar, const unsigned int version) { void serialize(ARCHIVE & ar, const unsigned int version) {
ar & boost::serialization::make_nvp("NonlinearFactor2", ar & boost::serialization::make_nvp("NoiseModelFactor2",
boost::serialization::base_object<Base>(*this)); boost::serialization::base_object<Base>(*this));
ar & BOOST_SERIALIZATION_NVP(measured_); ar & BOOST_SERIALIZATION_NVP(measured_);
} }

View File

@ -23,7 +23,7 @@
namespace gtsam { namespace gtsam {
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericStereoFactor: public NonlinearFactor2<POSE, LANDMARK> { class GenericStereoFactor: public NoiseModelFactor2<POSE, LANDMARK> {
private: private:
// Keep a copy of measurement and calibration for I/O // Keep a copy of measurement and calibration for I/O
@ -33,7 +33,7 @@ private:
public: public:
// shorthand for base class type // shorthand for base class type
typedef NonlinearFactor2<POSE, LANDMARK> Base; ///< typedef for base class typedef NoiseModelFactor2<POSE, LANDMARK> Base; ///< typedef for base class
typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object typedef boost::shared_ptr<GenericStereoFactor> shared_ptr; ///< typedef for shared pointer to this object
typedef POSE CamPose; ///< typedef for Pose Lie Value type typedef POSE CamPose; ///< typedef for Pose Lie Value type
@ -50,7 +50,7 @@ public:
* @param landmarkKey the landmark variable key * @param landmarkKey the landmark variable key
* @param K the constant calibration * @param K the constant calibration
*/ */
GenericStereoFactor(const StereoPoint2& measured, const SharedNoiseModel& model, const Symbol& poseKey, const Symbol& landmarkKey, const shared_ptrKStereo& K) : GenericStereoFactor(const StereoPoint2& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey, const shared_ptrKStereo& K) :
Base(model, poseKey, landmarkKey), measured_(measured), K_(K) { Base(model, poseKey, landmarkKey), measured_(measured), K_(K) {
} }
@ -60,8 +60,8 @@ public:
* print * print
* @param s optional string naming the factor * @param s optional string naming the factor
*/ */
void print(const std::string& s) const { void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
Base::print(s); Base::print(s, keyFormatter);
measured_.print(s + ".z"); measured_.print(s + ".z");
} }

View File

@ -156,7 +156,7 @@ void save2D(const pose2SLAM::Graph& graph, const Values& config, const SharedDia
// save poses // save poses
BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) { BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) {
const Pose2& pose = dynamic_cast<const Pose2&>(key_value.second); const Pose2& pose = dynamic_cast<const Pose2&>(key_value.second);
stream << "VERTEX2 " << key_value.first.index() << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl; stream << "VERTEX2 " << key_value.first << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl;
} }
// save edges // save edges
@ -167,7 +167,7 @@ void save2D(const pose2SLAM::Graph& graph, const Values& config, const SharedDia
if (!factor) continue; if (!factor) continue;
Pose2 pose = factor->measured().inverse(); Pose2 pose = factor->measured().inverse();
stream << "EDGE2 " << factor->key2().index() << " " << factor->key1().index() stream << "EDGE2 " << factor->key2() << " " << factor->key1()
<< " " << pose.x() << " " << pose.y() << " " << pose.theta() << " " << pose.x() << " " << pose.y() << " " << pose.theta()
<< " " << RR(0, 0) << " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2) << " " << RR(0, 0) << " " << RR(0, 1) << " " << RR(1, 1) << " " << RR(2, 2)
<< " " << RR(0, 2) << " " << RR(1, 2) << endl; << " " << RR(0, 2) << " " << RR(1, 2) << endl;

View File

@ -120,16 +120,16 @@ namespace simulated2D {
* Unary factor encoding a soft prior on a vector * Unary factor encoding a soft prior on a vector
*/ */
template<class VALUE = Point2> template<class VALUE = Point2>
class GenericPrior: public NonlinearFactor1<VALUE> { class GenericPrior: public NoiseModelFactor1<VALUE> {
public: public:
typedef NonlinearFactor1<VALUE> Base; ///< base class typedef NoiseModelFactor1<VALUE> Base; ///< base class
typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr; typedef boost::shared_ptr<GenericPrior<VALUE> > shared_ptr;
typedef VALUE Pose; ///< shortcut to Pose type typedef VALUE Pose; ///< shortcut to Pose type
Pose measured_; ///< prior mean Pose measured_; ///< prior mean
/// Create generic prior /// Create generic prior
GenericPrior(const Pose& z, const SharedNoiseModel& model, const Symbol& key) : GenericPrior(const Pose& z, const SharedNoiseModel& model, Key key) :
Base(model, key), measured_(z) { Base(model, key), measured_(z) {
} }
@ -157,16 +157,16 @@ namespace simulated2D {
* Binary factor simulating "odometry" between two Vectors * Binary factor simulating "odometry" between two Vectors
*/ */
template<class VALUE = Point2> template<class VALUE = Point2>
class GenericOdometry: public NonlinearFactor2<VALUE, VALUE> { class GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
public: public:
typedef NonlinearFactor2<VALUE, VALUE> Base; ///< base class typedef NoiseModelFactor2<VALUE, VALUE> Base; ///< base class
typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr; typedef boost::shared_ptr<GenericOdometry<VALUE> > shared_ptr;
typedef VALUE Pose; ///< shortcut to Pose type typedef VALUE Pose; ///< shortcut to Pose type
Pose measured_; ///< odometry measurement Pose measured_; ///< odometry measurement
/// Create odometry /// Create odometry
GenericOdometry(const Pose& measured, const SharedNoiseModel& model, const Symbol& key1, const Symbol& key2) : GenericOdometry(const Pose& measured, const SharedNoiseModel& model, Key key1, Key key2) :
Base(model, key1, key2), measured_(measured) { Base(model, key1, key2), measured_(measured) {
} }
@ -196,9 +196,9 @@ namespace simulated2D {
* Binary factor simulating "measurement" between two Vectors * Binary factor simulating "measurement" between two Vectors
*/ */
template<class POSE, class LANDMARK> template<class POSE, class LANDMARK>
class GenericMeasurement: public NonlinearFactor2<POSE, LANDMARK> { class GenericMeasurement: public NoiseModelFactor2<POSE, LANDMARK> {
public: public:
typedef NonlinearFactor2<POSE, LANDMARK> Base; ///< base class typedef NoiseModelFactor2<POSE, LANDMARK> Base; ///< base class
typedef boost::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr; typedef boost::shared_ptr<GenericMeasurement<POSE, LANDMARK> > shared_ptr;
typedef POSE Pose; ///< shortcut to Pose type typedef POSE Pose; ///< shortcut to Pose type
typedef LANDMARK Landmark; ///< shortcut to Landmark type typedef LANDMARK Landmark; ///< shortcut to Landmark type
@ -206,7 +206,7 @@ namespace simulated2D {
Landmark measured_; ///< Measurement Landmark measured_; ///< Measurement
/// Create measurement factor /// Create measurement factor
GenericMeasurement(const Landmark& measured, const SharedNoiseModel& model, const Symbol& poseKey, const Symbol& landmarkKey) : GenericMeasurement(const Landmark& measured, const SharedNoiseModel& model, Key poseKey, Key landmarkKey) :
Base(model, poseKey, landmarkKey), measured_(measured) { Base(model, poseKey, landmarkKey), measured_(measured) {
} }

View File

@ -65,7 +65,7 @@ namespace simulated2D {
* @param isGreaterThan is a flag to set inequality as greater than or less than * @param isGreaterThan is a flag to set inequality as greater than or less than
* @param mu is the penalty function gain * @param mu is the penalty function gain
*/ */
ScalarCoordConstraint1(const Symbol& key, double c, ScalarCoordConstraint1(Key key, double c,
bool isGreaterThan, double mu = 1000.0) : bool isGreaterThan, double mu = 1000.0) :
Base(key, c, isGreaterThan, mu) { Base(key, c, isGreaterThan, mu) {
} }
@ -127,7 +127,7 @@ namespace simulated2D {
* @param range_bound is the maximum range allowed between the variables * @param range_bound is the maximum range allowed between the variables
* @param mu is the gain for the penalty function * @param mu is the gain for the penalty function
*/ */
MaxDistanceConstraint(const Symbol& key1, const Symbol& key2, double range_bound, double mu = 1000.0) : MaxDistanceConstraint(Key key1, Key key2, double range_bound, double mu = 1000.0) :
Base(key1, key2, range_bound, false, mu) {} Base(key1, key2, range_bound, false, mu) {}
/** /**
@ -170,7 +170,7 @@ namespace simulated2D {
* @param range_bound is the minimum range allowed between the variables * @param range_bound is the minimum range allowed between the variables
* @param mu is the gain for the penalty function * @param mu is the gain for the penalty function
*/ */
MinDistanceConstraint(const Symbol& key1, const Symbol& key2, MinDistanceConstraint(Key key1, Key key2,
double range_bound, double mu = 1000.0) double range_bound, double mu = 1000.0)
: Base(key1, key2, range_bound, true, mu) {} : Base(key1, key2, range_bound, true, mu) {}

View File

@ -78,13 +78,13 @@ namespace simulated2DOriented {
/// Unary factor encoding a soft prior on a vector /// Unary factor encoding a soft prior on a vector
template<class VALUE = Pose2> template<class VALUE = Pose2>
struct GenericPosePrior: public NonlinearFactor1<VALUE> { struct GenericPosePrior: public NoiseModelFactor1<VALUE> {
Pose2 measured_; ///< measurement Pose2 measured_; ///< measurement
/// Create generic pose prior /// Create generic pose prior
GenericPosePrior(const Pose2& measured, const SharedNoiseModel& model, const Symbol& key) : GenericPosePrior(const Pose2& measured, const SharedNoiseModel& model, Key key) :
NonlinearFactor1<VALUE>(model, key), measured_(measured) { NoiseModelFactor1<VALUE>(model, key), measured_(measured) {
} }
/// Evaluate error and optionally derivative /// Evaluate error and optionally derivative
@ -99,15 +99,15 @@ namespace simulated2DOriented {
* Binary factor simulating "odometry" between two Vectors * Binary factor simulating "odometry" between two Vectors
*/ */
template<class VALUE = Pose2> template<class VALUE = Pose2>
struct GenericOdometry: public NonlinearFactor2<VALUE, VALUE> { struct GenericOdometry: public NoiseModelFactor2<VALUE, VALUE> {
Pose2 measured_; ///< Between measurement for odometry factor Pose2 measured_; ///< Between measurement for odometry factor
/** /**
* Creates an odometry factor between two poses * Creates an odometry factor between two poses
*/ */
GenericOdometry(const Pose2& measured, const SharedNoiseModel& model, GenericOdometry(const Pose2& measured, const SharedNoiseModel& model,
const Symbol& i1, const Symbol& i2) : Key i1, Key i2) :
NonlinearFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) { NoiseModelFactor2<VALUE, VALUE>(model, i1, i2), measured_(measured) {
} }
/// Evaluate error and optionally derivative /// Evaluate error and optionally derivative

View File

@ -64,7 +64,7 @@ Point3 mea(const Point3& x, const Point3& l,
/** /**
* A prior factor on a single linear robot pose * A prior factor on a single linear robot pose
*/ */
struct PointPrior3D: public NonlinearFactor1<Point3> { struct PointPrior3D: public NoiseModelFactor1<Point3> {
Point3 measured_; ///< The prior pose value for the variable attached to this factor Point3 measured_; ///< The prior pose value for the variable attached to this factor
@ -74,8 +74,8 @@ struct PointPrior3D: public NonlinearFactor1<Point3> {
* @param model is the measurement model for the factor (Dimension: 3) * @param model is the measurement model for the factor (Dimension: 3)
* @param key is the key for the pose * @param key is the key for the pose
*/ */
PointPrior3D(const Point3& measured, const SharedNoiseModel& model, const Symbol& key) : PointPrior3D(const Point3& measured, const SharedNoiseModel& model, Key key) :
NonlinearFactor1<Point3> (model, key), measured_(measured) { NoiseModelFactor1<Point3> (model, key), measured_(measured) {
} }
/** /**
@ -94,7 +94,7 @@ struct PointPrior3D: public NonlinearFactor1<Point3> {
/** /**
* Models a linear 3D measurement between 3D points * Models a linear 3D measurement between 3D points
*/ */
struct Simulated3DMeasurement: public NonlinearFactor2<Point3, Point3> { struct Simulated3DMeasurement: public NoiseModelFactor2<Point3, Point3> {
Point3 measured_; ///< Linear displacement between a pose and landmark Point3 measured_; ///< Linear displacement between a pose and landmark
@ -106,8 +106,8 @@ struct Simulated3DMeasurement: public NonlinearFactor2<Point3, Point3> {
* @param pointKey is the point key for the landmark * @param pointKey is the point key for the landmark
*/ */
Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model, Simulated3DMeasurement(const Point3& measured, const SharedNoiseModel& model,
const Symbol& poseKey, const Symbol& pointKey) : Key poseKey, Key pointKey) :
NonlinearFactor2<Point3, Point3>(model, poseKey, pointKey), measured_(measured) {} NoiseModelFactor2<Point3, Point3>(model, poseKey, pointKey), measured_(measured) {}
/** /**
* Error function with optional derivatives * Error function with optional derivatives

View File

@ -24,7 +24,7 @@
using namespace std; using namespace std;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like Symbol("x3") to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
@ -121,18 +121,18 @@ namespace example {
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createCorrectDelta(const Ordering& ordering) { VectorValues createCorrectDelta(const Ordering& ordering) {
VectorValues c(vector<size_t>(3,2)); VectorValues c(vector<size_t>(3,2));
c[ordering["l1"]] = Vector_(2, -0.1, 0.1); c[ordering[Symbol(Symbol("l1"))]] = Vector_(2, -0.1, 0.1);
c[ordering["x1"]] = Vector_(2, -0.1, -0.1); c[ordering[Symbol("x1")]] = Vector_(2, -0.1, -0.1);
c[ordering["x2"]] = Vector_(2, 0.1, -0.2); c[ordering[Symbol("x2")]] = Vector_(2, 0.1, -0.2);
return c; return c;
} }
/* ************************************************************************* */ /* ************************************************************************* */
VectorValues createZeroDelta(const Ordering& ordering) { VectorValues createZeroDelta(const Ordering& ordering) {
VectorValues c(vector<size_t>(3,2)); VectorValues c(vector<size_t>(3,2));
c[ordering["l1"]] = zero(2); c[ordering[Symbol(Symbol("l1"))]] = zero(2);
c[ordering["x1"]] = zero(2); c[ordering[Symbol("x1")]] = zero(2);
c[ordering["x2"]] = zero(2); c[ordering[Symbol("x2")]] = zero(2);
return c; return c;
} }
@ -144,16 +144,16 @@ namespace example {
SharedDiagonal unit2 = noiseModel::Unit::Create(2); SharedDiagonal unit2 = noiseModel::Unit::Create(2);
// linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_] // linearized prior on x1: c[_x1_]+x1=0 i.e. x1=-c[_x1_]
fg.add(ordering["x1"], 10*eye(2), -1.0*ones(2), unit2); fg.add(ordering[Symbol("x1")], 10*eye(2), -1.0*ones(2), unit2);
// odometry between x1 and x2: x2-x1=[0.2;-0.1] // odometry between x1 and x2: x2-x1=[0.2;-0.1]
fg.add(ordering["x1"], -10*eye(2),ordering["x2"], 10*eye(2), Vector_(2, 2.0, -1.0), unit2); fg.add(ordering[Symbol("x1")], -10*eye(2),ordering[Symbol("x2")], 10*eye(2), Vector_(2, 2.0, -1.0), unit2);
// measurement between x1 and l1: l1-x1=[0.0;0.2] // measurement between x1 and l1: l1-x1=[0.0;0.2]
fg.add(ordering["x1"], -5*eye(2), ordering["l1"], 5*eye(2), Vector_(2, 0.0, 1.0), unit2); fg.add(ordering[Symbol("x1")], -5*eye(2), ordering[Symbol("l1")], 5*eye(2), Vector_(2, 0.0, 1.0), unit2);
// measurement between x2 and l1: l1-x2=[-0.2;0.3] // measurement between x2 and l1: l1-x2=[-0.2;0.3]
fg.add(ordering["x2"], -5*eye(2), ordering["l1"], 5*eye(2), Vector_(2, -1.0, 1.5), unit2); fg.add(ordering[Symbol("x2")], -5*eye(2), ordering[Symbol("l1")], 5*eye(2), Vector_(2, -1.0, 1.5), unit2);
return *fg.dynamicCastFactors<FactorGraph<JacobianFactor> >(); return *fg.dynamicCastFactors<FactorGraph<JacobianFactor> >();
} }
@ -198,12 +198,12 @@ namespace example {
0.0, cos(v.y())); 0.0, cos(v.y()));
} }
struct UnaryFactor: public gtsam::NonlinearFactor1<Point2> { struct UnaryFactor: public gtsam::NoiseModelFactor1<Point2> {
Point2 z_; Point2 z_;
UnaryFactor(const Point2& z, const SharedNoiseModel& model, const Symbol& key) : UnaryFactor(const Point2& z, const SharedNoiseModel& model, Key key) :
gtsam::NonlinearFactor1<Point2>(model, key), z_(z) { gtsam::NoiseModelFactor1<Point2>(model, key), z_(z) {
} }
Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const { Vector evaluateError(const Point2& x, boost::optional<Matrix&> A = boost::none) const {

View File

@ -89,14 +89,14 @@ TEST( GeneralSFMFactor, equals )
TEST( GeneralSFMFactor, error ) { TEST( GeneralSFMFactor, error ) {
Point2 z(3.,0.); Point2 z(3.,0.);
const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); const SharedNoiseModel sigma(noiseModel::Unit::Create(1));
boost::shared_ptr<Projection> factor(new Projection(z, sigma, "x1", "l1")); boost::shared_ptr<Projection> factor(new Projection(z, sigma, Symbol("x1"), Symbol("l1")));
// For the following configuration, the factor predicts 320,240 // For the following configuration, the factor predicts 320,240
Values values; Values values;
Rot3 R; Rot3 R;
Point3 t1(0,0,-6); Point3 t1(0,0,-6);
Pose3 x1(R,t1); Pose3 x1(R,t1);
values.insert("x1", GeneralCamera(x1)); values.insert(Symbol("x1"), GeneralCamera(x1));
Point3 l1; values.insert("l1", l1); Point3 l1; values.insert(Symbol("l1"), l1);
EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values)));
} }
@ -137,10 +137,9 @@ vector<GeneralCamera> genCameraVariableCalibration() {
} }
shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& X, const vector<Point3>& L) { shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& X, const vector<Point3>& L) {
list<Symbol> keys; shared_ptr<Ordering> ordering(new Ordering);
for ( size_t i = 0 ; i < L.size() ; ++i ) keys.push_back(Symbol('l', i)) ; for ( size_t i = 0 ; i < L.size() ; ++i ) ordering->push_back(Symbol('l', i)) ;
for ( size_t i = 0 ; i < X.size() ; ++i ) keys.push_back(Symbol('x', i)) ; for ( size_t i = 0 ; i < X.size() ; ++i ) ordering->push_back(Symbol('x', i)) ;
shared_ptr<Ordering> ordering(new Ordering(keys));
return ordering ; return ordering ;
} }

View File

@ -91,14 +91,14 @@ TEST( GeneralSFMFactor, error ) {
Point2 z(3.,0.); Point2 z(3.,0.);
const SharedNoiseModel sigma(noiseModel::Unit::Create(1)); const SharedNoiseModel sigma(noiseModel::Unit::Create(1));
boost::shared_ptr<Projection> boost::shared_ptr<Projection>
factor(new Projection(z, sigma, "x1", "l1")); factor(new Projection(z, sigma, Symbol("x1"), Symbol("l1")));
// For the following configuration, the factor predicts 320,240 // For the following configuration, the factor predicts 320,240
Values values; Values values;
Rot3 R; Rot3 R;
Point3 t1(0,0,-6); Point3 t1(0,0,-6);
Pose3 x1(R,t1); Pose3 x1(R,t1);
values.insert("x1", GeneralCamera(x1)); values.insert(Symbol("x1"), GeneralCamera(x1));
Point3 l1; values.insert("l1", l1); Point3 l1; values.insert(Symbol("l1"), l1);
EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values))); EXPECT(assert_equal(Vector_(2, -3.0, 0.0), factor->unwhitenedError(values)));
} }
@ -140,10 +140,9 @@ vector<GeneralCamera> genCameraVariableCalibration() {
} }
shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& X, const vector<Point3>& L) { shared_ptr<Ordering> getOrdering(const vector<GeneralCamera>& X, const vector<Point3>& L) {
list<Symbol> keys; shared_ptr<Ordering> ordering(new Ordering);
for ( size_t i = 0 ; i < L.size() ; ++i ) keys.push_back(Symbol('l', i)) ; for ( size_t i = 0 ; i < L.size() ; ++i ) ordering->push_back(Symbol('l', i)) ;
for ( size_t i = 0 ; i < X.size() ; ++i ) keys.push_back(Symbol('x', i)) ; for ( size_t i = 0 ; i < X.size() ; ++i ) ordering->push_back(Symbol('x', i)) ;
shared_ptr<Ordering> ordering(new Ordering(keys));
return ordering ; return ordering ;
} }

View File

@ -46,6 +46,8 @@ static noiseModel::Gaussian::shared_ptr covariance(
))); )));
//static noiseModel::Gaussian::shared_ptr I3(noiseModel::Unit::Create(3)); //static noiseModel::Gaussian::shared_ptr I3(noiseModel::Unit::Create(3));
const Key kx0 = Symbol("x0"), kx1 = Symbol("x1"), kx2 = Symbol("x2"), kx3 = Symbol("x3"), kx4 = Symbol("x4"), kx5 = Symbol("x5"), kl1 = Symbol("l1");
/* ************************************************************************* */ /* ************************************************************************* */
// Test constraint, small displacement // Test constraint, small displacement
Vector f1(const Pose2& pose1, const Pose2& pose2) { Vector f1(const Pose2& pose1, const Pose2& pose2) {
@ -140,7 +142,7 @@ TEST( Pose2SLAM, linearization )
Vector b = Vector_(3,-0.1/sx,0.1/sy,0.0); Vector b = Vector_(3,-0.1/sx,0.1/sy,0.0);
SharedDiagonal probModel1 = noiseModel::Unit::Create(3); SharedDiagonal probModel1 = noiseModel::Unit::Create(3);
lfg_expected.push_back(JacobianFactor::shared_ptr(new JacobianFactor(ordering["x1"], A1, ordering["x2"], A2, b, probModel1))); lfg_expected.push_back(JacobianFactor::shared_ptr(new JacobianFactor(ordering[kx1], A1, ordering[kx2], A2, b, probModel1)));
CHECK(assert_equal(lfg_expected, *lfg_linearized)); CHECK(assert_equal(lfg_expected, *lfg_linearized));
} }
@ -160,7 +162,7 @@ TEST(Pose2Graph, optimize) {
// Choose an ordering and optimize // Choose an ordering and optimize
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "x0","x1"; *ordering += kx0, kx1;
typedef NonlinearOptimizer<pose2SLAM::Graph> Optimizer; typedef NonlinearOptimizer<pose2SLAM::Graph> Optimizer;
NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15); NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15);
@ -198,7 +200,7 @@ TEST(Pose2Graph, optimizeThreePoses) {
// Choose an ordering // Choose an ordering
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "x0","x1","x2"; *ordering += kx0,kx1,kx2;
// optimize // optimize
NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15); NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15);
@ -241,7 +243,7 @@ TEST_UNSAFE(Pose2SLAM, optimizeCircle) {
// Choose an ordering // Choose an ordering
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "x0","x1","x2","x3","x4","x5"; *ordering += kx0,kx1,kx2,kx3,kx4,kx5;
// optimize // optimize
NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15); NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15);
@ -400,14 +402,14 @@ TEST( Pose2Prior, error )
// Check error at x0, i.e. delta = zero ! // Check error at x0, i.e. delta = zero !
VectorValues delta(VectorValues::Zero(x0.dims(ordering))); VectorValues delta(VectorValues::Zero(x0.dims(ordering)));
delta[ordering["x1"]] = zero(3); delta[ordering[kx1]] = zero(3);
Vector error_at_zero = Vector_(3,0.0,0.0,0.0); Vector error_at_zero = Vector_(3,0.0,0.0,0.0);
CHECK(assert_equal(error_at_zero,factor.whitenedError(x0))); CHECK(assert_equal(error_at_zero,factor.whitenedError(x0)));
CHECK(assert_equal(-error_at_zero,linear->error_vector(delta))); CHECK(assert_equal(-error_at_zero,linear->error_vector(delta)));
// Check error after increasing p2 // Check error after increasing p2
VectorValues addition(VectorValues::Zero(x0.dims(ordering))); VectorValues addition(VectorValues::Zero(x0.dims(ordering)));
addition[ordering["x1"]] = Vector_(3, 0.1, 0.0, 0.0); addition[ordering[kx1]] = Vector_(3, 0.1, 0.0, 0.0);
VectorValues plus = delta + addition; VectorValues plus = delta + addition;
pose2SLAM::Values x1 = x0.retract(plus, ordering); pose2SLAM::Values x1 = x0.retract(plus, ordering);
Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 ! Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 !
@ -441,7 +443,7 @@ TEST( Pose2Prior, linearize )
// Test with numerical derivative // Test with numerical derivative
Matrix numericalH = numericalDerivative11(hprior, priorVal); Matrix numericalH = numericalDerivative11(hprior, priorVal);
CHECK(assert_equal(numericalH,actual->getA(actual->find(ordering["x1"])))); CHECK(assert_equal(numericalH,actual->getA(actual->find(ordering[kx1]))));
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -466,15 +468,15 @@ TEST( Pose2Factor, error )
// Check error at x0, i.e. delta = zero ! // Check error at x0, i.e. delta = zero !
VectorValues delta(x0.dims(ordering)); VectorValues delta(x0.dims(ordering));
delta[ordering["x1"]] = zero(3); delta[ordering[kx1]] = zero(3);
delta[ordering["x2"]] = zero(3); delta[ordering[kx2]] = zero(3);
Vector error_at_zero = Vector_(3,0.0,0.0,0.0); Vector error_at_zero = Vector_(3,0.0,0.0,0.0);
CHECK(assert_equal(error_at_zero,factor.unwhitenedError(x0))); CHECK(assert_equal(error_at_zero,factor.unwhitenedError(x0)));
CHECK(assert_equal(-error_at_zero, linear->error_vector(delta))); CHECK(assert_equal(-error_at_zero, linear->error_vector(delta)));
// Check error after increasing p2 // Check error after increasing p2
VectorValues plus = delta; VectorValues plus = delta;
plus[ordering["x2"]] = Vector_(3, 0.1, 0.0, 0.0); plus[ordering[kx2]] = Vector_(3, 0.1, 0.0, 0.0);
pose2SLAM::Values x1 = x0.retract(plus, ordering); pose2SLAM::Values x1 = x0.retract(plus, ordering);
Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 ! Vector error_at_plus = Vector_(3,0.1/sx,0.0,0.0); // h(x)-z = 0.1 !
CHECK(assert_equal(error_at_plus,factor.whitenedError(x1))); CHECK(assert_equal(error_at_plus,factor.whitenedError(x1)));
@ -542,7 +544,7 @@ TEST( Pose2Factor, linearize )
// expected linear factor // expected linear factor
Ordering ordering(*x0.orderingArbitrary()); Ordering ordering(*x0.orderingArbitrary());
SharedDiagonal probModel1 = noiseModel::Unit::Create(3); SharedDiagonal probModel1 = noiseModel::Unit::Create(3);
JacobianFactor expected(ordering["x1"], expectedH1, ordering["x2"], expectedH2, expected_b, probModel1); JacobianFactor expected(ordering[kx1], expectedH1, ordering[kx2], expectedH2, expected_b, probModel1);
// Actual linearization // Actual linearization
boost::shared_ptr<JacobianFactor> actual = boost::shared_ptr<JacobianFactor> actual =

View File

@ -43,6 +43,8 @@ static Matrix covariance = eye(6);
const double tol=1e-5; const double tol=1e-5;
const Key kx0 = Symbol("x0"), kx1 = Symbol("x1"), kx2 = Symbol("x2"), kx3 = Symbol("x3"), kx4 = Symbol("x4"), kx5 = Symbol("x5");
/* ************************************************************************* */ /* ************************************************************************* */
// test optimization with 6 poses arranged in a hexagon and a loop closure // test optimization with 6 poses arranged in a hexagon and a loop closure
TEST(Pose3Graph, optimizeCircle) { TEST(Pose3Graph, optimizeCircle) {
@ -76,7 +78,7 @@ TEST(Pose3Graph, optimizeCircle) {
// Choose an ordering and optimize // Choose an ordering and optimize
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "x0","x1","x2","x3","x4","x5"; *ordering += kx0,kx1,kx2,kx3,kx4,kx5;
NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15); NonlinearOptimizationParameters::shared_ptr params = NonlinearOptimizationParameters::newDecreaseThresholds(1e-15, 1e-15);
pose3SLAM::Optimizer optimizer0(fg, initial, ordering, params); pose3SLAM::Optimizer optimizer0(fg, initial, ordering, params);
pose3SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt(); pose3SLAM::Optimizer optimizer = optimizer0.levenbergMarquardt();

View File

@ -40,6 +40,8 @@ static Cal3_S2 K(fov,w,h);
static SharedNoiseModel sigma(noiseModel::Unit::Create(1)); static SharedNoiseModel sigma(noiseModel::Unit::Create(1));
static shared_ptrK sK(new Cal3_S2(K)); static shared_ptrK sK(new Cal3_S2(K));
const Key kx1 = Symbol("x1"), kl1 = Symbol("l1");
// make cameras // make cameras
/* ************************************************************************* */ /* ************************************************************************* */
@ -62,12 +64,12 @@ TEST( ProjectionFactor, error )
DOUBLES_EQUAL(4.5,factor->error(config),1e-9); DOUBLES_EQUAL(4.5,factor->error(config),1e-9);
// Check linearize // Check linearize
Ordering ordering; ordering += "x1","l1"; Ordering ordering; ordering += kx1,kl1;
Matrix Ax1 = Matrix_(2, 6, 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.); Matrix Ax1 = Matrix_(2, 6, 0., -554.256, 0., -92.376, 0., 0., 554.256, 0., 0., 0., -92.376, 0.);
Matrix Al1 = Matrix_(2, 3, 92.376, 0., 0., 0., 92.376, 0.); Matrix Al1 = Matrix_(2, 3, 92.376, 0., 0., 0., 92.376, 0.);
Vector b = Vector_(2,3.,0.); Vector b = Vector_(2,3.,0.);
SharedDiagonal probModel1 = noiseModel::Unit::Create(2); SharedDiagonal probModel1 = noiseModel::Unit::Create(2);
JacobianFactor expected(ordering["x1"], Ax1, ordering["l1"], Al1, b, probModel1); JacobianFactor expected(ordering[kx1], Ax1, ordering[kl1], Al1, b, probModel1);
JacobianFactor::shared_ptr actual = JacobianFactor::shared_ptr actual =
boost::dynamic_pointer_cast<JacobianFactor>(factor->linearize(config, ordering)); boost::dynamic_pointer_cast<JacobianFactor>(factor->linearize(config, ordering));
CHECK(assert_equal(expected,*actual,1e-3)); CHECK(assert_equal(expected,*actual,1e-3));
@ -85,8 +87,8 @@ TEST( ProjectionFactor, error )
Point3 t2(1,1,-5); Pose3 x2(R,t2); expected_config.insert(PoseKey(1), x2); Point3 t2(1,1,-5); Pose3 x2(R,t2); expected_config.insert(PoseKey(1), x2);
Point3 l2(1,2,3); expected_config.insert(PointKey(1), l2); Point3 l2(1,2,3); expected_config.insert(PointKey(1), l2);
VectorValues delta(expected_config.dims(ordering)); VectorValues delta(expected_config.dims(ordering));
delta[ordering["x1"]] = Vector_(6, 0.,0.,0., 1.,1.,1.); delta[ordering[kx1]] = Vector_(6, 0.,0.,0., 1.,1.,1.);
delta[ordering["l1"]] = Vector_(3, 1.,2.,3.); delta[ordering[kl1]] = Vector_(3, 1.,2.,3.);
Values actual_config = config.retract(delta, ordering); Values actual_config = config.retract(delta, ordering);
CHECK(assert_equal(expected_config,actual_config,1e-9)); CHECK(assert_equal(expected_config,actual_config,1e-9));
} }

View File

@ -51,7 +51,7 @@ BOOST_CLASS_EXPORT_GUID(gtsam::SharedDiagonal, "gtsam_SharedDiagonal");
TEST (Serialization, smallExample_linear) { TEST (Serialization, smallExample_linear) {
using namespace example; using namespace example;
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += Symbol("x1"),Symbol("x2"),Symbol("l1");
GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
EXPECT(equalsObj(ordering)); EXPECT(equalsObj(ordering));
EXPECT(equalsXML(ordering)); EXPECT(equalsXML(ordering));

View File

@ -101,7 +101,7 @@ TEST( Graph, optimizeLM)
// Create an ordering of the variables // Create an ordering of the variables
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "l1","l2","l3","l4","x1","x2"; *ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2);
// Create an optimizer and check its error // Create an optimizer and check its error
// We expect the initial to be zero because config is the ground truth // We expect the initial to be zero because config is the ground truth
@ -138,7 +138,7 @@ TEST( Graph, optimizeLM2)
// Create an ordering of the variables // Create an ordering of the variables
shared_ptr<Ordering> ordering(new Ordering); shared_ptr<Ordering> ordering(new Ordering);
*ordering += "l1","l2","l3","l4","x1","x2"; *ordering += PointKey(1),PointKey(2),PointKey(3),PointKey(4),PoseKey(1),PoseKey(2);
// Create an optimizer and check its error // Create an optimizer and check its error
// We expect the initial to be zero because config is the ground truth // We expect the initial to be zero because config is the ground truth
@ -204,11 +204,11 @@ TEST( Values, update_with_large_delta) {
Ordering largeOrdering; Ordering largeOrdering;
Values largeValues = init; Values largeValues = init;
largeValues.insert(PoseKey(2), Pose3()); largeValues.insert(PoseKey(2), Pose3());
largeOrdering += "x1","l1","x2"; largeOrdering += PoseKey(1),PointKey(1),PoseKey(2);
VectorValues delta(largeValues.dims(largeOrdering)); VectorValues delta(largeValues.dims(largeOrdering));
delta[largeOrdering["x1"]] = Vector_(6, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1); delta[largeOrdering[PoseKey(1)]] = Vector_(6, 0.0, 0.0, 0.0, 0.1, 0.1, 0.1);
delta[largeOrdering["l1"]] = Vector_(3, 0.1, 0.1, 0.1); delta[largeOrdering[PointKey(1)]] = Vector_(3, 0.1, 0.1, 0.1);
delta[largeOrdering["x2"]] = Vector_(6, 0.0, 0.0, 0.0, 100.1, 4.1, 9.1); delta[largeOrdering[PoseKey(2)]] = Vector_(6, 0.0, 0.0, 0.0, 100.1, 4.1, 9.1);
Values actual = init.retract(delta, largeOrdering); Values actual = init.retract(delta, largeOrdering);
CHECK(assert_equal(expected,actual)); CHECK(assert_equal(expected,actual));

View File

@ -67,8 +67,8 @@ namespace visualSLAM {
} }
/// print out graph /// print out graph
void print(const std::string& s = "") const { void print(const std::string& s = "", const KeyFormatter& keyFormatter = DefaultKeyFormatter) const {
NonlinearFactorGraph::print(s); NonlinearFactorGraph::print(s, keyFormatter);
} }
/// check if two graphs are equal /// check if two graphs are equal

View File

@ -88,12 +88,12 @@ TEST( ExtendedKalmanFilter, linear ) {
// Create Motion Model Factor // Create Motion Model Factor
class NonlinearMotionModel : public NonlinearFactor2<Point2,Point2> { class NonlinearMotionModel : public NoiseModelFactor2<Point2,Point2> {
public: public:
typedef Point2 T; typedef Point2 T;
private: private:
typedef NonlinearFactor2<Point2, Point2> Base; typedef NoiseModelFactor2<Point2, Point2> Base;
typedef NonlinearMotionModel This; typedef NonlinearMotionModel This;
protected: protected:
@ -155,8 +155,8 @@ public:
/* print */ /* print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearMotionModel\n"; std::cout << s << ": NonlinearMotionModel\n";
std::cout << " TestKey1: " << (std::string) key1() << std::endl; std::cout << " TestKey1: " << DefaultKeyFormatter(key1()) << std::endl;
std::cout << " TestKey2: " << (std::string) key2() << std::endl; std::cout << " TestKey2: " << DefaultKeyFormatter(key2()) << std::endl;
} }
/** Check if two factors are equal. Note type is IndexFactor and needs cast. */ /** Check if two factors are equal. Note type is IndexFactor and needs cast. */
@ -235,13 +235,13 @@ public:
}; };
// Create Measurement Model Factor // Create Measurement Model Factor
class NonlinearMeasurementModel : public NonlinearFactor1<Point2> { class NonlinearMeasurementModel : public NoiseModelFactor1<Point2> {
public: public:
typedef Point2 T; typedef Point2 T;
private: private:
typedef NonlinearFactor1<Point2> Base; typedef NoiseModelFactor1<Point2> Base;
typedef NonlinearMeasurementModel This; typedef NonlinearMeasurementModel This;
protected: protected:
@ -293,7 +293,7 @@ public:
/* print */ /* print */
virtual void print(const std::string& s = "") const { virtual void print(const std::string& s = "") const {
std::cout << s << ": NonlinearMeasurementModel\n"; std::cout << s << ": NonlinearMeasurementModel\n";
std::cout << " TestKey: " << (std::string) key() << std::endl; std::cout << " TestKey: " << DefaultKeyFormatter(key()) << std::endl;
} }
/** Check if two factors are equal. Note type is IndexFactor and needs cast. */ /** Check if two factors are equal. Note type is IndexFactor and needs cast. */

View File

@ -26,7 +26,7 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx3 to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
@ -44,19 +44,21 @@ static SharedDiagonal
sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2), sigma0_1 = sharedSigma(2,0.1), sigma_02 = sharedSigma(2,0.2),
constraintModel = noiseModel::Constrained::All(2); constraintModel = noiseModel::Constrained::All(2);
const Key kx1 = Symbol("x1"), kx2 = Symbol("x2"), kl1 = Symbol("l1");
/* ************************************************************************* */ /* ************************************************************************* */
TEST( GaussianFactor, linearFactor ) TEST( GaussianFactor, linearFactor )
{ {
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
Matrix I = eye(2); Matrix I = eye(2);
Vector b = Vector_(2, 2.0, -1.0); Vector b = Vector_(2, 2.0, -1.0);
JacobianFactor expected(ordering["x1"], -10*I,ordering["x2"], 10*I, b, noiseModel::Unit::Create(2)); JacobianFactor expected(ordering[kx1], -10*I,ordering[kx2], 10*I, b, noiseModel::Unit::Create(2));
// create a small linear factor graph // create a small linear factor graph
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering); FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
// get the factor "f2" from the factor graph // get the factor kf2 from the factor graph
JacobianFactor::shared_ptr lf = fg[1]; JacobianFactor::shared_ptr lf = fg[1];
// check if the two factors are the same // check if the two factors are the same
@ -66,26 +68,26 @@ TEST( GaussianFactor, linearFactor )
///* ************************************************************************* */ ///* ************************************************************************* */
// SL-FIX TEST( GaussianFactor, keys ) // SL-FIX TEST( GaussianFactor, keys )
//{ //{
// // get the factor "f2" from the small linear factor graph // // get the factor kf2 from the small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// GaussianFactor::shared_ptr lf = fg[1]; // GaussianFactor::shared_ptr lf = fg[1];
// list<Symbol> expected; // list<Symbol> expected;
// expected.push_back("x1"); // expected.push_back(kx1);
// expected.push_back("x2"); // expected.push_back(kx2);
// EXPECT(lf->keys() == expected); // EXPECT(lf->keys() == expected);
//} //}
///* ************************************************************************* */ ///* ************************************************************************* */
// SL-FIX TEST( GaussianFactor, dimensions ) // SL-FIX TEST( GaussianFactor, dimensions )
//{ //{
// // get the factor "f2" from the small linear factor graph // // get the factor kf2 from the small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// //
// // Check a single factor // // Check a single factor
// Dimensions expected; // Dimensions expected;
// insert(expected)("x1", 2)("x2", 2); // insert(expected)(kx1, 2)(kx2, 2);
// Dimensions actual = fg[1]->dimensions(); // Dimensions actual = fg[1]->dimensions();
// EXPECT(expected==actual); // EXPECT(expected==actual);
//} //}
@ -94,12 +96,12 @@ TEST( GaussianFactor, linearFactor )
TEST( GaussianFactor, getDim ) TEST( GaussianFactor, getDim )
{ {
// get a factor // get a factor
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
GaussianFactor::shared_ptr factor = fg[0]; GaussianFactor::shared_ptr factor = fg[0];
// get the size of a variable // get the size of a variable
size_t actual = factor->getDim(factor->find(ordering["x1"])); size_t actual = factor->getDim(factor->find(ordering[kx1]));
// verify // verify
size_t expected = 2; size_t expected = 2;
@ -110,7 +112,7 @@ TEST( GaussianFactor, getDim )
// SL-FIX TEST( GaussianFactor, combine ) // SL-FIX TEST( GaussianFactor, combine )
//{ //{
// // create a small linear factor graph // // create a small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// //
// // get two factors from it and insert the factors into a vector // // get two factors from it and insert the factors into a vector
@ -155,9 +157,9 @@ TEST( GaussianFactor, getDim )
// //
// // use general constructor for making arbitrary factors // // use general constructor for making arbitrary factors
// vector<pair<Symbol, Matrix> > meas; // vector<pair<Symbol, Matrix> > meas;
// meas.push_back(make_pair("x2", Ax2)); // meas.push_back(make_pair(kx2, Ax2));
// meas.push_back(make_pair("l1", Al1)); // meas.push_back(make_pair(kl1, Al1));
// meas.push_back(make_pair("x1", Ax1)); // meas.push_back(make_pair(kx1, Ax1));
// GaussianFactor expected(meas, b2, noiseModel::Diagonal::Sigmas(ones(4))); // GaussianFactor expected(meas, b2, noiseModel::Diagonal::Sigmas(ones(4)));
// EXPECT(assert_equal(expected,combined)); // EXPECT(assert_equal(expected,combined));
//} //}
@ -166,7 +168,7 @@ TEST( GaussianFactor, getDim )
TEST( GaussianFactor, error ) TEST( GaussianFactor, error )
{ {
// create a small linear factor graph // create a small linear factor graph
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// get the first factor from the factor graph // get the first factor from the factor graph
@ -175,7 +177,7 @@ TEST( GaussianFactor, error )
// check the error of the first factor with noisy config // check the error of the first factor with noisy config
VectorValues cfg = createZeroDelta(ordering); VectorValues cfg = createZeroDelta(ordering);
// calculate the error from the factor "f1" // calculate the error from the factor kf1
// note the error is the same as in testNonlinearFactor // note the error is the same as in testNonlinearFactor
double actual = lf->error(cfg); double actual = lf->error(cfg);
DOUBLES_EQUAL( 1.0, actual, 0.00000001 ); DOUBLES_EQUAL( 1.0, actual, 0.00000001 );
@ -185,7 +187,7 @@ TEST( GaussianFactor, error )
// SL-FIX TEST( GaussianFactor, eliminate ) // SL-FIX TEST( GaussianFactor, eliminate )
//{ //{
// // create a small linear factor graph // // create a small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// //
// // get two factors from it and insert the factors into a vector // // get two factors from it and insert the factors into a vector
@ -199,7 +201,7 @@ TEST( GaussianFactor, error )
// // eliminate the combined factor // // eliminate the combined factor
// GaussianConditional::shared_ptr actualCG; // GaussianConditional::shared_ptr actualCG;
// GaussianFactor::shared_ptr actualLF; // GaussianFactor::shared_ptr actualLF;
// boost::tie(actualCG,actualLF) = combined.eliminate("x2"); // boost::tie(actualCG,actualLF) = combined.eliminate(kx2);
// //
// // create expected Conditional Gaussian // // create expected Conditional Gaussian
// Matrix I = eye(2)*sqrt(125.0); // Matrix I = eye(2)*sqrt(125.0);
@ -208,14 +210,14 @@ TEST( GaussianFactor, error )
// //
// // Check the conditional Gaussian // // Check the conditional Gaussian
// GaussianConditional // GaussianConditional
// expectedCG("x2", d, R11, "l1", S12, "x1", S13, repeat(2, 1.0)); // expectedCG(kx2, d, R11, kl1, S12, kx1, S13, repeat(2, 1.0));
// //
// // the expected linear factor // // the expected linear factor
// I = eye(2)/0.2236; // I = eye(2)/0.2236;
// Matrix Bl1 = I, Bx1 = -I; // Matrix Bl1 = I, Bx1 = -I;
// Vector b1 = I*Vector_(2,0.0,0.2); // Vector b1 = I*Vector_(2,0.0,0.2);
// //
// GaussianFactor expectedLF("l1", Bl1, "x1", Bx1, b1, repeat(2,1.0)); // GaussianFactor expectedLF(kl1, Bl1, kx1, Bx1, b1, repeat(2,1.0));
// //
// // check if the result matches // // check if the result matches
// EXPECT(assert_equal(expectedCG,*actualCG,1e-3)); // EXPECT(assert_equal(expectedCG,*actualCG,1e-3));
@ -226,17 +228,17 @@ TEST( GaussianFactor, error )
TEST( GaussianFactor, matrix ) TEST( GaussianFactor, matrix )
{ {
// create a small linear factor graph // create a small linear factor graph
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering); FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
// get the factor "f2" from the factor graph // get the factor kf2 from the factor graph
//GaussianFactor::shared_ptr lf = fg[1]; // NOTE: using the older version //GaussianFactor::shared_ptr lf = fg[1]; // NOTE: using the older version
Vector b2 = Vector_(2, 0.2, -0.1); Vector b2 = Vector_(2, 0.2, -0.1);
Matrix I = eye(2); Matrix I = eye(2);
// render with a given ordering // render with a given ordering
Ordering ord; Ordering ord;
ord += "x1","x2"; ord += kx1,kx2;
JacobianFactor::shared_ptr lf(new JacobianFactor(ord["x1"], -I, ord["x2"], I, b2, sigma0_1)); JacobianFactor::shared_ptr lf(new JacobianFactor(ord[kx1], -I, ord[kx2], I, b2, sigma0_1));
// Test whitened version // Test whitened version
Matrix A_act1; Vector b_act1; Matrix A_act1; Vector b_act1;
@ -274,17 +276,17 @@ TEST( GaussianFactor, matrix )
TEST( GaussianFactor, matrix_aug ) TEST( GaussianFactor, matrix_aug )
{ {
// create a small linear factor graph // create a small linear factor graph
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering); FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
// get the factor "f2" from the factor graph // get the factor kf2 from the factor graph
//GaussianFactor::shared_ptr lf = fg[1]; //GaussianFactor::shared_ptr lf = fg[1];
Vector b2 = Vector_(2, 0.2, -0.1); Vector b2 = Vector_(2, 0.2, -0.1);
Matrix I = eye(2); Matrix I = eye(2);
// render with a given ordering // render with a given ordering
Ordering ord; Ordering ord;
ord += "x1","x2"; ord += kx1,kx2;
JacobianFactor::shared_ptr lf(new JacobianFactor(ord["x1"], -I, ord["x2"], I, b2, sigma0_1)); JacobianFactor::shared_ptr lf(new JacobianFactor(ord[kx1], -I, ord[kx2], I, b2, sigma0_1));
// Test unwhitened version // Test unwhitened version
@ -325,15 +327,15 @@ void print(const list<T>& i) {
// SL-FIX TEST( GaussianFactor, sparse ) // SL-FIX TEST( GaussianFactor, sparse )
//{ //{
// // create a small linear factor graph // // create a small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// //
// // get the factor "f2" from the factor graph // // get the factor kf2 from the factor graph
// GaussianFactor::shared_ptr lf = fg[1]; // GaussianFactor::shared_ptr lf = fg[1];
// //
// // render with a given ordering // // render with a given ordering
// Ordering ord; // Ordering ord;
// ord += "x1","x2"; // ord += kx1,kx2;
// //
// list<int> i,j; // list<int> i,j;
// list<double> s; // list<double> s;
@ -355,15 +357,15 @@ void print(const list<T>& i) {
// SL-FIX TEST( GaussianFactor, sparse2 ) // SL-FIX TEST( GaussianFactor, sparse2 )
//{ //{
// // create a small linear factor graph // // create a small linear factor graph
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx1,kx2,kl1;
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// //
// // get the factor "f2" from the factor graph // // get the factor kf2 from the factor graph
// GaussianFactor::shared_ptr lf = fg[1]; // GaussianFactor::shared_ptr lf = fg[1];
// //
// // render with a given ordering // // render with a given ordering
// Ordering ord; // Ordering ord;
// ord += "x2","l1","x1"; // ord += kx2,kl1,kx1;
// //
// list<int> i,j; // list<int> i,j;
// list<double> s; // list<double> s;
@ -385,7 +387,7 @@ void print(const list<T>& i) {
TEST( GaussianFactor, size ) TEST( GaussianFactor, size )
{ {
// create a linear factor graph // create a linear factor graph
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx1,kx2,kl1;
GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// get some factors from the graph // get some factors from the graph

View File

@ -28,7 +28,7 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
@ -44,10 +44,13 @@ using namespace example;
double tol=1e-5; double tol=1e-5;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
/* ************************************************************************* */ /* ************************************************************************* */
TEST( GaussianFactorGraph, equals ) { TEST( GaussianFactorGraph, equals ) {
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx(1),kx(2),kl(1);
GaussianFactorGraph fg = createGaussianFactorGraph(ordering); GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
GaussianFactorGraph fg2 = createGaussianFactorGraph(ordering); GaussianFactorGraph fg2 = createGaussianFactorGraph(ordering);
EXPECT(fg.equals(fg2)); EXPECT(fg.equals(fg2));
@ -55,7 +58,7 @@ TEST( GaussianFactorGraph, equals ) {
/* ************************************************************************* */ /* ************************************************************************* */
//TEST( GaussianFactorGraph, error ) { //TEST( GaussianFactorGraph, error ) {
// Ordering ordering; ordering += "x1","x2","l1"; // Ordering ordering; ordering += kx(1),kx(2),kl(1);
// FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering); // FactorGraph<JacobianFactor> fg = createGaussianFactorGraph(ordering);
// VectorValues cfg = createZeroDelta(ordering); // VectorValues cfg = createZeroDelta(ordering);
// //
@ -73,10 +76,10 @@ TEST( GaussianFactorGraph, equals ) {
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// //
// set<Symbol> separator = fg.find_separator("x2"); // set<Symbol> separator = fg.find_separator(kx(2));
// set<Symbol> expected; // set<Symbol> expected;
// expected.insert("x1"); // expected.insert(kx(1));
// expected.insert("l1"); // expected.insert(kl(1));
// //
// EXPECT(separator.size()==expected.size()); // EXPECT(separator.size()==expected.size());
// set<Symbol>::iterator it1 = separator.begin(), it2 = expected.begin(); // set<Symbol>::iterator it1 = separator.begin(), it2 = expected.begin();
@ -91,7 +94,7 @@ TEST( GaussianFactorGraph, equals ) {
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// //
// // combine all factors // // combine all factors
// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,"x1"); // GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(1));
// //
// // the expected linear factor // // the expected linear factor
// Matrix Al1 = Matrix_(6,2, // Matrix Al1 = Matrix_(6,2,
@ -131,11 +134,11 @@ TEST( GaussianFactorGraph, equals ) {
// b(5) = 1; // b(5) = 1;
// //
// vector<pair<Symbol, Matrix> > meas; // vector<pair<Symbol, Matrix> > meas;
// meas.push_back(make_pair("l1", Al1)); // meas.push_back(make_pair(kl(1), Al1));
// meas.push_back(make_pair("x1", Ax1)); // meas.push_back(make_pair(kx(1), Ax1));
// meas.push_back(make_pair("x2", Ax2)); // meas.push_back(make_pair(kx(2), Ax2));
// GaussianFactor expected(meas, b, ones(6)); // GaussianFactor expected(meas, b, ones(6));
// //GaussianFactor expected("l1", Al1, "x1", Ax1, "x2", Ax2, b); // //GaussianFactor expected(kl(1), Al1, kx(1), Ax1, kx(2), Ax2, b);
// //
// // check if the two factors are the same // // check if the two factors are the same
// EXPECT(assert_equal(expected,*actual)); // EXPECT(assert_equal(expected,*actual));
@ -148,7 +151,7 @@ TEST( GaussianFactorGraph, equals ) {
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// //
// // combine all factors // // combine all factors
// GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,"x2"); // GaussianFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(2));
// //
// // the expected linear factor // // the expected linear factor
// Matrix Al1 = Matrix_(4,2, // Matrix Al1 = Matrix_(4,2,
@ -183,9 +186,9 @@ TEST( GaussianFactorGraph, equals ) {
// b(3) = 1.5; // b(3) = 1.5;
// //
// vector<pair<Symbol, Matrix> > meas; // vector<pair<Symbol, Matrix> > meas;
// meas.push_back(make_pair("l1", Al1)); // meas.push_back(make_pair(kl(1), Al1));
// meas.push_back(make_pair("x1", Ax1)); // meas.push_back(make_pair(kx(1), Ax1));
// meas.push_back(make_pair("x2", Ax2)); // meas.push_back(make_pair(kx(2), Ax2));
// GaussianFactor expected(meas, b, ones(4)); // GaussianFactor expected(meas, b, ones(4));
// //
// // check if the two factors are the same // // check if the two factors are the same
@ -195,14 +198,14 @@ TEST( GaussianFactorGraph, equals ) {
///* ************************************************************************* */ ///* ************************************************************************* */
//TEST( GaussianFactorGraph, eliminateOne_x1 ) //TEST( GaussianFactorGraph, eliminateOne_x1 )
//{ //{
// Ordering ordering; ordering += "x1","l1","x2"; // Ordering ordering; ordering += kx(1),kl(1),kx(2);
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1); // GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1);
// //
// // create expected Conditional Gaussian // // create expected Conditional Gaussian
// Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; // Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I;
// Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2); // Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2);
// GaussianConditional expected(ordering["x1"],15*d,R11,ordering["l1"],S12,ordering["x2"],S13,sigma); // GaussianConditional expected(ordering[kx(1)],15*d,R11,ordering[kl(1)],S12,ordering[kx(2)],S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -210,7 +213,7 @@ TEST( GaussianFactorGraph, equals ) {
///* ************************************************************************* */ ///* ************************************************************************* */
//TEST( GaussianFactorGraph, eliminateOne_x2 ) //TEST( GaussianFactorGraph, eliminateOne_x2 )
//{ //{
// Ordering ordering; ordering += "x2","l1","x1"; // Ordering ordering; ordering += kx(2),kl(1),kx(1);
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1); // GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1);
// //
@ -218,7 +221,7 @@ TEST( GaussianFactorGraph, equals ) {
// double sig = 0.0894427; // double sig = 0.0894427;
// Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; // Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I;
// Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2); // Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2);
// GaussianConditional expected(ordering["x2"],d,R11,ordering["l1"],S12,ordering["x1"],S13,sigma); // GaussianConditional expected(ordering[kx(2)],d,R11,ordering[kl(1)],S12,ordering[kx(1)],S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -226,7 +229,7 @@ TEST( GaussianFactorGraph, equals ) {
///* ************************************************************************* */ ///* ************************************************************************* */
//TEST( GaussianFactorGraph, eliminateOne_l1 ) //TEST( GaussianFactorGraph, eliminateOne_l1 )
//{ //{
// Ordering ordering; ordering += "l1","x1","x2"; // Ordering ordering; ordering += kl(1),kx(1),kx(2);
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1); // GaussianConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, 1);
// //
@ -234,7 +237,7 @@ TEST( GaussianFactorGraph, equals ) {
// double sig = sqrt(2)/10.; // double sig = sqrt(2)/10.;
// Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; // Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I;
// Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2); // Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2);
// GaussianConditional expected(ordering["l1"],d,R11,ordering["x1"],S12,ordering["x2"],S13,sigma); // GaussianConditional expected(ordering[kl(1)],d,R11,ordering[kx(1)],S12,ordering[kx(2)],S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -243,12 +246,12 @@ TEST( GaussianFactorGraph, equals ) {
//TEST( GaussianFactorGraph, eliminateOne_x1_fast ) //TEST( GaussianFactorGraph, eliminateOne_x1_fast )
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// GaussianConditional::shared_ptr actual = fg.eliminateOne("x1", false); // GaussianConditional::shared_ptr actual = fg.eliminateOne(kx(1), false);
// //
// // create expected Conditional Gaussian // // create expected Conditional Gaussian
// Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I; // Matrix I = 15*eye(2), R11 = I, S12 = -0.111111*I, S13 = -0.444444*I;
// Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2); // Vector d = Vector_(2, -0.133333, -0.0222222), sigma = ones(2);
// GaussianConditional expected("x1",15*d,R11,"l1",S12,"x2",S13,sigma); // GaussianConditional expected(kx(1),15*d,R11,kl(1),S12,kx(2),S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -257,13 +260,13 @@ TEST( GaussianFactorGraph, equals ) {
//TEST( GaussianFactorGraph, eliminateOne_x2_fast ) //TEST( GaussianFactorGraph, eliminateOne_x2_fast )
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// GaussianConditional::shared_ptr actual = fg.eliminateOne("x2", false); // GaussianConditional::shared_ptr actual = fg.eliminateOne(kx(2), false);
// //
// // create expected Conditional Gaussian // // create expected Conditional Gaussian
// double sig = 0.0894427; // double sig = 0.0894427;
// Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I; // Matrix I = eye(2)/sig, R11 = I, S12 = -0.2*I, S13 = -0.8*I;
// Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2); // Vector d = Vector_(2, 0.2, -0.14)/sig, sigma = ones(2);
// GaussianConditional expected("x2",d,R11,"l1",S12,"x1",S13,sigma); // GaussianConditional expected(kx(2),d,R11,kl(1),S12,kx(1),S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -272,13 +275,13 @@ TEST( GaussianFactorGraph, equals ) {
//TEST( GaussianFactorGraph, eliminateOne_l1_fast ) //TEST( GaussianFactorGraph, eliminateOne_l1_fast )
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// GaussianConditional::shared_ptr actual = fg.eliminateOne("l1", false); // GaussianConditional::shared_ptr actual = fg.eliminateOne(kl(1), false);
// //
// // create expected Conditional Gaussian // // create expected Conditional Gaussian
// double sig = sqrt(2)/10.; // double sig = sqrt(2)/10.;
// Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I; // Matrix I = eye(2)/sig, R11 = I, S12 = -0.5*I, S13 = -0.5*I;
// Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2); // Vector d = Vector_(2, -0.1, 0.25)/sig, sigma = ones(2);
// GaussianConditional expected("l1",d,R11,"x1",S12,"x2",S13,sigma); // GaussianConditional expected(kl(1),d,R11,kx(1),S12,kx(2),S13,sigma);
// //
// EXPECT(assert_equal(expected,*actual,tol)); // EXPECT(assert_equal(expected,*actual,tol));
//} //}
@ -290,18 +293,18 @@ TEST( GaussianFactorGraph, eliminateAll )
Matrix I = eye(2); Matrix I = eye(2);
Ordering ordering; Ordering ordering;
ordering += "x2","l1","x1"; ordering += kx(2),kl(1),kx(1);
Vector d1 = Vector_(2, -0.1,-0.1); Vector d1 = Vector_(2, -0.1,-0.1);
GaussianBayesNet expected = simpleGaussian(ordering["x1"],d1,0.1); GaussianBayesNet expected = simpleGaussian(ordering[kx(1)],d1,0.1);
double sig1 = 0.149071; double sig1 = 0.149071;
Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2); Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2);
push_front(expected,ordering["l1"],d2, I/sig1,ordering["x1"], (-1)*I/sig1,sigma2); push_front(expected,ordering[kl(1)],d2, I/sig1,ordering[kx(1)], (-1)*I/sig1,sigma2);
double sig2 = 0.0894427; double sig2 = 0.0894427;
Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2); Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2);
push_front(expected,ordering["x2"],d3, I/sig2,ordering["l1"], (-0.2)*I/sig2, ordering["x1"], (-0.8)*I/sig2, sigma3); push_front(expected,ordering[kx(2)],d3, I/sig2,ordering[kl(1)], (-0.2)*I/sig2, ordering[kx(1)], (-0.8)*I/sig2, sigma3);
// Check one ordering // Check one ordering
GaussianFactorGraph fg1 = createGaussianFactorGraph(ordering); GaussianFactorGraph fg1 = createGaussianFactorGraph(ordering);
@ -319,20 +322,20 @@ TEST( GaussianFactorGraph, eliminateAll )
// Matrix I = eye(2); // Matrix I = eye(2);
// //
// Vector d1 = Vector_(2, -0.1,-0.1); // Vector d1 = Vector_(2, -0.1,-0.1);
// GaussianBayesNet expected = simpleGaussian("x1",d1,0.1); // GaussianBayesNet expected = simpleGaussian(kx(1),d1,0.1);
// //
// double sig1 = 0.149071; // double sig1 = 0.149071;
// Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2); // Vector d2 = Vector_(2, 0.0, 0.2)/sig1, sigma2 = ones(2);
// push_front(expected,"l1",d2, I/sig1,"x1", (-1)*I/sig1,sigma2); // push_front(expected,kl(1),d2, I/sig1,kx(1), (-1)*I/sig1,sigma2);
// //
// double sig2 = 0.0894427; // double sig2 = 0.0894427;
// Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2); // Vector d3 = Vector_(2, 0.2, -0.14)/sig2, sigma3 = ones(2);
// push_front(expected,"x2",d3, I/sig2,"l1", (-0.2)*I/sig2, "x1", (-0.8)*I/sig2, sigma3); // push_front(expected,kx(2),d3, I/sig2,kl(1), (-0.2)*I/sig2, kx(1), (-0.8)*I/sig2, sigma3);
// //
// // Check one ordering // // Check one ordering
// GaussianFactorGraph fg1 = createGaussianFactorGraph(); // GaussianFactorGraph fg1 = createGaussianFactorGraph();
// Ordering ordering; // Ordering ordering;
// ordering += "x2","l1","x1"; // ordering += kx(2),kl(1),kx(1);
// GaussianBayesNet actual = fg1.eliminate(ordering, false); // GaussianBayesNet actual = fg1.eliminate(ordering, false);
// EXPECT(assert_equal(expected,actual,tol)); // EXPECT(assert_equal(expected,actual,tol));
//} //}
@ -340,16 +343,16 @@ TEST( GaussianFactorGraph, eliminateAll )
///* ************************************************************************* */ ///* ************************************************************************* */
//TEST( GaussianFactorGraph, add_priors ) //TEST( GaussianFactorGraph, add_priors )
//{ //{
// Ordering ordering; ordering += "l1","x1","x2"; // Ordering ordering; ordering += kl(1),kx(1),kx(2);
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
// GaussianFactorGraph actual = fg.add_priors(3, vector<size_t>(3,2)); // GaussianFactorGraph actual = fg.add_priors(3, vector<size_t>(3,2));
// GaussianFactorGraph expected = createGaussianFactorGraph(ordering); // GaussianFactorGraph expected = createGaussianFactorGraph(ordering);
// Matrix A = eye(2); // Matrix A = eye(2);
// Vector b = zero(2); // Vector b = zero(2);
// SharedDiagonal sigma = sharedSigma(2,3.0); // SharedDiagonal sigma = sharedSigma(2,3.0);
// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering["l1"],A,b,sigma))); // expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kl(1)],A,b,sigma)));
// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering["x1"],A,b,sigma))); // expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kx(1)],A,b,sigma)));
// expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering["x2"],A,b,sigma))); // expected.push_back(GaussianFactor::shared_ptr(new JacobianFactor(ordering[kx(2)],A,b,sigma)));
// EXPECT(assert_equal(expected,actual)); // EXPECT(assert_equal(expected,actual));
//} //}
@ -357,7 +360,7 @@ TEST( GaussianFactorGraph, eliminateAll )
TEST( GaussianFactorGraph, copying ) TEST( GaussianFactorGraph, copying )
{ {
// Create a graph // Create a graph
Ordering ordering; ordering += "x2","l1","x1"; Ordering ordering; ordering += kx(2),kl(1),kx(1);
GaussianFactorGraph actual = createGaussianFactorGraph(ordering); GaussianFactorGraph actual = createGaussianFactorGraph(ordering);
// Copy the graph ! // Copy the graph !
@ -378,7 +381,7 @@ TEST( GaussianFactorGraph, copying )
//{ //{
// // render with a given ordering // // render with a given ordering
// Ordering ord; // Ordering ord;
// ord += "x2","l1","x1"; // ord += kx(2),kl(1),kx(1);
// //
// // Create a graph // // Create a graph
// GaussianFactorGraph fg = createGaussianFactorGraph(ordering); // GaussianFactorGraph fg = createGaussianFactorGraph(ordering);
@ -417,7 +420,7 @@ TEST( GaussianFactorGraph, copying )
TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet ) TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet )
{ {
Ordering ord; Ordering ord;
ord += "x2","l1","x1"; ord += kx(2),kl(1),kx(1);
GaussianFactorGraph fg = createGaussianFactorGraph(ord); GaussianFactorGraph fg = createGaussianFactorGraph(ord);
// render with a given ordering // render with a given ordering
@ -437,20 +440,20 @@ TEST( GaussianFactorGraph, CONSTRUCTOR_GaussianBayesNet )
/* ************************************************************************* */ /* ************************************************************************* */
TEST( GaussianFactorGraph, getOrdering) TEST( GaussianFactorGraph, getOrdering)
{ {
Ordering original; original += "l1","x1","x2"; Ordering original; original += kl(1),kx(1),kx(2);
FactorGraph<IndexFactor> symbolic(createGaussianFactorGraph(original)); FactorGraph<IndexFactor> symbolic(createGaussianFactorGraph(original));
Permutation perm(*Inference::PermutationCOLAMD(VariableIndex(symbolic))); Permutation perm(*Inference::PermutationCOLAMD(VariableIndex(symbolic)));
Ordering actual = original; actual.permuteWithInverse((*perm.inverse())); Ordering actual = original; actual.permuteWithInverse((*perm.inverse()));
Ordering expected; expected += "l1","x2","x1"; Ordering expected; expected += kl(1),kx(2),kx(1);
EXPECT(assert_equal(expected,actual)); EXPECT(assert_equal(expected,actual));
} }
// SL-FIX TEST( GaussianFactorGraph, getOrdering2) // SL-FIX TEST( GaussianFactorGraph, getOrdering2)
//{ //{
// Ordering expected; // Ordering expected;
// expected += "l1","x1"; // expected += kl(1),kx(1);
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// set<Symbol> interested; interested += "l1","x1"; // set<Symbol> interested; interested += kl(1),kx(1);
// Ordering actual = fg.getOrdering(interested); // Ordering actual = fg.getOrdering(interested);
// EXPECT(assert_equal(expected,actual)); // EXPECT(assert_equal(expected,actual));
//} //}
@ -459,7 +462,7 @@ TEST( GaussianFactorGraph, getOrdering)
TEST( GaussianFactorGraph, optimize_LDL ) TEST( GaussianFactorGraph, optimize_LDL )
{ {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
// create a graph // create a graph
GaussianFactorGraph fg = createGaussianFactorGraph(ord); GaussianFactorGraph fg = createGaussianFactorGraph(ord);
@ -477,7 +480,7 @@ TEST( GaussianFactorGraph, optimize_LDL )
TEST( GaussianFactorGraph, optimize_QR ) TEST( GaussianFactorGraph, optimize_QR )
{ {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
// create a graph // create a graph
GaussianFactorGraph fg = createGaussianFactorGraph(ord); GaussianFactorGraph fg = createGaussianFactorGraph(ord);
@ -495,7 +498,7 @@ TEST( GaussianFactorGraph, optimize_QR )
// SL-FIX TEST( GaussianFactorGraph, optimizeMultiFrontlas ) // SL-FIX TEST( GaussianFactorGraph, optimizeMultiFrontlas )
//{ //{
// // create an ordering // // create an ordering
// Ordering ord; ord += "x2","l1","x1"; // Ordering ord; ord += kx(2),kl(1),kx(1);
// //
// // create a graph // // create a graph
// GaussianFactorGraph fg = createGaussianFactorGraph(ord); // GaussianFactorGraph fg = createGaussianFactorGraph(ord);
@ -513,7 +516,7 @@ TEST( GaussianFactorGraph, optimize_QR )
TEST( GaussianFactorGraph, combine) TEST( GaussianFactorGraph, combine)
{ {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
// create a test graph // create a test graph
GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); GaussianFactorGraph fg1 = createGaussianFactorGraph(ord);
@ -535,7 +538,7 @@ TEST( GaussianFactorGraph, combine)
TEST( GaussianFactorGraph, combine2) TEST( GaussianFactorGraph, combine2)
{ {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
// create a test graph // create a test graph
GaussianFactorGraph fg1 = createGaussianFactorGraph(ord); GaussianFactorGraph fg1 = createGaussianFactorGraph(ord);
@ -568,13 +571,13 @@ void print(vector<int> v) {
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// //
// // ask for all factor indices connected to x1 // // ask for all factor indices connected to x1
// list<size_t> x1_factors = fg.factors("x1"); // list<size_t> x1_factors = fg.factors(kx(1));
// size_t x1_indices[] = { 0, 1, 2 }; // size_t x1_indices[] = { 0, 1, 2 };
// list<size_t> x1_expected(x1_indices, x1_indices + 3); // list<size_t> x1_expected(x1_indices, x1_indices + 3);
// EXPECT(x1_factors==x1_expected); // EXPECT(x1_factors==x1_expected);
// //
// // ask for all factor indices connected to x2 // // ask for all factor indices connected to x2
// list<size_t> x2_factors = fg.factors("x2"); // list<size_t> x2_factors = fg.factors(kx(2));
// size_t x2_indices[] = { 1, 3 }; // size_t x2_indices[] = { 1, 3 };
// list<size_t> x2_expected(x2_indices, x2_indices + 2); // list<size_t> x2_expected(x2_indices, x2_indices + 2);
// EXPECT(x2_factors==x2_expected); // EXPECT(x2_factors==x2_expected);
@ -592,7 +595,7 @@ void print(vector<int> v) {
// GaussianFactor::shared_ptr f2 = fg[2]; // GaussianFactor::shared_ptr f2 = fg[2];
// //
// // call the function // // call the function
// vector<GaussianFactor::shared_ptr> factors = fg.findAndRemoveFactors("x1"); // vector<GaussianFactor::shared_ptr> factors = fg.findAndRemoveFactors(kx(1));
// //
// // Check the factors // // Check the factors
// EXPECT(f0==factors[0]); // EXPECT(f0==factors[0]);
@ -617,7 +620,7 @@ TEST(GaussianFactorGraph, createSmoother)
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// Dimensions expected; // Dimensions expected;
// insert(expected)("l1", 2)("x1", 2)("x2", 2); // insert(expected)(kl(1), 2)(kx(1), 2)(kx(2), 2);
// Dimensions actual = fg.dimensions(); // Dimensions actual = fg.dimensions();
// EXPECT(expected==actual); // EXPECT(expected==actual);
//} //}
@ -627,7 +630,7 @@ TEST(GaussianFactorGraph, createSmoother)
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// Ordering expected; // Ordering expected;
// expected += "l1","x1","x2"; // expected += kl(1),kx(1),kx(2);
// EXPECT(assert_equal(expected,fg.keys())); // EXPECT(assert_equal(expected,fg.keys()));
//} //}
@ -635,16 +638,16 @@ TEST(GaussianFactorGraph, createSmoother)
// SL-NEEDED? TEST( GaussianFactorGraph, involves ) // SL-NEEDED? TEST( GaussianFactorGraph, involves )
//{ //{
// GaussianFactorGraph fg = createGaussianFactorGraph(); // GaussianFactorGraph fg = createGaussianFactorGraph();
// EXPECT(fg.involves("l1")); // EXPECT(fg.involves(kl(1)));
// EXPECT(fg.involves("x1")); // EXPECT(fg.involves(kx(1)));
// EXPECT(fg.involves("x2")); // EXPECT(fg.involves(kx(2)));
// EXPECT(!fg.involves("x3")); // EXPECT(!fg.involves(kx(3)));
//} //}
/* ************************************************************************* */ /* ************************************************************************* */
double error(const VectorValues& x) { double error(const VectorValues& x) {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
GaussianFactorGraph fg = createGaussianFactorGraph(ord); GaussianFactorGraph fg = createGaussianFactorGraph(ord);
return fg.error(x); return fg.error(x);
@ -658,11 +661,11 @@ double error(const VectorValues& x) {
// // Construct expected gradient // // Construct expected gradient
// VectorValues expected; // VectorValues expected;
// //
// // 2*f(x) = 100*(x1+c["x1"])^2 + 100*(x2-x1-[0.2;-0.1])^2 + 25*(l1-x1-[0.0;0.2])^2 + 25*(l1-x2-[-0.2;0.3])^2 // // 2*f(x) = 100*(x1+c[kx(1)])^2 + 100*(x2-x1-[0.2;-0.1])^2 + 25*(l1-x1-[0.0;0.2])^2 + 25*(l1-x2-[-0.2;0.3])^2
// // worked out: df/dx1 = 100*[0.1;0.1] + 100*[0.2;-0.1]) + 25*[0.0;0.2] = [10+20;10-10+5] = [30;5] // // worked out: df/dx1 = 100*[0.1;0.1] + 100*[0.2;-0.1]) + 25*[0.0;0.2] = [10+20;10-10+5] = [30;5]
// expected.insert("l1",Vector_(2, 5.0,-12.5)); // expected.insert(kl(1),Vector_(2, 5.0,-12.5));
// expected.insert("x1",Vector_(2, 30.0, 5.0)); // expected.insert(kx(1),Vector_(2, 30.0, 5.0));
// expected.insert("x2",Vector_(2,-25.0, 17.5)); // expected.insert(kx(2),Vector_(2,-25.0, 17.5));
// //
// // Check the gradient at delta=0 // // Check the gradient at delta=0
// VectorValues zero = createZeroDelta(); // VectorValues zero = createZeroDelta();
@ -675,7 +678,7 @@ double error(const VectorValues& x) {
// //
// // Check the gradient at the solution (should be zero) // // Check the gradient at the solution (should be zero)
// Ordering ord; // Ordering ord;
// ord += "x2","l1","x1"; // ord += kx(2),kl(1),kx(1);
// GaussianFactorGraph fg2 = createGaussianFactorGraph(); // GaussianFactorGraph fg2 = createGaussianFactorGraph();
// VectorValues solution = fg2.optimize(ord); // destructive // VectorValues solution = fg2.optimize(ord); // destructive
// VectorValues actual2 = fg.gradient(solution); // VectorValues actual2 = fg.gradient(solution);
@ -686,7 +689,7 @@ double error(const VectorValues& x) {
TEST( GaussianFactorGraph, multiplication ) TEST( GaussianFactorGraph, multiplication )
{ {
// create an ordering // create an ordering
Ordering ord; ord += "x2","l1","x1"; Ordering ord; ord += kx(2),kl(1),kx(1);
FactorGraph<JacobianFactor> A = createGaussianFactorGraph(ord); FactorGraph<JacobianFactor> A = createGaussianFactorGraph(ord);
VectorValues x = createCorrectDelta(ord); VectorValues x = createCorrectDelta(ord);
@ -703,7 +706,7 @@ TEST( GaussianFactorGraph, multiplication )
// SL-NEEDED? TEST( GaussianFactorGraph, transposeMultiplication ) // SL-NEEDED? TEST( GaussianFactorGraph, transposeMultiplication )
//{ //{
// // create an ordering // // create an ordering
// Ordering ord; ord += "x2","l1","x1"; // Ordering ord; ord += kx(2),kl(1),kx(1);
// //
// GaussianFactorGraph A = createGaussianFactorGraph(ord); // GaussianFactorGraph A = createGaussianFactorGraph(ord);
// Errors e; // Errors e;
@ -713,9 +716,9 @@ TEST( GaussianFactorGraph, multiplication )
// e += Vector_(2,-7.5,-5.0); // e += Vector_(2,-7.5,-5.0);
// //
// VectorValues expected = createZeroDelta(ord), actual = A ^ e; // VectorValues expected = createZeroDelta(ord), actual = A ^ e;
// expected[ord["l1"]] = Vector_(2, -37.5,-50.0); // expected[ord[kl(1)]] = Vector_(2, -37.5,-50.0);
// expected[ord["x1"]] = Vector_(2,-150.0, 25.0); // expected[ord[kx(1)]] = Vector_(2,-150.0, 25.0);
// expected[ord["x2"]] = Vector_(2, 187.5, 25.0); // expected[ord[kx(2)]] = Vector_(2, 187.5, 25.0);
// EXPECT(assert_equal(expected,actual)); // EXPECT(assert_equal(expected,actual));
//} //}
@ -723,7 +726,7 @@ TEST( GaussianFactorGraph, multiplication )
// SL-NEEDED? TEST( GaussianFactorGraph, rhs ) // SL-NEEDED? TEST( GaussianFactorGraph, rhs )
//{ //{
// // create an ordering // // create an ordering
// Ordering ord; ord += "x2","l1","x1"; // Ordering ord; ord += kx(2),kl(1),kx(1);
// //
// GaussianFactorGraph Ab = createGaussianFactorGraph(ord); // GaussianFactorGraph Ab = createGaussianFactorGraph(ord);
// Errors expected = createZeroDelta(ord), actual = Ab.rhs(); // Errors expected = createZeroDelta(ord), actual = Ab.rhs();
@ -739,21 +742,21 @@ TEST( GaussianFactorGraph, multiplication )
TEST( GaussianFactorGraph, elimination ) TEST( GaussianFactorGraph, elimination )
{ {
Ordering ord; Ordering ord;
ord += "x1", "x2"; ord += kx(1), kx(2);
// Create Gaussian Factor Graph // Create Gaussian Factor Graph
GaussianFactorGraph fg; GaussianFactorGraph fg;
Matrix Ap = eye(1), An = eye(1) * -1; Matrix Ap = eye(1), An = eye(1) * -1;
Vector b = Vector_(1, 0.0); Vector b = Vector_(1, 0.0);
SharedDiagonal sigma = sharedSigma(1,2.0); SharedDiagonal sigma = sharedSigma(1,2.0);
fg.add(ord["x1"], An, ord["x2"], Ap, b, sigma); fg.add(ord[kx(1)], An, ord[kx(2)], Ap, b, sigma);
fg.add(ord["x1"], Ap, b, sigma); fg.add(ord[kx(1)], Ap, b, sigma);
fg.add(ord["x2"], Ap, b, sigma); fg.add(ord[kx(2)], Ap, b, sigma);
// Eliminate // Eliminate
GaussianBayesNet bayesNet = *GaussianSequentialSolver(fg).eliminate(); GaussianBayesNet bayesNet = *GaussianSequentialSolver(fg).eliminate();
// Check sigma // Check sigma
EXPECT_DOUBLES_EQUAL(1.0,bayesNet[ord["x2"]]->get_sigmas()(0),1e-5); EXPECT_DOUBLES_EQUAL(1.0,bayesNet[ord[kx(2)]]->get_sigmas()(0),1e-5);
// Check matrix // Check matrix
Matrix R;Vector d; Matrix R;Vector d;
@ -808,7 +811,7 @@ TEST( GaussianFactorGraph, constrained_single )
// //
// // eliminate and solve // // eliminate and solve
// Ordering ord; // Ordering ord;
// ord += "y", "x"; // ord += "yk, x";
// VectorValues actual = fg.optimize(ord); // VectorValues actual = fg.optimize(ord);
// //
// // verify // // verify
@ -839,7 +842,7 @@ TEST( GaussianFactorGraph, constrained_multi1 )
// //
// // eliminate and solve // // eliminate and solve
// Ordering ord; // Ordering ord;
// ord += "z", "x", "y"; // ord += "zk, xk, y";
// VectorValues actual = fg.optimize(ord); // VectorValues actual = fg.optimize(ord);
// //
// // verify // // verify
@ -856,18 +859,18 @@ SharedDiagonal model = sharedSigma(2,1);
// GaussianFactorGraph g; // GaussianFactorGraph g;
// Matrix I = eye(2); // Matrix I = eye(2);
// Vector b = Vector_(0, 0, 0); // Vector b = Vector_(0, 0, 0);
// g.add("x1", I, "x2", I, b, model); // g.add(kx(1), I, kx(2), I, b, model);
// g.add("x1", I, "x3", I, b, model); // g.add(kx(1), I, kx(3), I, b, model);
// g.add("x1", I, "x4", I, b, model); // g.add(kx(1), I, kx(4), I, b, model);
// g.add("x2", I, "x3", I, b, model); // g.add(kx(2), I, kx(3), I, b, model);
// g.add("x2", I, "x4", I, b, model); // g.add(kx(2), I, kx(4), I, b, model);
// g.add("x3", I, "x4", I, b, model); // g.add(kx(3), I, kx(4), I, b, model);
// //
// map<string, string> tree = g.findMinimumSpanningTree<string, GaussianFactor>(); // map<string, string> tree = g.findMinimumSpanningTree<string, GaussianFactor>();
// EXPECT(tree["x1"].compare("x1")==0); // EXPECT(tree[kx(1)].compare(kx(1))==0);
// EXPECT(tree["x2"].compare("x1")==0); // EXPECT(tree[kx(2)].compare(kx(1))==0);
// EXPECT(tree["x3"].compare("x1")==0); // EXPECT(tree[kx(3)].compare(kx(1))==0);
// EXPECT(tree["x4"].compare("x1")==0); // EXPECT(tree[kx(4)].compare(kx(1))==0);
//} //}
///* ************************************************************************* */ ///* ************************************************************************* */
@ -876,17 +879,17 @@ SharedDiagonal model = sharedSigma(2,1);
// GaussianFactorGraph g; // GaussianFactorGraph g;
// Matrix I = eye(2); // Matrix I = eye(2);
// Vector b = Vector_(0, 0, 0); // Vector b = Vector_(0, 0, 0);
// g.add("x1", I, "x2", I, b, model); // g.add(kx(1), I, kx(2), I, b, model);
// g.add("x1", I, "x3", I, b, model); // g.add(kx(1), I, kx(3), I, b, model);
// g.add("x1", I, "x4", I, b, model); // g.add(kx(1), I, kx(4), I, b, model);
// g.add("x2", I, "x3", I, b, model); // g.add(kx(2), I, kx(3), I, b, model);
// g.add("x2", I, "x4", I, b, model); // g.add(kx(2), I, kx(4), I, b, model);
// //
// PredecessorMap<string> tree; // PredecessorMap<string> tree;
// tree["x1"] = "x1"; // tree[kx(1)] = kx(1);
// tree["x2"] = "x1"; // tree[kx(2)] = kx(1);
// tree["x3"] = "x1"; // tree[kx(3)] = kx(1);
// tree["x4"] = "x1"; // tree[kx(4)] = kx(1);
// //
// GaussianFactorGraph Ab1, Ab2; // GaussianFactorGraph Ab1, Ab2;
// g.split<string, GaussianFactor>(tree, Ab1, Ab2); // g.split<string, GaussianFactor>(tree, Ab1, Ab2);
@ -897,17 +900,17 @@ SharedDiagonal model = sharedSigma(2,1);
/* ************************************************************************* */ /* ************************************************************************* */
TEST(GaussianFactorGraph, replace) TEST(GaussianFactorGraph, replace)
{ {
Ordering ord; ord += "x1","x2","x3","x4","x5","x6"; Ordering ord; ord += kx(1),kx(2),kx(3),kx(4),kx(5),kx(6);
SharedDiagonal noise(sharedSigma(3, 1.0)); SharedDiagonal noise(sharedSigma(3, 1.0));
GaussianFactorGraph::sharedFactor f1(new JacobianFactor( GaussianFactorGraph::sharedFactor f1(new JacobianFactor(
ord["x1"], eye(3,3), ord["x2"], eye(3,3), zero(3), noise)); ord[kx(1)], eye(3,3), ord[kx(2)], eye(3,3), zero(3), noise));
GaussianFactorGraph::sharedFactor f2(new JacobianFactor( GaussianFactorGraph::sharedFactor f2(new JacobianFactor(
ord["x2"], eye(3,3), ord["x3"], eye(3,3), zero(3), noise)); ord[kx(2)], eye(3,3), ord[kx(3)], eye(3,3), zero(3), noise));
GaussianFactorGraph::sharedFactor f3(new JacobianFactor( GaussianFactorGraph::sharedFactor f3(new JacobianFactor(
ord["x3"], eye(3,3), ord["x4"], eye(3,3), zero(3), noise)); ord[kx(3)], eye(3,3), ord[kx(4)], eye(3,3), zero(3), noise));
GaussianFactorGraph::sharedFactor f4(new JacobianFactor( GaussianFactorGraph::sharedFactor f4(new JacobianFactor(
ord["x5"], eye(3,3), ord["x6"], eye(3,3), zero(3), noise)); ord[kx(5)], eye(3,3), ord[kx(6)], eye(3,3), zero(3), noise));
GaussianFactorGraph actual; GaussianFactorGraph actual;
actual.push_back(f1); actual.push_back(f1);
@ -943,7 +946,7 @@ TEST(GaussianFactorGraph, replace)
// //
// // combine in a factor // // combine in a factor
// Matrix Ab; SharedDiagonal noise; // Matrix Ab; SharedDiagonal noise;
// Ordering order; order += "x2", "l1", "x1"; // Ordering order; order += kx(2), kl(1), kx(1);
// boost::tie(Ab, noise) = combineFactorsAndCreateMatrix(lfg, order, dimensions); // boost::tie(Ab, noise) = combineFactorsAndCreateMatrix(lfg, order, dimensions);
// //
// // the expected augmented matrix // // the expected augmented matrix
@ -971,26 +974,26 @@ TEST(GaussianFactorGraph, replace)
// typedef GaussianFactorGraph::sharedFactor Factor; // typedef GaussianFactorGraph::sharedFactor Factor;
// SharedDiagonal model(Vector_(1, 0.5)); // SharedDiagonal model(Vector_(1, 0.5));
// GaussianFactorGraph fg; // GaussianFactorGraph fg;
// Factor factor1(new JacobianFactor("x1", Matrix_(1,1,1.), "x2", Matrix_(1,1,1.), Vector_(1,1.), model)); // Factor factor1(new JacobianFactor(kx(1), Matrix_(1,1,1.), kx(2), Matrix_(1,1,1.), Vector_(1,1.), model));
// Factor factor2(new JacobianFactor("x2", Matrix_(1,1,1.), "x3", Matrix_(1,1,1.), Vector_(1,1.), model)); // Factor factor2(new JacobianFactor(kx(2), Matrix_(1,1,1.), kx(3), Matrix_(1,1,1.), Vector_(1,1.), model));
// Factor factor3(new JacobianFactor("x3", Matrix_(1,1,1.), "x3", Matrix_(1,1,1.), Vector_(1,1.), model)); // Factor factor3(new JacobianFactor(kx(3), Matrix_(1,1,1.), kx(3), Matrix_(1,1,1.), Vector_(1,1.), model));
// fg.push_back(factor1); // fg.push_back(factor1);
// fg.push_back(factor2); // fg.push_back(factor2);
// fg.push_back(factor3); // fg.push_back(factor3);
// //
// Ordering frontals; frontals += "x2", "x1"; // Ordering frontals; frontals += kx(2), kx(1);
// GaussianBayesNet bn = fg.eliminateFrontals(frontals); // GaussianBayesNet bn = fg.eliminateFrontals(frontals);
// //
// GaussianBayesNet bn_expected; // GaussianBayesNet bn_expected;
// GaussianBayesNet::sharedConditional conditional1(new GaussianConditional("x2", Vector_(1, 2.), Matrix_(1, 1, 2.), // GaussianBayesNet::sharedConditional conditional1(new GaussianConditional(kx(2), Vector_(1, 2.), Matrix_(1, 1, 2.),
// "x1", Matrix_(1, 1, 1.), "x3", Matrix_(1, 1, 1.), Vector_(1, 1.))); // kx(1), Matrix_(1, 1, 1.), kx(3), Matrix_(1, 1, 1.), Vector_(1, 1.)));
// GaussianBayesNet::sharedConditional conditional2(new GaussianConditional("x1", Vector_(1, 0.), Matrix_(1, 1, -1.), // GaussianBayesNet::sharedConditional conditional2(new GaussianConditional(kx(1), Vector_(1, 0.), Matrix_(1, 1, -1.),
// "x3", Matrix_(1, 1, 1.), Vector_(1, 1.))); // kx(3), Matrix_(1, 1, 1.), Vector_(1, 1.)));
// bn_expected.push_back(conditional1); // bn_expected.push_back(conditional1);
// bn_expected.push_back(conditional2); // bn_expected.push_back(conditional2);
// EXPECT(assert_equal(bn_expected, bn)); // EXPECT(assert_equal(bn_expected, bn));
// //
// GaussianFactorGraph::sharedFactor factor_expected(new JacobianFactor("x3", Matrix_(1, 1, 2.), Vector_(1, 2.), SharedDiagonal(Vector_(1, 1.)))); // GaussianFactorGraph::sharedFactor factor_expected(new JacobianFactor(kx(3), Matrix_(1, 1, 2.), Vector_(1, 2.), SharedDiagonal(Vector_(1, 1.))));
// GaussianFactorGraph fg_expected; // GaussianFactorGraph fg_expected;
// fg_expected.push_back(factor_expected); // fg_expected.push_back(factor_expected);
// EXPECT(assert_equal(fg_expected, fg)); // EXPECT(assert_equal(fg_expected, fg));
@ -1006,8 +1009,8 @@ TEST(GaussianFactorGraph, createSmoother2)
LONGS_EQUAL(5,fg2.size()); LONGS_EQUAL(5,fg2.size());
// eliminate // eliminate
vector<Index> x3var; x3var.push_back(ordering["x3"]); vector<Index> x3var; x3var.push_back(ordering[kx(3)]);
vector<Index> x1var; x1var.push_back(ordering["x1"]); vector<Index> x1var; x1var.push_back(ordering[kx(1)]);
GaussianBayesNet p_x3 = *GaussianSequentialSolver( GaussianBayesNet p_x3 = *GaussianSequentialSolver(
*GaussianSequentialSolver(fg2).jointFactorGraph(x3var)).eliminate(); *GaussianSequentialSolver(fg2).jointFactorGraph(x3var)).eliminate();
GaussianBayesNet p_x1 = *GaussianSequentialSolver( GaussianBayesNet p_x1 = *GaussianSequentialSolver(
@ -1024,7 +1027,7 @@ TEST(GaussianFactorGraph, hasConstraints)
FactorGraph<GaussianFactor> fgc2 = createSimpleConstraintGraph() ; FactorGraph<GaussianFactor> fgc2 = createSimpleConstraintGraph() ;
EXPECT(hasConstraints(fgc2)); EXPECT(hasConstraints(fgc2));
Ordering ordering; ordering += "x1", "x2", "l1"; Ordering ordering; ordering += kx(1), kx(2), kl(1);
FactorGraph<GaussianFactor> fg = createGaussianFactorGraph(ordering); FactorGraph<GaussianFactor> fg = createGaussianFactorGraph(ordering);
EXPECT(!hasConstraints(fg)); EXPECT(!hasConstraints(fg));
} }

View File

@ -21,7 +21,7 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/geometry/Rot2.h> #include <gtsam/geometry/Rot2.h>
@ -37,6 +37,9 @@ using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
/* ************************************************************************* */ /* ************************************************************************* */
// Some numbers that should be consistent among all smoother tests // Some numbers that should be consistent among all smoother tests
@ -49,7 +52,7 @@ const double tol = 1e-4;
TEST_UNSAFE( ISAM, iSAM_smoother ) TEST_UNSAFE( ISAM, iSAM_smoother )
{ {
Ordering ordering; Ordering ordering;
for (int t = 1; t <= 7; t++) ordering += Symbol('x', t); for (int t = 1; t <= 7; t++) ordering += kx(t);
// Create smoother with 7 nodes // Create smoother with 7 nodes
GaussianFactorGraph smoother = createSmoother(7, ordering).first; GaussianFactorGraph smoother = createSmoother(7, ordering).first;
@ -82,7 +85,7 @@ TEST_UNSAFE( ISAM, iSAM_smoother )
// GaussianFactorGraph smoother = createSmoother(7); // GaussianFactorGraph smoother = createSmoother(7);
// //
// // Create initial tree from first 4 timestamps in reverse order ! // // Create initial tree from first 4 timestamps in reverse order !
// Ordering ord; ord += "x4","x3","x2","x1"; // Ordering ord; ord += kx(4),kx(3),kx(2),kx(1);
// GaussianFactorGraph factors1; // GaussianFactorGraph factors1;
// for (int i=0;i<7;i++) factors1.push_back(smoother[i]); // for (int i=0;i<7;i++) factors1.push_back(smoother[i]);
// GaussianISAM actual(*Inference::Eliminate(factors1)); // GaussianISAM actual(*Inference::Eliminate(factors1));
@ -129,7 +132,7 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts )
EXPECT(assert_equal(empty,actual1,tol)); EXPECT(assert_equal(empty,actual1,tol));
// Check the conditional P(C2|Root) // Check the conditional P(C2|Root)
GaussianISAM::sharedClique C2 = isamTree[ordering["x5"]]; GaussianISAM::sharedClique C2 = isamTree[ordering[kx(5)]];
GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R); GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R);
EXPECT(assert_equal(empty,actual2,tol)); EXPECT(assert_equal(empty,actual2,tol));
@ -137,8 +140,8 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts )
double sigma3 = 0.61808; double sigma3 = 0.61808;
Matrix A56 = Matrix_(2,2,-0.382022,0.,0.,-0.382022); Matrix A56 = Matrix_(2,2,-0.382022,0.,0.,-0.382022);
GaussianBayesNet expected3; GaussianBayesNet expected3;
push_front(expected3,ordering["x5"], zero(2), eye(2)/sigma3, ordering["x6"], A56/sigma3, ones(2)); push_front(expected3,ordering[kx(5)], zero(2), eye(2)/sigma3, ordering[kx(6)], A56/sigma3, ones(2));
GaussianISAM::sharedClique C3 = isamTree[ordering["x4"]]; GaussianISAM::sharedClique C3 = isamTree[ordering[kx(4)]];
GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R); GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R);
EXPECT(assert_equal(expected3,actual3,tol)); EXPECT(assert_equal(expected3,actual3,tol));
@ -146,8 +149,8 @@ TEST_UNSAFE( BayesTree, linear_smoother_shortcuts )
double sigma4 = 0.661968; double sigma4 = 0.661968;
Matrix A46 = Matrix_(2,2,-0.146067,0.,0.,-0.146067); Matrix A46 = Matrix_(2,2,-0.146067,0.,0.,-0.146067);
GaussianBayesNet expected4; GaussianBayesNet expected4;
push_front(expected4, ordering["x4"], zero(2), eye(2)/sigma4, ordering["x6"], A46/sigma4, ones(2)); push_front(expected4, ordering[kx(4)], zero(2), eye(2)/sigma4, ordering[kx(6)], A46/sigma4, ones(2));
GaussianISAM::sharedClique C4 = isamTree[ordering["x3"]]; GaussianISAM::sharedClique C4 = isamTree[ordering[kx(3)]];
GaussianBayesNet actual4 = GaussianISAM::shortcut(C4,R); GaussianBayesNet actual4 = GaussianISAM::shortcut(C4,R);
EXPECT(assert_equal(expected4,actual4,tol)); EXPECT(assert_equal(expected4,actual4,tol));
} }
@ -175,7 +178,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_marginals )
{ {
// Create smoother with 7 nodes // Create smoother with 7 nodes
Ordering ordering; Ordering ordering;
ordering += "x1","x3","x5","x7","x2","x6","x4"; ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4);
GaussianFactorGraph smoother = createSmoother(7, ordering).first; GaussianFactorGraph smoother = createSmoother(7, ordering).first;
// Create the Bayes tree // Create the Bayes tree
@ -192,48 +195,48 @@ TEST_UNSAFE( BayesTree, balanced_smoother_marginals )
double tol=1e-5; double tol=1e-5;
// Check marginal on x1 // Check marginal on x1
GaussianBayesNet expected1 = simpleGaussian(ordering["x1"], zero(2), sigmax1); GaussianBayesNet expected1 = simpleGaussian(ordering[kx(1)], zero(2), sigmax1);
GaussianBayesNet actual1 = *bayesTree.marginalBayesNet(ordering["x1"]); GaussianBayesNet actual1 = *bayesTree.marginalBayesNet(ordering[kx(1)]);
Matrix expectedCovarianceX1 = eye(2,2) * (sigmax1 * sigmax1); Matrix expectedCovarianceX1 = eye(2,2) * (sigmax1 * sigmax1);
Matrix actualCovarianceX1; Matrix actualCovarianceX1;
actualCovarianceX1 = bayesTree.marginalCovariance(ordering["x1"]); actualCovarianceX1 = bayesTree.marginalCovariance(ordering[kx(1)]);
EXPECT(assert_equal(expectedCovarianceX1, actualCovarianceX1, tol)); EXPECT(assert_equal(expectedCovarianceX1, actualCovarianceX1, tol));
EXPECT(assert_equal(expected1,actual1,tol)); EXPECT(assert_equal(expected1,actual1,tol));
// Check marginal on x2 // Check marginal on x2
double sigx2 = 0.68712938; // FIXME: this should be corrected analytically double sigx2 = 0.68712938; // FIXME: this should be corrected analytically
GaussianBayesNet expected2 = simpleGaussian(ordering["x2"], zero(2), sigx2); GaussianBayesNet expected2 = simpleGaussian(ordering[kx(2)], zero(2), sigx2);
GaussianBayesNet actual2 = *bayesTree.marginalBayesNet(ordering["x2"]); GaussianBayesNet actual2 = *bayesTree.marginalBayesNet(ordering[kx(2)]);
Matrix expectedCovarianceX2 = eye(2,2) * (sigx2 * sigx2); Matrix expectedCovarianceX2 = eye(2,2) * (sigx2 * sigx2);
Matrix actualCovarianceX2; Matrix actualCovarianceX2;
actualCovarianceX2 = bayesTree.marginalCovariance(ordering["x2"]); actualCovarianceX2 = bayesTree.marginalCovariance(ordering[kx(2)]);
EXPECT(assert_equal(expectedCovarianceX2, actualCovarianceX2, tol)); EXPECT(assert_equal(expectedCovarianceX2, actualCovarianceX2, tol));
EXPECT(assert_equal(expected2,actual2,tol)); EXPECT(assert_equal(expected2,actual2,tol));
// Check marginal on x3 // Check marginal on x3
GaussianBayesNet expected3 = simpleGaussian(ordering["x3"], zero(2), sigmax3); GaussianBayesNet expected3 = simpleGaussian(ordering[kx(3)], zero(2), sigmax3);
GaussianBayesNet actual3 = *bayesTree.marginalBayesNet(ordering["x3"]); GaussianBayesNet actual3 = *bayesTree.marginalBayesNet(ordering[kx(3)]);
Matrix expectedCovarianceX3 = eye(2,2) * (sigmax3 * sigmax3); Matrix expectedCovarianceX3 = eye(2,2) * (sigmax3 * sigmax3);
Matrix actualCovarianceX3; Matrix actualCovarianceX3;
actualCovarianceX3 = bayesTree.marginalCovariance(ordering["x3"]); actualCovarianceX3 = bayesTree.marginalCovariance(ordering[kx(3)]);
EXPECT(assert_equal(expectedCovarianceX3, actualCovarianceX3, tol)); EXPECT(assert_equal(expectedCovarianceX3, actualCovarianceX3, tol));
EXPECT(assert_equal(expected3,actual3,tol)); EXPECT(assert_equal(expected3,actual3,tol));
// Check marginal on x4 // Check marginal on x4
GaussianBayesNet expected4 = simpleGaussian(ordering["x4"], zero(2), sigmax4); GaussianBayesNet expected4 = simpleGaussian(ordering[kx(4)], zero(2), sigmax4);
GaussianBayesNet actual4 = *bayesTree.marginalBayesNet(ordering["x4"]); GaussianBayesNet actual4 = *bayesTree.marginalBayesNet(ordering[kx(4)]);
Matrix expectedCovarianceX4 = eye(2,2) * (sigmax4 * sigmax4); Matrix expectedCovarianceX4 = eye(2,2) * (sigmax4 * sigmax4);
Matrix actualCovarianceX4; Matrix actualCovarianceX4;
actualCovarianceX4 = bayesTree.marginalCovariance(ordering["x4"]); actualCovarianceX4 = bayesTree.marginalCovariance(ordering[kx(4)]);
EXPECT(assert_equal(expectedCovarianceX4, actualCovarianceX4, tol)); EXPECT(assert_equal(expectedCovarianceX4, actualCovarianceX4, tol));
EXPECT(assert_equal(expected4,actual4,tol)); EXPECT(assert_equal(expected4,actual4,tol));
// Check marginal on x7 (should be equal to x1) // Check marginal on x7 (should be equal to x1)
GaussianBayesNet expected7 = simpleGaussian(ordering["x7"], zero(2), sigmax7); GaussianBayesNet expected7 = simpleGaussian(ordering[kx(7)], zero(2), sigmax7);
GaussianBayesNet actual7 = *bayesTree.marginalBayesNet(ordering["x7"]); GaussianBayesNet actual7 = *bayesTree.marginalBayesNet(ordering[kx(7)]);
Matrix expectedCovarianceX7 = eye(2,2) * (sigmax7 * sigmax7); Matrix expectedCovarianceX7 = eye(2,2) * (sigmax7 * sigmax7);
Matrix actualCovarianceX7; Matrix actualCovarianceX7;
actualCovarianceX7 = bayesTree.marginalCovariance(ordering["x7"]); actualCovarianceX7 = bayesTree.marginalCovariance(ordering[kx(7)]);
EXPECT(assert_equal(expectedCovarianceX7, actualCovarianceX7, tol)); EXPECT(assert_equal(expectedCovarianceX7, actualCovarianceX7, tol));
EXPECT(assert_equal(expected7,actual7,tol)); EXPECT(assert_equal(expected7,actual7,tol));
} }
@ -243,7 +246,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts )
{ {
// Create smoother with 7 nodes // Create smoother with 7 nodes
Ordering ordering; Ordering ordering;
ordering += "x1","x3","x5","x7","x2","x6","x4"; ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4);
GaussianFactorGraph smoother = createSmoother(7, ordering).first; GaussianFactorGraph smoother = createSmoother(7, ordering).first;
// Create the Bayes tree // Create the Bayes tree
@ -257,19 +260,19 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts )
EXPECT(assert_equal(empty,actual1,tol)); EXPECT(assert_equal(empty,actual1,tol));
// Check the conditional P(C2|Root) // Check the conditional P(C2|Root)
GaussianISAM::sharedClique C2 = isamTree[ordering["x3"]]; GaussianISAM::sharedClique C2 = isamTree[ordering[kx(3)]];
GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R); GaussianBayesNet actual2 = GaussianISAM::shortcut(C2,R);
EXPECT(assert_equal(empty,actual2,tol)); EXPECT(assert_equal(empty,actual2,tol));
// Check the conditional P(C3|Root), which should be equal to P(x2|x4) // Check the conditional P(C3|Root), which should be equal to P(x2|x4)
/** TODO: Note for multifrontal conditional: /** TODO: Note for multifrontal conditional:
* p_x2_x4 is now an element conditional of the multifrontal conditional bayesTree[ordering["x2"]]->conditional() * p_x2_x4 is now an element conditional of the multifrontal conditional bayesTree[ordering[kx(2)]]->conditional()
* We don't know yet how to take it out. * We don't know yet how to take it out.
*/ */
// GaussianConditional::shared_ptr p_x2_x4 = bayesTree[ordering["x2"]]->conditional(); // GaussianConditional::shared_ptr p_x2_x4 = bayesTree[ordering[kx(2)]]->conditional();
// p_x2_x4->print("Conditional p_x2_x4: "); // p_x2_x4->print("Conditional p_x2_x4: ");
// GaussianBayesNet expected3(p_x2_x4); // GaussianBayesNet expected3(p_x2_x4);
// GaussianISAM::sharedClique C3 = isamTree[ordering["x1"]]; // GaussianISAM::sharedClique C3 = isamTree[ordering[kx(1)]];
// GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R); // GaussianBayesNet actual3 = GaussianISAM::shortcut(C3,R);
// EXPECT(assert_equal(expected3,actual3,tol)); // EXPECT(assert_equal(expected3,actual3,tol));
} }
@ -279,7 +282,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts )
//{ //{
// // Create smoother with 7 nodes // // Create smoother with 7 nodes
// Ordering ordering; // Ordering ordering;
// ordering += "x1","x3","x5","x7","x2","x6","x4"; // ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4);
// GaussianFactorGraph smoother = createSmoother(7, ordering).first; // GaussianFactorGraph smoother = createSmoother(7, ordering).first;
// //
// // Create the Bayes tree // // Create the Bayes tree
@ -288,9 +291,9 @@ TEST_UNSAFE( BayesTree, balanced_smoother_shortcuts )
// //
// // Check the clique marginal P(C3) // // Check the clique marginal P(C3)
// double sigmax2_alt = 1/1.45533; // THIS NEEDS TO BE CHECKED! // double sigmax2_alt = 1/1.45533; // THIS NEEDS TO BE CHECKED!
// GaussianBayesNet expected = simpleGaussian(ordering["x2"],zero(2),sigmax2_alt); // GaussianBayesNet expected = simpleGaussian(ordering[kx(2)],zero(2),sigmax2_alt);
// push_front(expected,ordering["x1"], zero(2), eye(2)*sqrt(2), ordering["x2"], -eye(2)*sqrt(2)/2, ones(2)); // push_front(expected,ordering[kx(1)], zero(2), eye(2)*sqrt(2), ordering[kx(2)], -eye(2)*sqrt(2)/2, ones(2));
// GaussianISAM::sharedClique R = bayesTree.root(), C3 = bayesTree[ordering["x1"]]; // GaussianISAM::sharedClique R = bayesTree.root(), C3 = bayesTree[ordering[kx(1)]];
// GaussianFactorGraph marginal = C3->marginal(R); // GaussianFactorGraph marginal = C3->marginal(R);
// GaussianVariableIndex varIndex(marginal); // GaussianVariableIndex varIndex(marginal);
// Permutation toFront(Permutation::PullToFront(C3->keys(), varIndex.size())); // Permutation toFront(Permutation::PullToFront(C3->keys(), varIndex.size()));
@ -308,7 +311,7 @@ TEST_UNSAFE( BayesTree, balanced_smoother_joint )
{ {
// Create smoother with 7 nodes // Create smoother with 7 nodes
Ordering ordering; Ordering ordering;
ordering += "x1","x3","x5","x7","x2","x6","x4"; ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4);
GaussianFactorGraph smoother = createSmoother(7, ordering).first; GaussianFactorGraph smoother = createSmoother(7, ordering).first;
// Create the Bayes tree, expected to look like: // Create the Bayes tree, expected to look like:
@ -327,41 +330,41 @@ TEST_UNSAFE( BayesTree, balanced_smoother_joint )
GaussianBayesNet expected1; GaussianBayesNet expected1;
// Why does the sign get flipped on the prior? // Why does the sign get flipped on the prior?
GaussianConditional::shared_ptr GaussianConditional::shared_ptr
parent1(new GaussianConditional(ordering["x7"], zero(2), -1*I/sigmax7, ones(2))); parent1(new GaussianConditional(ordering[kx(7)], zero(2), -1*I/sigmax7, ones(2)));
expected1.push_front(parent1); expected1.push_front(parent1);
push_front(expected1,ordering["x1"], zero(2), I/sigmax7, ordering["x7"], A/sigmax7, sigma); push_front(expected1,ordering[kx(1)], zero(2), I/sigmax7, ordering[kx(7)], A/sigmax7, sigma);
GaussianBayesNet actual1 = *bayesTree.jointBayesNet(ordering["x1"],ordering["x7"]); GaussianBayesNet actual1 = *bayesTree.jointBayesNet(ordering[kx(1)],ordering[kx(7)]);
EXPECT(assert_equal(expected1,actual1,tol)); EXPECT(assert_equal(expected1,actual1,tol));
// // Check the joint density P(x7,x1) factored as P(x7|x1)P(x1) // // Check the joint density P(x7,x1) factored as P(x7|x1)P(x1)
// GaussianBayesNet expected2; // GaussianBayesNet expected2;
// GaussianConditional::shared_ptr // GaussianConditional::shared_ptr
// parent2(new GaussianConditional(ordering["x1"], zero(2), -1*I/sigmax1, ones(2))); // parent2(new GaussianConditional(ordering[kx(1)], zero(2), -1*I/sigmax1, ones(2)));
// expected2.push_front(parent2); // expected2.push_front(parent2);
// push_front(expected2,ordering["x7"], zero(2), I/sigmax1, ordering["x1"], A/sigmax1, sigma); // push_front(expected2,ordering[kx(7)], zero(2), I/sigmax1, ordering[kx(1)], A/sigmax1, sigma);
// GaussianBayesNet actual2 = *bayesTree.jointBayesNet(ordering["x7"],ordering["x1"]); // GaussianBayesNet actual2 = *bayesTree.jointBayesNet(ordering[kx(7)],ordering[kx(1)]);
// EXPECT(assert_equal(expected2,actual2,tol)); // EXPECT(assert_equal(expected2,actual2,tol));
// Check the joint density P(x1,x4), i.e. with a root variable // Check the joint density P(x1,x4), i.e. with a root variable
GaussianBayesNet expected3; GaussianBayesNet expected3;
GaussianConditional::shared_ptr GaussianConditional::shared_ptr
parent3(new GaussianConditional(ordering["x4"], zero(2), I/sigmax4, ones(2))); parent3(new GaussianConditional(ordering[kx(4)], zero(2), I/sigmax4, ones(2)));
expected3.push_front(parent3); expected3.push_front(parent3);
double sig14 = 0.784465; double sig14 = 0.784465;
Matrix A14 = -0.0769231*I; Matrix A14 = -0.0769231*I;
push_front(expected3,ordering["x1"], zero(2), I/sig14, ordering["x4"], A14/sig14, sigma); push_front(expected3,ordering[kx(1)], zero(2), I/sig14, ordering[kx(4)], A14/sig14, sigma);
GaussianBayesNet actual3 = *bayesTree.jointBayesNet(ordering["x1"],ordering["x4"]); GaussianBayesNet actual3 = *bayesTree.jointBayesNet(ordering[kx(1)],ordering[kx(4)]);
EXPECT(assert_equal(expected3,actual3,tol)); EXPECT(assert_equal(expected3,actual3,tol));
// // Check the joint density P(x4,x1), i.e. with a root variable, factored the other way // // Check the joint density P(x4,x1), i.e. with a root variable, factored the other way
// GaussianBayesNet expected4; // GaussianBayesNet expected4;
// GaussianConditional::shared_ptr // GaussianConditional::shared_ptr
// parent4(new GaussianConditional(ordering["x1"], zero(2), -1.0*I/sigmax1, ones(2))); // parent4(new GaussianConditional(ordering[kx(1)], zero(2), -1.0*I/sigmax1, ones(2)));
// expected4.push_front(parent4); // expected4.push_front(parent4);
// double sig41 = 0.668096; // double sig41 = 0.668096;
// Matrix A41 = -0.055794*I; // Matrix A41 = -0.055794*I;
// push_front(expected4,ordering["x4"], zero(2), I/sig41, ordering["x1"], A41/sig41, sigma); // push_front(expected4,ordering[kx(4)], zero(2), I/sig41, ordering[kx(1)], A41/sig41, sigma);
// GaussianBayesNet actual4 = *bayesTree.jointBayesNet(ordering["x4"],ordering["x1"]); // GaussianBayesNet actual4 = *bayesTree.jointBayesNet(ordering[kx(4)],ordering[kx(1)]);
// EXPECT(assert_equal(expected4,actual4,tol)); // EXPECT(assert_equal(expected4,actual4,tol));
} }

View File

@ -788,7 +788,7 @@ TEST(ISAM2, constrained_ordering)
planarSLAM::Graph fullgraph; planarSLAM::Graph fullgraph;
// We will constrain x3 and x4 to the end // We will constrain x3 and x4 to the end
FastSet<Symbol> constrained; constrained.insert(planarSLAM::PoseKey(3)); constrained.insert(planarSLAM::PoseKey(4)); FastSet<Key> constrained; constrained.insert(planarSLAM::PoseKey(3)); constrained.insert(planarSLAM::PoseKey(4));
// i keeps track of the time step // i keeps track of the time step
size_t i = 0; size_t i = 0;

View File

@ -25,7 +25,7 @@
#include <boost/assign/std/vector.hpp> #include <boost/assign/std/vector.hpp>
using namespace boost::assign; using namespace boost::assign;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/debug.h> #include <gtsam/base/debug.h>
@ -43,6 +43,9 @@ using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
/* ************************************************************************* * /* ************************************************************************* *
Bayes tree for smoother with "nested dissection" ordering: Bayes tree for smoother with "nested dissection" ordering:
C1 x5 x6 x4 C1 x5 x6 x4
@ -53,20 +56,20 @@ using namespace example;
TEST( GaussianJunctionTree, constructor2 ) TEST( GaussianJunctionTree, constructor2 )
{ {
// create a graph // create a graph
Ordering ordering; ordering += "x1","x3","x5","x7","x2","x6","x4"; Ordering ordering; ordering += kx(1),kx(3),kx(5),kx(7),kx(2),kx(6),kx(4);
GaussianFactorGraph fg = createSmoother(7, ordering).first; GaussianFactorGraph fg = createSmoother(7, ordering).first;
// create an ordering // create an ordering
GaussianJunctionTree actual(fg); GaussianJunctionTree actual(fg);
vector<Index> frontal1; frontal1 += ordering["x5"], ordering["x6"], ordering["x4"]; vector<Index> frontal1; frontal1 += ordering[kx(5)], ordering[kx(6)], ordering[kx(4)];
vector<Index> frontal2; frontal2 += ordering["x3"], ordering["x2"]; vector<Index> frontal2; frontal2 += ordering[kx(3)], ordering[kx(2)];
vector<Index> frontal3; frontal3 += ordering["x1"]; vector<Index> frontal3; frontal3 += ordering[kx(1)];
vector<Index> frontal4; frontal4 += ordering["x7"]; vector<Index> frontal4; frontal4 += ordering[kx(7)];
vector<Index> sep1; vector<Index> sep1;
vector<Index> sep2; sep2 += ordering["x4"]; vector<Index> sep2; sep2 += ordering[kx(4)];
vector<Index> sep3; sep3 += ordering["x2"]; vector<Index> sep3; sep3 += ordering[kx(2)];
vector<Index> sep4; sep4 += ordering["x6"]; vector<Index> sep4; sep4 += ordering[kx(6)];
EXPECT(assert_equal(frontal1, actual.root()->frontal)); EXPECT(assert_equal(frontal1, actual.root()->frontal));
EXPECT(assert_equal(sep1, actual.root()->separator)); EXPECT(assert_equal(sep1, actual.root()->separator));
LONGS_EQUAL(5, actual.root()->size()); LONGS_EQUAL(5, actual.root()->size());
@ -111,7 +114,7 @@ TEST( GaussianJunctionTree, optimizeMultiFrontal2)
// create a graph // create a graph
example::Graph nlfg = createNonlinearFactorGraph(); example::Graph nlfg = createNonlinearFactorGraph();
Values noisy = createNoisyValues(); Values noisy = createNoisyValues();
Ordering ordering; ordering += "x1","x2","l1"; Ordering ordering; ordering += kx(1),kx(2),kl(1);
GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering); GaussianFactorGraph fg = *nlfg.linearize(noisy, ordering);
// optimize the graph // optimize the graph
@ -203,7 +206,7 @@ TEST(GaussianJunctionTree, simpleMarginal) {
init.insert(pose2SLAM::PoseKey(1), Pose2(1.0, 0.0, 0.0)); init.insert(pose2SLAM::PoseKey(1), Pose2(1.0, 0.0, 0.0));
Ordering ordering; Ordering ordering;
ordering += "x1", "x0"; ordering += kx(1), kx(0);
GaussianFactorGraph gfg = *fg.linearize(init, ordering); GaussianFactorGraph gfg = *fg.linearize(init, ordering);

View File

@ -34,26 +34,28 @@ using namespace boost::assign;
using namespace std; using namespace std;
using namespace gtsam; using namespace gtsam;
Key kx(size_t i) { return Symbol('x',i); }
/* ************************************************************************* */ /* ************************************************************************* */
// x1 -> x2 // x1 -> x2
// -> x3 -> x4 // -> x3 -> x4
// -> x5 // -> x5
TEST ( Ordering, predecessorMap2Keys ) { TEST ( Ordering, predecessorMap2Keys ) {
PredecessorMap<Symbol> p_map; PredecessorMap<Key> p_map;
p_map.insert("x1","x1"); p_map.insert(kx(1),kx(1));
p_map.insert("x2","x1"); p_map.insert(kx(2),kx(1));
p_map.insert("x3","x1"); p_map.insert(kx(3),kx(1));
p_map.insert("x4","x3"); p_map.insert(kx(4),kx(3));
p_map.insert("x5","x1"); p_map.insert(kx(5),kx(1));
list<Symbol> expected; list<Key> expected;
expected += "x4","x5","x3","x2","x1";//PoseKey(4), PoseKey(5), PoseKey(3), PoseKey(2), PoseKey(1); expected += kx(4),kx(5),kx(3),kx(2),kx(1);//PoseKey(4), PoseKey(5), PoseKey(3), PoseKey(2), PoseKey(1);
list<Symbol> actual = predecessorMap2Keys<Symbol>(p_map); list<Key> actual = predecessorMap2Keys<Key>(p_map);
LONGS_EQUAL(expected.size(), actual.size()); LONGS_EQUAL(expected.size(), actual.size());
list<Symbol>::const_iterator it1 = expected.begin(); list<Key>::const_iterator it1 = expected.begin();
list<Symbol>::const_iterator it2 = actual.begin(); list<Key>::const_iterator it2 = actual.begin();
for(; it1!=expected.end(); it1++, it2++) for(; it1!=expected.end(); it1++, it2++)
CHECK(*it1 == *it2) CHECK(*it1 == *it2)
} }
@ -62,18 +64,18 @@ TEST ( Ordering, predecessorMap2Keys ) {
TEST( Graph, predecessorMap2Graph ) TEST( Graph, predecessorMap2Graph )
{ {
typedef SGraph<string>::Vertex SVertex; typedef SGraph<string>::Vertex SVertex;
SGraph<string> graph; SGraph<Key> graph;
SVertex root; SVertex root;
map<string, SVertex> key2vertex; map<Key, SVertex> key2vertex;
PredecessorMap<string> p_map; PredecessorMap<Key> p_map;
p_map.insert("x1", "x2"); p_map.insert(kx(1), kx(2));
p_map.insert("x2", "x2"); p_map.insert(kx(2), kx(2));
p_map.insert("x3", "x2"); p_map.insert(kx(3), kx(2));
tie(graph, root, key2vertex) = predecessorMap2Graph<SGraph<string>, SVertex, string>(p_map); tie(graph, root, key2vertex) = predecessorMap2Graph<SGraph<Key>, SVertex, Key>(p_map);
LONGS_EQUAL(3, boost::num_vertices(graph)); LONGS_EQUAL(3, boost::num_vertices(graph));
CHECK(root == key2vertex["x2"]); CHECK(root == key2vertex[kx(2)]);
} }
/* ************************************************************************* */ /* ************************************************************************* */
@ -87,7 +89,7 @@ TEST( Graph, composePoses )
graph.addOdometry(2,3, p23, cov); graph.addOdometry(2,3, p23, cov);
graph.addOdometry(4,3, p43, cov); graph.addOdometry(4,3, p43, cov);
PredecessorMap<Symbol> tree; PredecessorMap<Key> tree;
tree.insert(pose2SLAM::PoseKey(1),pose2SLAM::PoseKey(2)); tree.insert(pose2SLAM::PoseKey(1),pose2SLAM::PoseKey(2));
tree.insert(pose2SLAM::PoseKey(2),pose2SLAM::PoseKey(2)); tree.insert(pose2SLAM::PoseKey(2),pose2SLAM::PoseKey(2));
tree.insert(pose2SLAM::PoseKey(3),pose2SLAM::PoseKey(2)); tree.insert(pose2SLAM::PoseKey(3),pose2SLAM::PoseKey(2));
@ -96,7 +98,7 @@ TEST( Graph, composePoses )
Pose2 rootPose = p2; Pose2 rootPose = p2;
boost::shared_ptr<Values> actual = composePoses<pose2SLAM::Graph, pose2SLAM::Odometry, boost::shared_ptr<Values> actual = composePoses<pose2SLAM::Graph, pose2SLAM::Odometry,
Pose2, Symbol> (graph, tree, rootPose); Pose2, Key> (graph, tree, rootPose);
Values expected; Values expected;
expected.insert(pose2SLAM::PoseKey(1), p1); expected.insert(pose2SLAM::PoseKey(1), p1);

View File

@ -25,7 +25,7 @@
// TODO: DANGEROUS, create shared pointers // TODO: DANGEROUS, create shared pointers
#define GTSAM_MAGIC_GAUSSIAN 2 #define GTSAM_MAGIC_GAUSSIAN 2
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like PoseKey(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
@ -211,7 +211,7 @@ TEST( NonlinearFactor, linearize_constraint1 )
// create expected // create expected
Ordering ord(*config.orderingArbitrary()); Ordering ord(*config.orderingArbitrary());
Vector b = Vector_(2, 0., -3.); Vector b = Vector_(2, 0., -3.);
JacobianFactor expected(ord["x1"], Matrix_(2,2, 5.0, 0.0, 0.0, 1.0), b, constraint); JacobianFactor expected(ord[PoseKey(1)], Matrix_(2,2, 5.0, 0.0, 0.0, 1.0), b, constraint);
CHECK(assert_equal((const GaussianFactor&)expected, *actual)); CHECK(assert_equal((const GaussianFactor&)expected, *actual));
} }
@ -233,15 +233,15 @@ TEST( NonlinearFactor, linearize_constraint2 )
Ordering ord(*config.orderingArbitrary()); Ordering ord(*config.orderingArbitrary());
Matrix A = Matrix_(2,2, 5.0, 0.0, 0.0, 1.0); Matrix A = Matrix_(2,2, 5.0, 0.0, 0.0, 1.0);
Vector b = Vector_(2, -15., -3.); Vector b = Vector_(2, -15., -3.);
JacobianFactor expected(ord["x1"], -1*A, ord["l1"], A, b, constraint); JacobianFactor expected(ord[PoseKey(1)], -1*A, ord[PointKey(1)], A, b, constraint);
CHECK(assert_equal((const GaussianFactor&)expected, *actual)); CHECK(assert_equal((const GaussianFactor&)expected, *actual));
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor4 : public NonlinearFactor4<LieVector, LieVector, LieVector, LieVector> { class TestFactor4 : public NoiseModelFactor4<LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor4<LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModelFactor4<LieVector, LieVector, LieVector, LieVector> Base;
TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4") {} TestFactor4() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4)) {}
virtual Vector virtual Vector
evaluateError(const LieVector& x1, const LieVector& x2, const LieVector& x3, const LieVector& x4, evaluateError(const LieVector& x1, const LieVector& x2, const LieVector& x3, const LieVector& x4,
@ -260,16 +260,16 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor4) { TEST(NonlinearFactor, NoiseModelFactor4) {
TestFactor4 tf; TestFactor4 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert(PoseKey(1), LieVector(1, 1.0));
tv.insert("x2", LieVector(1, 2.0)); tv.insert(PoseKey(2), LieVector(1, 2.0));
tv.insert("x3", LieVector(1, 3.0)); tv.insert(PoseKey(3), LieVector(1, 3.0));
tv.insert("x4", LieVector(1, 4.0)); tv.insert(PoseKey(4), LieVector(1, 4.0));
EXPECT(assert_equal(Vector_(1, 10.0), tf.unwhitenedError(tv))); EXPECT(assert_equal(Vector_(1, 10.0), tf.unwhitenedError(tv)));
DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9); DOUBLES_EQUAL(25.0/2.0, tf.error(tv), 1e-9);
Ordering ordering; ordering += "x1", "x2", "x3", "x4"; Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4);
JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering))); JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering)));
LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[0], 0);
LONGS_EQUAL(jf.keys()[1], 1); LONGS_EQUAL(jf.keys()[1], 1);
@ -283,10 +283,10 @@ TEST(NonlinearFactor, NonlinearFactor4) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor5 : public NonlinearFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> { class TestFactor5 : public NoiseModelFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModelFactor5<LieVector, LieVector, LieVector, LieVector, LieVector> Base;
TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5") {} TestFactor5() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5)) {}
virtual Vector virtual Vector
evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5,
@ -307,17 +307,17 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor5) { TEST(NonlinearFactor, NoiseModelFactor5) {
TestFactor5 tf; TestFactor5 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert(PoseKey(1), LieVector(1, 1.0));
tv.insert("x2", LieVector(1, 2.0)); tv.insert(PoseKey(2), LieVector(1, 2.0));
tv.insert("x3", LieVector(1, 3.0)); tv.insert(PoseKey(3), LieVector(1, 3.0));
tv.insert("x4", LieVector(1, 4.0)); tv.insert(PoseKey(4), LieVector(1, 4.0));
tv.insert("x5", LieVector(1, 5.0)); tv.insert(PoseKey(5), LieVector(1, 5.0));
EXPECT(assert_equal(Vector_(1, 15.0), tf.unwhitenedError(tv))); EXPECT(assert_equal(Vector_(1, 15.0), tf.unwhitenedError(tv)));
DOUBLES_EQUAL(56.25/2.0, tf.error(tv), 1e-9); DOUBLES_EQUAL(56.25/2.0, tf.error(tv), 1e-9);
Ordering ordering; ordering += "x1", "x2", "x3", "x4", "x5"; Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5);
JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering))); JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering)));
LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[0], 0);
LONGS_EQUAL(jf.keys()[1], 1); LONGS_EQUAL(jf.keys()[1], 1);
@ -333,10 +333,10 @@ TEST(NonlinearFactor, NonlinearFactor5) {
} }
/* ************************************************************************* */ /* ************************************************************************* */
class TestFactor6 : public NonlinearFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> { class TestFactor6 : public NoiseModelFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> {
public: public:
typedef NonlinearFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> Base; typedef NoiseModelFactor6<LieVector, LieVector, LieVector, LieVector, LieVector, LieVector> Base;
TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), "x1", "x2", "x3", "x4", "x5", "x6") {} TestFactor6() : Base(sharedSigmas(Vector_(1, 2.0)), PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5), PoseKey(6)) {}
virtual Vector virtual Vector
evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6, evaluateError(const X1& x1, const X2& x2, const X3& x3, const X4& x4, const X5& x5, const X6& x6,
@ -359,18 +359,18 @@ public:
}; };
/* ************************************ */ /* ************************************ */
TEST(NonlinearFactor, NonlinearFactor6) { TEST(NonlinearFactor, NoiseModelFactor6) {
TestFactor6 tf; TestFactor6 tf;
Values tv; Values tv;
tv.insert("x1", LieVector(1, 1.0)); tv.insert(PoseKey(1), LieVector(1, 1.0));
tv.insert("x2", LieVector(1, 2.0)); tv.insert(PoseKey(2), LieVector(1, 2.0));
tv.insert("x3", LieVector(1, 3.0)); tv.insert(PoseKey(3), LieVector(1, 3.0));
tv.insert("x4", LieVector(1, 4.0)); tv.insert(PoseKey(4), LieVector(1, 4.0));
tv.insert("x5", LieVector(1, 5.0)); tv.insert(PoseKey(5), LieVector(1, 5.0));
tv.insert("x6", LieVector(1, 6.0)); tv.insert(PoseKey(6), LieVector(1, 6.0));
EXPECT(assert_equal(Vector_(1, 21.0), tf.unwhitenedError(tv))); EXPECT(assert_equal(Vector_(1, 21.0), tf.unwhitenedError(tv)));
DOUBLES_EQUAL(110.25/2.0, tf.error(tv), 1e-9); DOUBLES_EQUAL(110.25/2.0, tf.error(tv), 1e-9);
Ordering ordering; ordering += "x1", "x2", "x3", "x4", "x5", "x6"; Ordering ordering; ordering += PoseKey(1), PoseKey(2), PoseKey(3), PoseKey(4), PoseKey(5), PoseKey(6);
JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering))); JacobianFactor jf(*boost::dynamic_pointer_cast<JacobianFactor>(tf.linearize(tv, ordering)));
LONGS_EQUAL(jf.keys()[0], 0); LONGS_EQUAL(jf.keys()[0], 0);
LONGS_EQUAL(jf.keys()[1], 1); LONGS_EQUAL(jf.keys()[1], 1);

View File

@ -39,6 +39,9 @@ using namespace boost::assign;
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
/* ************************************************************************* */ /* ************************************************************************* */
TEST( Graph, equals ) TEST( Graph, equals )
{ {
@ -64,19 +67,19 @@ TEST( Graph, error )
TEST( Graph, keys ) TEST( Graph, keys )
{ {
Graph fg = createNonlinearFactorGraph(); Graph fg = createNonlinearFactorGraph();
set<Symbol> actual = fg.keys(); set<Key> actual = fg.keys();
LONGS_EQUAL(3, actual.size()); LONGS_EQUAL(3, actual.size());
set<Symbol>::const_iterator it = actual.begin(); set<Key>::const_iterator it = actual.begin();
CHECK(assert_equal(Symbol('l', 1), *(it++))); LONGS_EQUAL(kl(1), *(it++));
CHECK(assert_equal(Symbol('x', 1), *(it++))); LONGS_EQUAL(kx(1), *(it++));
CHECK(assert_equal(Symbol('x', 2), *(it++))); LONGS_EQUAL(kx(2), *(it++));
} }
/* ************************************************************************* */ /* ************************************************************************* */
TEST( Graph, GET_ORDERING) TEST( Graph, GET_ORDERING)
{ {
// Ordering expected; expected += "x1","l1","x2"; // For starting with x1,x2,l1 // Ordering expected; expected += "x1","l1","x2"; // For starting with x1,x2,l1
Ordering expected; expected += "l1","x2","x1"; // For starting with l1,x1,x2 Ordering expected; expected += kl(1), kx(2), kx(1); // For starting with l1,x1,x2
Graph nlfg = createNonlinearFactorGraph(); Graph nlfg = createNonlinearFactorGraph();
SymbolicFactorGraph::shared_ptr symbolic; SymbolicFactorGraph::shared_ptr symbolic;
Ordering::shared_ptr ordering; Ordering::shared_ptr ordering;

View File

@ -48,8 +48,8 @@ TEST(testNonlinearISAM, markov_chain ) {
Ordering ordering = isam.getOrdering(); Ordering ordering = isam.getOrdering();
// swap last two elements // swap last two elements
Symbol last = ordering.pop_back().first; Key last = ordering.pop_back().first;
Symbol secondLast = ordering.pop_back().first; Key secondLast = ordering.pop_back().first;
ordering.push_back(last); ordering.push_back(last);
ordering.push_back(secondLast); ordering.push_back(secondLast);
isam.setOrdering(ordering); isam.setOrdering(ordering);

View File

@ -26,7 +26,7 @@ using namespace boost::assign;
#include <boost/shared_ptr.hpp> #include <boost/shared_ptr.hpp>
using namespace boost; using namespace boost;
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Matrix.h> #include <gtsam/base/Matrix.h>
@ -44,6 +44,9 @@ using namespace gtsam;
const double tol = 1e-5; const double tol = 1e-5;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
typedef NonlinearOptimizer<example::Graph> Optimizer; typedef NonlinearOptimizer<example::Graph> Optimizer;
/* ************************************************************************* */ /* ************************************************************************* */
@ -55,20 +58,20 @@ TEST( NonlinearOptimizer, linearizeAndOptimizeForDelta )
// Expected values structure is the difference between the noisy config // Expected values structure is the difference between the noisy config
// and the ground-truth config. One step only because it's linear ! // and the ground-truth config. One step only because it's linear !
Ordering ord1; ord1 += "x2","l1","x1"; Ordering ord1; ord1 += kx(2),kl(1),kx(1);
VectorValues expected(initial->dims(ord1)); VectorValues expected(initial->dims(ord1));
Vector dl1(2); Vector dl1(2);
dl1(0) = -0.1; dl1(0) = -0.1;
dl1(1) = 0.1; dl1(1) = 0.1;
expected[ord1["l1"]] = dl1; expected[ord1[kl(1)]] = dl1;
Vector dx1(2); Vector dx1(2);
dx1(0) = -0.1; dx1(0) = -0.1;
dx1(1) = -0.1; dx1(1) = -0.1;
expected[ord1["x1"]] = dx1; expected[ord1[kx(1)]] = dx1;
Vector dx2(2); Vector dx2(2);
dx2(0) = 0.1; dx2(0) = 0.1;
dx2(1) = -0.2; dx2(1) = -0.2;
expected[ord1["x2"]] = dx2; expected[ord1[kx(2)]] = dx2;
// Check one ordering // Check one ordering
Optimizer optimizer1(fg, initial, Optimizer::shared_ordering(new Ordering(ord1))); Optimizer optimizer1(fg, initial, Optimizer::shared_ordering(new Ordering(ord1)));
@ -78,7 +81,7 @@ TEST( NonlinearOptimizer, linearizeAndOptimizeForDelta )
// SL-FIX // Check another // SL-FIX // Check another
// shared_ptr<Ordering> ord2(new Ordering()); // shared_ptr<Ordering> ord2(new Ordering());
// *ord2 += "x1","x2","l1"; // *ord2 += kx(1),kx(2),kl(1);
// solver = Optimizer::shared_solver(new Optimizer::solver(ord2)); // solver = Optimizer::shared_solver(new Optimizer::solver(ord2));
// Optimizer optimizer2(fg, initial, solver); // Optimizer optimizer2(fg, initial, solver);
// //
@ -87,7 +90,7 @@ TEST( NonlinearOptimizer, linearizeAndOptimizeForDelta )
// //
// // And yet another... // // And yet another...
// shared_ptr<Ordering> ord3(new Ordering()); // shared_ptr<Ordering> ord3(new Ordering());
// *ord3 += "l1","x1","x2"; // *ord3 += kl(1),kx(1),kx(2);
// solver = Optimizer::shared_solver(new Optimizer::solver(ord3)); // solver = Optimizer::shared_solver(new Optimizer::solver(ord3));
// Optimizer optimizer3(fg, initial, solver); // Optimizer optimizer3(fg, initial, solver);
// //
@ -96,7 +99,7 @@ TEST( NonlinearOptimizer, linearizeAndOptimizeForDelta )
// //
// // More... // // More...
// shared_ptr<Ordering> ord4(new Ordering()); // shared_ptr<Ordering> ord4(new Ordering());
// *ord4 += "x1","x2", "l1"; // *ord4 += kx(1),kx(2), kl(1);
// solver = Optimizer::shared_solver(new Optimizer::solver(ord4)); // solver = Optimizer::shared_solver(new Optimizer::solver(ord4));
// Optimizer optimizer4(fg, initial, solver); // Optimizer optimizer4(fg, initial, solver);
// //
@ -118,7 +121,7 @@ TEST( NonlinearOptimizer, iterateLM )
// ordering // ordering
shared_ptr<Ordering> ord(new Ordering()); shared_ptr<Ordering> ord(new Ordering());
ord->push_back("x1"); ord->push_back(kx(1));
// create initial optimization state, with lambda=0 // create initial optimization state, with lambda=0
Optimizer optimizer(fg, config, ord, NonlinearOptimizationParameters::newLambda(0.)); Optimizer optimizer(fg, config, ord, NonlinearOptimizationParameters::newLambda(0.));
@ -161,7 +164,7 @@ TEST( NonlinearOptimizer, optimize )
// optimize parameters // optimize parameters
shared_ptr<Ordering> ord(new Ordering()); shared_ptr<Ordering> ord(new Ordering());
ord->push_back("x1"); ord->push_back(kx(1));
// initial optimization state is the same in both cases tested // initial optimization state is the same in both cases tested
boost::shared_ptr<NonlinearOptimizationParameters> params = boost::make_shared<NonlinearOptimizationParameters>(); boost::shared_ptr<NonlinearOptimizationParameters> params = boost::make_shared<NonlinearOptimizationParameters>();
@ -299,7 +302,7 @@ TEST_UNSAFE(NonlinearOptimizer, NullFactor) {
// optimize parameters // optimize parameters
shared_ptr<Ordering> ord(new Ordering()); shared_ptr<Ordering> ord(new Ordering());
ord->push_back("x1"); ord->push_back(kx(1));
// initial optimization state is the same in both cases tested // initial optimization state is the same in both cases tested
boost::shared_ptr<NonlinearOptimizationParameters> params = boost::make_shared<NonlinearOptimizationParameters>(); boost::shared_ptr<NonlinearOptimizationParameters> params = boost::make_shared<NonlinearOptimizationParameters>();
@ -367,7 +370,7 @@ TEST_UNSAFE(NonlinearOptimizer, NullFactor) {
// //
// // Check one ordering // // Check one ordering
// shared_ptr<Ordering> ord1(new Ordering()); // shared_ptr<Ordering> ord1(new Ordering());
// *ord1 += "x2","l1","x1"; // *ord1 += kx(2),kl(1),kx(1);
// solver = Optimizer::shared_solver(new Optimizer::solver(ord1)); // solver = Optimizer::shared_solver(new Optimizer::solver(ord1));
// Optimizer optimizer1(fg, initial, solver); // Optimizer optimizer1(fg, initial, solver);
// //

View File

@ -21,7 +21,7 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/base/Testable.h> #include <gtsam/base/Testable.h>
@ -34,6 +34,9 @@ using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
//Symbol _B_('B', 0), _L_('L', 0); //Symbol _B_('B', 0), _L_('L', 0);
//IndexConditional::shared_ptr //IndexConditional::shared_ptr
// B(new IndexConditional(_B_)), // B(new IndexConditional(_B_)),
@ -42,12 +45,12 @@ using namespace example;
/* ************************************************************************* */ /* ************************************************************************* */
TEST( SymbolicBayesNet, constructor ) TEST( SymbolicBayesNet, constructor )
{ {
Ordering o; o += "x2","l1","x1"; Ordering o; o += kx(2),kl(1),kx(1);
// Create manually // Create manually
IndexConditional::shared_ptr IndexConditional::shared_ptr
x2(new IndexConditional(o["x2"],o["l1"], o["x1"])), x2(new IndexConditional(o[kx(2)],o[kl(1)], o[kx(1)])),
l1(new IndexConditional(o["l1"],o["x1"])), l1(new IndexConditional(o[kl(1)],o[kx(1)])),
x1(new IndexConditional(o["x1"])); x1(new IndexConditional(o[kx(1)]));
BayesNet<IndexConditional> expected; BayesNet<IndexConditional> expected;
expected.push_back(x2); expected.push_back(x2);
expected.push_back(l1); expected.push_back(l1);

View File

@ -20,7 +20,7 @@ using namespace boost::assign;
#include <CppUnitLite/TestHarness.h> #include <CppUnitLite/TestHarness.h>
// Magically casts strings like "x3" to a Symbol('x',3) key, see Symbol.h // Magically casts strings like kx(3) to a Symbol('x',3) key, see Symbol.h
#define GTSAM_MAGIC_KEY #define GTSAM_MAGIC_KEY
#include <gtsam/slam/smallExample.h> #include <gtsam/slam/smallExample.h>
@ -33,16 +33,19 @@ using namespace std;
using namespace gtsam; using namespace gtsam;
using namespace example; using namespace example;
Key kx(size_t i) { return Symbol('x',i); }
Key kl(size_t i) { return Symbol('l',i); }
/* ************************************************************************* */ /* ************************************************************************* */
TEST( SymbolicFactorGraph, symbolicFactorGraph ) TEST( SymbolicFactorGraph, symbolicFactorGraph )
{ {
Ordering o; o += "x1","l1","x2"; Ordering o; o += kx(1),kl(1),kx(2);
// construct expected symbolic graph // construct expected symbolic graph
SymbolicFactorGraph expected; SymbolicFactorGraph expected;
expected.push_factor(o["x1"]); expected.push_factor(o[kx(1)]);
expected.push_factor(o["x1"],o["x2"]); expected.push_factor(o[kx(1)],o[kx(2)]);
expected.push_factor(o["x1"],o["l1"]); expected.push_factor(o[kx(1)],o[kl(1)]);
expected.push_factor(o["x2"],o["l1"]); expected.push_factor(o[kx(2)],o[kl(1)]);
// construct it from the factor graph // construct it from the factor graph
GaussianFactorGraph factorGraph = createGaussianFactorGraph(o); GaussianFactorGraph factorGraph = createGaussianFactorGraph(o);
@ -59,7 +62,7 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
// SymbolicFactorGraph actual(factorGraph); // SymbolicFactorGraph actual(factorGraph);
// SymbolicFactor::shared_ptr f1 = actual[0]; // SymbolicFactor::shared_ptr f1 = actual[0];
// SymbolicFactor::shared_ptr f3 = actual[2]; // SymbolicFactor::shared_ptr f3 = actual[2];
// actual.findAndRemoveFactors("x2"); // actual.findAndRemoveFactors(kx(2));
// //
// // construct expected graph after find_factors_and_remove // // construct expected graph after find_factors_and_remove
// SymbolicFactorGraph expected; // SymbolicFactorGraph expected;
@ -79,13 +82,13 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
// SymbolicFactorGraph fg(factorGraph); // SymbolicFactorGraph fg(factorGraph);
// //
// // ask for all factor indices connected to x1 // // ask for all factor indices connected to x1
// list<size_t> x1_factors = fg.factors("x1"); // list<size_t> x1_factors = fg.factors(kx(1));
// int x1_indices[] = { 0, 1, 2 }; // int x1_indices[] = { 0, 1, 2 };
// list<size_t> x1_expected(x1_indices, x1_indices + 3); // list<size_t> x1_expected(x1_indices, x1_indices + 3);
// CHECK(x1_factors==x1_expected); // CHECK(x1_factors==x1_expected);
// //
// // ask for all factor indices connected to x2 // // ask for all factor indices connected to x2
// list<size_t> x2_factors = fg.factors("x2"); // list<size_t> x2_factors = fg.factors(kx(2));
// int x2_indices[] = { 1, 3 }; // int x2_indices[] = { 1, 3 };
// list<size_t> x2_expected(x2_indices, x2_indices + 2); // list<size_t> x2_expected(x2_indices, x2_indices + 2);
// CHECK(x2_factors==x2_expected); // CHECK(x2_factors==x2_expected);
@ -99,26 +102,26 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
// SymbolicFactorGraph fg(factorGraph); // SymbolicFactorGraph fg(factorGraph);
// //
// // combine all factors connected to x1 // // combine all factors connected to x1
// SymbolicFactor::shared_ptr actual = removeAndCombineFactors(fg,"x1"); // SymbolicFactor::shared_ptr actual = removeAndCombineFactors(fg,kx(1));
// //
// // check result // // check result
// SymbolicFactor expected("l1","x1","x2"); // SymbolicFactor expected(kl(1),kx(1),kx(2));
// CHECK(assert_equal(expected,*actual)); // CHECK(assert_equal(expected,*actual));
//} //}
///* ************************************************************************* */ ///* ************************************************************************* */
//TEST( SymbolicFactorGraph, eliminateOne ) //TEST( SymbolicFactorGraph, eliminateOne )
//{ //{
// Ordering o; o += "x1","l1","x2"; // Ordering o; o += kx(1),kl(1),kx(2);
// // create a test graph // // create a test graph
// GaussianFactorGraph factorGraph = createGaussianFactorGraph(o); // GaussianFactorGraph factorGraph = createGaussianFactorGraph(o);
// SymbolicFactorGraph fg(factorGraph); // SymbolicFactorGraph fg(factorGraph);
// //
// // eliminate // // eliminate
// IndexConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, o["x1"]+1); // IndexConditional::shared_ptr actual = GaussianSequentialSolver::EliminateUntil(fg, o[kx(1)]+1);
// //
// // create expected symbolic IndexConditional // // create expected symbolic IndexConditional
// IndexConditional expected(o["x1"],o["l1"],o["x2"]); // IndexConditional expected(o[kx(1)],o[kl(1)],o[kx(2)]);
// //
// CHECK(assert_equal(expected,*actual)); // CHECK(assert_equal(expected,*actual));
//} //}
@ -126,12 +129,12 @@ TEST( SymbolicFactorGraph, symbolicFactorGraph )
/* ************************************************************************* */ /* ************************************************************************* */
TEST( SymbolicFactorGraph, eliminate ) TEST( SymbolicFactorGraph, eliminate )
{ {
Ordering o; o += "x2","l1","x1"; Ordering o; o += kx(2),kl(1),kx(1);
// create expected Chordal bayes Net // create expected Chordal bayes Net
IndexConditional::shared_ptr x2(new IndexConditional(o["x2"], o["l1"], o["x1"])); IndexConditional::shared_ptr x2(new IndexConditional(o[kx(2)], o[kl(1)], o[kx(1)]));
IndexConditional::shared_ptr l1(new IndexConditional(o["l1"], o["x1"])); IndexConditional::shared_ptr l1(new IndexConditional(o[kl(1)], o[kx(1)]));
IndexConditional::shared_ptr x1(new IndexConditional(o["x1"])); IndexConditional::shared_ptr x1(new IndexConditional(o[kx(1)]));
SymbolicBayesNet expected; SymbolicBayesNet expected;
expected.push_back(x2); expected.push_back(x2);