Template arguments capitlized

release/4.3a0
Rahul Sawhney 2010-10-20 18:02:08 +00:00
parent 82a2f29e48
commit 11a822a9f2
2 changed files with 164 additions and 164 deletions

View File

@ -49,140 +49,140 @@ namespace gtsam {
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 1 */ /** TupleValues 1 */
template<class Values1> template<class VALUES1>
TupleValues1<Values1>::TupleValues1(const TupleValues1<Values1>& config) : TupleValues1<VALUES1>::TupleValues1(const TupleValues1<VALUES1>& config) :
TupleValuesEnd<Values1> (config) {} TupleValuesEnd<VALUES1> (config) {}
template<class Values1> template<class VALUES1>
TupleValues1<Values1>::TupleValues1(const Values1& cfg1) : TupleValues1<VALUES1>::TupleValues1(const VALUES1& cfg1) :
TupleValuesEnd<Values1> (cfg1) {} TupleValuesEnd<VALUES1> (cfg1) {}
template<class Values1> template<class VALUES1>
TupleValues1<Values1>::TupleValues1(const TupleValuesEnd<Values1>& config) : TupleValues1<VALUES1>::TupleValues1(const TupleValuesEnd<VALUES1>& config) :
TupleValuesEnd<Values1>(config) {} TupleValuesEnd<VALUES1>(config) {}
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 2 */ /** TupleValues 2 */
template<class Values1, class Values2> template<class VALUES1, class VALUES2>
TupleValues2<Values1, Values2>::TupleValues2(const TupleValues2<Values1, Values2>& config) : TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues2<VALUES1, VALUES2>& config) :
TupleValues<Values1, TupleValuesEnd<Values2> >(config) {} TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(config) {}
template<class Values1, class Values2> template<class VALUES1, class VALUES2>
TupleValues2<Values1, Values2>::TupleValues2(const Values1& cfg1, const Values2& cfg2) : TupleValues2<VALUES1, VALUES2>::TupleValues2(const VALUES1& cfg1, const VALUES2& cfg2) :
TupleValues<Values1, TupleValuesEnd<Values2> >( TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(
cfg1, TupleValuesEnd<Values2>(cfg2)) {} cfg1, TupleValuesEnd<VALUES2>(cfg2)) {}
template<class Values1, class Values2> template<class VALUES1, class VALUES2>
TupleValues2<Values1, Values2>::TupleValues2(const TupleValues<Values1, TupleValuesEnd<Values2> >& config) : TupleValues2<VALUES1, VALUES2>::TupleValues2(const TupleValues<VALUES1, TupleValuesEnd<VALUES2> >& config) :
TupleValues<Values1, TupleValuesEnd<Values2> >(config) {} TupleValues<VALUES1, TupleValuesEnd<VALUES2> >(config) {}
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 3 */ /** TupleValues 3 */
template<class Values1, class Values2, class Values3> template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<Values1, Values2, Values3>::TupleValues3( TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
const TupleValues3<Values1, Values2, Values3>& config) : const TupleValues3<VALUES1, VALUES2, VALUES3>& config) :
TupleValues<Values1, TupleValues<Values2, TupleValuesEnd<Values3> > >(config) {} TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(config) {}
template<class Values1, class Values2, class Values3> template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<Values1, Values2, Values3>::TupleValues3( TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
const Values1& cfg1, const Values2& cfg2, const Values3& cfg3) : const VALUES1& cfg1, const VALUES2& cfg2, const VALUES3& cfg3) :
TupleValues<Values1, TupleValues<Values2, TupleValuesEnd<Values3> > >( TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(
cfg1, TupleValues<Values2, TupleValuesEnd<Values3> >( cfg1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> >(
cfg2, TupleValuesEnd<Values3>(cfg3))) {} cfg2, TupleValuesEnd<VALUES3>(cfg3))) {}
template<class Values1, class Values2, class Values3> template<class VALUES1, class VALUES2, class VALUES3>
TupleValues3<Values1, Values2, Values3>::TupleValues3( TupleValues3<VALUES1, VALUES2, VALUES3>::TupleValues3(
const TupleValues<Values1, TupleValues<Values2, TupleValuesEnd<Values3> > >& config) : const TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >& config) :
TupleValues<Values1, TupleValues<Values2, TupleValuesEnd<Values3> > >(config) {} TupleValues<VALUES1, TupleValues<VALUES2, TupleValuesEnd<VALUES3> > >(config) {}
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 4 */ /** TupleValues 4 */
template<class Values1, class Values2, class Values3, class Values4> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<Values1, Values2, Values3, Values4>::TupleValues4( TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
const TupleValues4<Values1, Values2, Values3, Values4>& config) : const TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>& config) :
TupleValues<Values1, TupleValues<Values2, TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<Values3, TupleValuesEnd<Values4> > > >(config) {} TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >(config) {}
template<class Values1, class Values2, class Values3, class Values4> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<Values1, Values2, Values3, Values4>::TupleValues4( TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
const Values1& cfg1, const Values2& cfg2, const VALUES1& cfg1, const VALUES2& cfg2,
const Values3& cfg3,const Values4& cfg4) : const VALUES3& cfg3,const VALUES4& cfg4) :
TupleValues<Values1, TupleValues<Values2, TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<Values3, TupleValuesEnd<Values4> > > >( TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >(
cfg1, TupleValues<Values2, TupleValues<Values3, TupleValuesEnd<Values4> > >( cfg1, TupleValues<VALUES2, TupleValues<VALUES3, TupleValuesEnd<VALUES4> > >(
cfg2, TupleValues<Values3, TupleValuesEnd<Values4> >( cfg2, TupleValues<VALUES3, TupleValuesEnd<VALUES4> >(
cfg3, TupleValuesEnd<Values4>(cfg4)))) {} cfg3, TupleValuesEnd<VALUES4>(cfg4)))) {}
template<class Values1, class Values2, class Values3, class Values4> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4>
TupleValues4<Values1, Values2, Values3, Values4>::TupleValues4( TupleValues4<VALUES1, VALUES2, VALUES3, VALUES4>::TupleValues4(
const TupleValues<Values1, TupleValues<Values2, const TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<Values3, TupleValuesEnd<Values4> > > >& config) : TupleValues<VALUES3, TupleValuesEnd<VALUES4> > > >& config) :
TupleValues<Values1, TupleValues<Values2,TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2,TupleValues<VALUES3,
TupleValuesEnd<Values4> > > >(config) {} TupleValuesEnd<VALUES4> > > >(config) {}
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 5 */ /** TupleValues 5 */
template<class Values1, class Values2, class Values3, class Values4, class Values5> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<Values1, Values2, Values3, Values4, Values5>::TupleValues5( TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
const TupleValues5<Values1, Values2, Values3, Values4, Values5>& config) : const TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>& config) :
TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValuesEnd<Values5> > > > >(config) {} TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(config) {}
template<class Values1, class Values2, class Values3, class Values4, class Values5> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<Values1, Values2, Values3, Values4, Values5>::TupleValues5( TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
const Values1& cfg1, const Values2& cfg2, const Values3& cfg3, const VALUES1& cfg1, const VALUES2& cfg2, const VALUES3& cfg3,
const Values4& cfg4, const Values5& cfg5) : const VALUES4& cfg4, const VALUES5& cfg5) :
TupleValues<Values1, TupleValues<Values2, TupleValues<VALUES1, TupleValues<VALUES2,
TupleValues<Values3, TupleValues<Values4, TupleValues<VALUES3, TupleValues<VALUES4,
TupleValuesEnd<Values5> > > > >( TupleValuesEnd<VALUES5> > > > >(
cfg1, TupleValues<Values2, TupleValues<Values3, cfg1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValuesEnd<Values5> > > >( TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > >(
cfg2, TupleValues<Values3, TupleValues<Values4, TupleValuesEnd<Values5> > >( cfg2, TupleValues<VALUES3, TupleValues<VALUES4, TupleValuesEnd<VALUES5> > >(
cfg3, TupleValues<Values4, TupleValuesEnd<Values5> >( cfg3, TupleValues<VALUES4, TupleValuesEnd<VALUES5> >(
cfg4, TupleValuesEnd<Values5>(cfg5))))) {} cfg4, TupleValuesEnd<VALUES5>(cfg5))))) {}
template<class Values1, class Values2, class Values3, class Values4, class Values5> template<class VALUES1, class VALUES2, class VALUES3, class VALUES4, class VALUES5>
TupleValues5<Values1, Values2, Values3, Values4, Values5>::TupleValues5( TupleValues5<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5>::TupleValues5(
const TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, const TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValuesEnd<Values5> > > > >& config) : TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >& config) :
TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValuesEnd<Values5> > > > >(config) {} TupleValues<VALUES4, TupleValuesEnd<VALUES5> > > > >(config) {}
/* ************************************************************************* */ /* ************************************************************************* */
/** TupleValues 6 */ /** TupleValues 6 */
template<class Values1, class Values2, class Values3, template<class VALUES1, class VALUES2, class VALUES3,
class Values4, class Values5, class Values6> class VALUES4, class VALUES5, class VALUES6>
TupleValues6<Values1, Values2, Values3, Values4, Values5, Values6>::TupleValues6( TupleValues6<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5, VALUES6>::TupleValues6(
const TupleValues6<Values1, Values2, Values3, const TupleValues6<VALUES1, VALUES2, VALUES3,
Values4, Values5, Values6>& config) : VALUES4, VALUES5, VALUES6>& config) :
TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValues<Values5, TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<Values6> > > > > >(config) {} TupleValuesEnd<VALUES6> > > > > >(config) {}
template<class Values1, class Values2, class Values3, template<class VALUES1, class VALUES2, class VALUES3,
class Values4, class Values5, class Values6> class VALUES4, class VALUES5, class VALUES6>
TupleValues6<Values1, Values2, Values3, Values4, Values5, Values6>::TupleValues6( TupleValues6<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5, VALUES6>::TupleValues6(
const Values1& cfg1, const Values2& cfg2, const Values3& cfg3, const VALUES1& cfg1, const VALUES2& cfg2, const VALUES3& cfg3,
const Values4& cfg4, const Values5& cfg5, const Values6& cfg6) : const VALUES4& cfg4, const VALUES5& cfg5, const VALUES6& cfg6) :
TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValues<Values5, TupleValuesEnd<Values6> > > > > >( TupleValues<VALUES4, TupleValues<VALUES5, TupleValuesEnd<VALUES6> > > > > >(
cfg1, TupleValues<Values2, TupleValues<Values3, TupleValues<Values4, cfg1, TupleValues<VALUES2, TupleValues<VALUES3, TupleValues<VALUES4,
TupleValues<Values5, TupleValuesEnd<Values6> > > > >( TupleValues<VALUES5, TupleValuesEnd<VALUES6> > > > >(
cfg2, TupleValues<Values3, TupleValues<Values4, TupleValues<Values5, cfg2, TupleValues<VALUES3, TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<Values6> > > >( TupleValuesEnd<VALUES6> > > >(
cfg3, TupleValues<Values4, TupleValues<Values5, cfg3, TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<Values6> > >( TupleValuesEnd<VALUES6> > >(
cfg4, TupleValues<Values5, TupleValuesEnd<Values6> >( cfg4, TupleValues<VALUES5, TupleValuesEnd<VALUES6> >(
cfg5, TupleValuesEnd<Values6>(cfg6)))))) {} cfg5, TupleValuesEnd<VALUES6>(cfg6)))))) {}
template<class Values1, class Values2, class Values3, template<class VALUES1, class VALUES2, class VALUES3,
class Values4, class Values5, class Values6> class VALUES4, class VALUES5, class VALUES6>
TupleValues6<Values1, Values2, Values3, Values4, Values5, Values6>::TupleValues6( TupleValues6<VALUES1, VALUES2, VALUES3, VALUES4, VALUES5, VALUES6>::TupleValues6(
const TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, const TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValues<Values5, TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<Values6> > > > > >& config) : TupleValuesEnd<VALUES6> > > > > >& config) :
TupleValues<Values1, TupleValues<Values2, TupleValues<Values3, TupleValues<VALUES1, TupleValues<VALUES2, TupleValues<VALUES3,
TupleValues<Values4, TupleValues<Values5, TupleValues<VALUES4, TupleValues<VALUES5,
TupleValuesEnd<Values6> > > > > >(config) {} TupleValuesEnd<VALUES6> > > > > >(config) {}
} }

View File

@ -46,28 +46,28 @@ namespace gtsam {
* for the arguments to be passed to the next config, while the specialized one * for the arguments to be passed to the next config, while the specialized one
* operates on the "first" config. TupleValuesEnd contains only the specialized version. * operates on the "first" config. TupleValuesEnd contains only the specialized version.
*/ */
template<class Values1, class Values2> template<class VALUES1, class VALUES2>
class TupleValues : public Testable<TupleValues<Values1, Values2> > { class TupleValues : public Testable<TupleValues<VALUES1, VALUES2> > {
protected: protected:
// Data for internal configs // Data for internal configs
Values1 first_; /// Arbitrary config VALUES1 first_; /// Arbitrary config
Values2 second_; /// A TupleValues or TupleValuesEnd, which wraps an arbitrary config VALUES2 second_; /// A TupleValues or TupleValuesEnd, which wraps an arbitrary config
public: public:
// typedefs for config subtypes // typedefs for config subtypes
typedef class Values1::Key Key1; typedef class VALUES1::Key Key1;
typedef class Values1::Value Value1; typedef class VALUES1::Value Value1;
/** default constructor */ /** default constructor */
TupleValues() {} TupleValues() {}
/** Copy constructor */ /** Copy constructor */
TupleValues(const TupleValues<Values1, Values2>& config) : TupleValues(const TupleValues<VALUES1, VALUES2>& config) :
first_(config.first_), second_(config.second_) {} first_(config.first_), second_(config.second_) {}
/** Construct from configs */ /** Construct from configs */
TupleValues(const Values1& cfg1, const Values2& cfg2) : TupleValues(const VALUES1& cfg1, const VALUES2& cfg2) :
first_(cfg1), second_(cfg2) {} first_(cfg1), second_(cfg2) {}
/** Print */ /** Print */
@ -77,7 +77,7 @@ namespace gtsam {
} }
/** Equality with tolerance for keys and values */ /** Equality with tolerance for keys and values */
bool equals(const TupleValues<Values1, Values2>& c, double tol=1e-9) const { bool equals(const TupleValues<VALUES1, VALUES2>& c, double tol=1e-9) const {
return first_.equals(c.first_, tol) && second_.equals(c.second_, tol); return first_.equals(c.first_, tol) && second_.equals(c.second_, tol);
} }
@ -88,8 +88,8 @@ namespace gtsam {
* @param key is the key - can be an int (second version) if the can can be initialized from an int * @param key is the key - can be an int (second version) if the can can be initialized from an int
* @param value is the value to insert * @param value is the value to insert
*/ */
template<class Key, class Value> template<class KEY, class VALUE>
void insert(const Key& key, const Value& value) {second_.insert(key, value);} void insert(const KEY& key, const VALUE& value) {second_.insert(key, value);}
void insert(int key, const Value1& value) {first_.insert(Key1(key), value);} void insert(int key, const Value1& value) {first_.insert(Key1(key), value);}
void insert(const Key1& key, const Value1& value) {first_.insert(key, value);} void insert(const Key1& key, const Value1& value) {first_.insert(key, value);}
@ -99,9 +99,9 @@ namespace gtsam {
* Use update() to allow for changing existing values. * Use update() to allow for changing existing values.
* @param config is a full config to add * @param config is a full config to add
*/ */
template<class Cfg1, class Cfg2> template<class CFG1, class CFG2>
void insert(const TupleValues<Cfg1, Cfg2>& config) { second_.insert(config); } void insert(const TupleValues<CFG1, CFG2>& config) { second_.insert(config); }
void insert(const TupleValues<Values1, Values2>& config) { void insert(const TupleValues<VALUES1, VALUES2>& config) {
first_.insert(config.first_); first_.insert(config.first_);
second_.insert(config.second_); second_.insert(config.second_);
} }
@ -110,9 +110,9 @@ namespace gtsam {
* Update function for whole configs - this will change existing values * Update function for whole configs - this will change existing values
* @param config is a config to add * @param config is a config to add
*/ */
template<class Cfg1, class Cfg2> template<class CFG1, class CFG2>
void update(const TupleValues<Cfg1, Cfg2>& config) { second_.update(config); } void update(const TupleValues<CFG1, CFG2>& config) { second_.update(config); }
void update(const TupleValues<Values1, Values2>& config) { void update(const TupleValues<VALUES1, VALUES2>& config) {
first_.update(config.first_); first_.update(config.first_);
second_.update(config.second_); second_.update(config.second_);
} }
@ -122,49 +122,49 @@ namespace gtsam {
* @param key is the variable identifier * @param key is the variable identifier
* @param value is the variable value to update * @param value is the variable value to update
*/ */
template<class Key, class Value> template<class KEY, class VALUE>
void update(const Key& key, const Value& value) { second_.update(key, value); } void update(const KEY& key, const VALUE& value) { second_.update(key, value); }
void update(const Key1& key, const Value1& value) { first_.update(key, value); } void update(const Key1& key, const Value1& value) { first_.update(key, value); }
/** /**
* Insert a subconfig * Insert a subconfig
* @param config is the config to insert * @param config is the config to insert
*/ */
template<class Cfg> template<class CFG>
void insertSub(const Cfg& config) { second_.insertSub(config); } void insertSub(const CFG& config) { second_.insertSub(config); }
void insertSub(const Values1& config) { first_.insert(config); } void insertSub(const VALUES1& config) { first_.insert(config); }
/** erase an element by key */ /** erase an element by key */
template<class Key> template<class KEY>
void erase(const Key& j) { second_.erase(j); } void erase(const KEY& j) { second_.erase(j); }
void erase(const Key1& j) { first_.erase(j); } void erase(const Key1& j) { first_.erase(j); }
/** clears the config */ /** clears the config */
void clear() { first_.clear(); second_.clear(); } void clear() { first_.clear(); second_.clear(); }
/** determine whether an element exists */ /** determine whether an element exists */
template<class Key> template<class KEY>
bool exists(const Key& j) const { return second_.exists(j); } bool exists(const KEY& j) const { return second_.exists(j); }
bool exists(const Key1& j) const { return first_.exists(j); } bool exists(const Key1& j) const { return first_.exists(j); }
/** a variant of exists */ /** a variant of exists */
template<class Key> template<class KEY>
boost::optional<typename Key::Value> exists_(const Key& j) const { return second_.exists_(j); } boost::optional<typename KEY::Value> exists_(const KEY& j) const { return second_.exists_(j); }
boost::optional<Value1> exists_(const Key1& j) const { return first_.exists_(j); } boost::optional<Value1> exists_(const Key1& j) const { return first_.exists_(j); }
/** access operator */ /** access operator */
template<class Key> template<class KEY>
const typename Key::Value & operator[](const Key& j) const { return second_[j]; } const typename KEY::Value & operator[](const KEY& j) const { return second_[j]; }
const Value1& operator[](const Key1& j) const { return first_[j]; } const Value1& operator[](const Key1& j) const { return first_[j]; }
/** at access function */ /** at access function */
template<class Key> template<class KEY>
const typename Key::Value & at(const Key& j) const { return second_.at(j); } const typename KEY::Value & at(const KEY& j) const { return second_.at(j); }
const Value1& at(const Key1& j) const { return first_.at(j); } const Value1& at(const Key1& j) const { return first_.at(j); }
/** direct config access */ /** direct config access */
const Values1& config() const { return first_; } const VALUES1& config() const { return first_; }
const Values2& rest() const { return second_; } const VALUES2& rest() const { return second_; }
/** zero: create VectorValues of appropriate structure */ /** zero: create VectorValues of appropriate structure */
VectorValues zero(const Ordering& ordering) const { VectorValues zero(const Ordering& ordering) const {
@ -203,19 +203,19 @@ namespace gtsam {
} }
/** Expmap */ /** Expmap */
TupleValues<Values1, Values2> expmap(const VectorValues& delta, const Ordering& ordering) const { TupleValues<VALUES1, VALUES2> expmap(const VectorValues& delta, const Ordering& ordering) const {
return TupleValues(first_.expmap(delta, ordering), second_.expmap(delta, ordering)); return TupleValues(first_.expmap(delta, ordering), second_.expmap(delta, ordering));
} }
/** logmap each element */ /** logmap each element */
VectorValues logmap(const TupleValues<Values1, Values2>& cp, const Ordering& ordering) const { VectorValues logmap(const TupleValues<VALUES1, VALUES2>& cp, const Ordering& ordering) const {
VectorValues delta(this->dims(ordering)); VectorValues delta(this->dims(ordering));
logmap(cp, ordering, delta); logmap(cp, ordering, delta);
return delta; return delta;
} }
/** logmap each element */ /** logmap each element */
void logmap(const TupleValues<Values1, Values2>& cp, const Ordering& ordering, VectorValues& delta) const { void logmap(const TupleValues<VALUES1, VALUES2>& cp, const Ordering& ordering, VectorValues& delta) const {
first_.logmap(cp.first_, ordering, delta); first_.logmap(cp.first_, ordering, delta);
second_.logmap(cp.second_, ordering, delta); second_.logmap(cp.second_, ordering, delta);
} }
@ -239,8 +239,8 @@ namespace gtsam {
private: private:
/** Serialization function */ /** Serialization function */
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_NVP(first_); ar & BOOST_SERIALIZATION_NVP(first_);
ar & BOOST_SERIALIZATION_NVP(second_); ar & BOOST_SERIALIZATION_NVP(second_);
} }
@ -253,48 +253,48 @@ namespace gtsam {
* Do not use this class directly - it should only be used as a part * Do not use this class directly - it should only be used as a part
* of a recursive structure * of a recursive structure
*/ */
template<class Values> template<class VALUES>
class TupleValuesEnd : public Testable<TupleValuesEnd<Values> > { class TupleValuesEnd : public Testable<TupleValuesEnd<VALUES> > {
protected: protected:
// Data for internal configs // Data for internal configs
Values first_; VALUES first_;
public: public:
// typedefs // typedefs
typedef class Values::Key Key1; typedef class VALUES::Key Key1;
typedef class Values::Value Value1; typedef class VALUES::Value Value1;
TupleValuesEnd() {} TupleValuesEnd() {}
TupleValuesEnd(const TupleValuesEnd<Values>& config) : TupleValuesEnd(const TupleValuesEnd<VALUES>& config) :
first_(config.first_) {} first_(config.first_) {}
TupleValuesEnd(const Values& cfg) : TupleValuesEnd(const VALUES& cfg) :
first_(cfg) {} first_(cfg) {}
void print(const std::string& s = "") const { void print(const std::string& s = "") const {
first_.print(); first_.print();
} }
bool equals(const TupleValuesEnd<Values>& c, double tol=1e-9) const { bool equals(const TupleValuesEnd<VALUES>& c, double tol=1e-9) const {
return first_.equals(c.first_, tol); return first_.equals(c.first_, tol);
} }
void insert(const Key1& key, const Value1& value) {first_.insert(key, value); } void insert(const Key1& key, const Value1& value) {first_.insert(key, value); }
void insert(int key, const Value1& value) {first_.insert(Key1(key), value);} void insert(int key, const Value1& value) {first_.insert(Key1(key), value);}
void insert(const TupleValuesEnd<Values>& config) {first_.insert(config.first_); } void insert(const TupleValuesEnd<VALUES>& config) {first_.insert(config.first_); }
void update(const TupleValuesEnd<Values>& config) {first_.update(config.first_); } void update(const TupleValuesEnd<VALUES>& config) {first_.update(config.first_); }
void update(const Key1& key, const Value1& value) { first_.update(key, value); } void update(const Key1& key, const Value1& value) { first_.update(key, value); }
void insertSub(const Values& config) {first_.insert(config); } void insertSub(const VALUES& config) {first_.insert(config); }
const Value1& operator[](const Key1& j) const { return first_[j]; } const Value1& operator[](const Key1& j) const { return first_[j]; }
const Values& config() const { return first_; } const VALUES& config() const { return first_; }
void erase(const Key1& j) { first_.erase(j); } void erase(const Key1& j) { first_.erase(j); }
@ -318,17 +318,17 @@ namespace gtsam {
size_t dim() const { return first_.dim(); } size_t dim() const { return first_.dim(); }
TupleValuesEnd<Values> expmap(const VectorValues& delta, const Ordering& ordering) const { TupleValuesEnd<VALUES> expmap(const VectorValues& delta, const Ordering& ordering) const {
return TupleValuesEnd(first_.expmap(delta, ordering)); return TupleValuesEnd(first_.expmap(delta, ordering));
} }
VectorValues logmap(const TupleValuesEnd<Values>& cp, const Ordering& ordering) const { VectorValues logmap(const TupleValuesEnd<VALUES>& cp, const Ordering& ordering) const {
VectorValues delta(this->dims(ordering)); VectorValues delta(this->dims(ordering));
logmap(cp, ordering, delta); logmap(cp, ordering, delta);
return delta; return delta;
} }
void logmap(const TupleValuesEnd<Values>& cp, const Ordering& ordering, VectorValues& delta) const { void logmap(const TupleValuesEnd<VALUES>& cp, const Ordering& ordering, VectorValues& delta) const {
first_.logmap(cp.first_, ordering, delta); first_.logmap(cp.first_, ordering, delta);
} }
@ -348,8 +348,8 @@ namespace gtsam {
private: 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_NVP(first_); ar & BOOST_SERIALIZATION_NVP(first_);
} }
}; };