Changed Value_t conventions to Value, fixed some install script problems
							parent
							
								
									2ac6447cd4
								
							
						
					
					
						commit
						5be0bf6e28
					
				|  | @ -13,7 +13,7 @@ check_PROGRAMS = | |||
| 
 | ||||
| # base Math
 | ||||
| 
 | ||||
| headers += FixedVector.h | ||||
| headers += FixedVector.h types.h blockMatrices.h | ||||
| sources += Vector.cpp svdcmp.cpp Matrix.cpp | ||||
| check_PROGRAMS += tests/testFixedVector tests/testVector tests/testMatrix  | ||||
| 
 | ||||
|  |  | |||
|  | @ -26,6 +26,8 @@ check_PROGRAMS += tests/testVariableIndex tests/testVariableSlots | |||
| headers += inference-inl.h VariableSlots-inl.h | ||||
| sources += inference.cpp VariableSlots.cpp | ||||
| headers += graph.h graph-inl.h | ||||
| headers += Permutation.h | ||||
| headers += VariableIndex.h | ||||
| headers += FactorGraph.h FactorGraph-inl.h | ||||
| headers += ClusterTree.h ClusterTree-inl.h | ||||
| headers += JunctionTree.h JunctionTree-inl.h | ||||
|  |  | |||
|  | @ -36,7 +36,7 @@ namespace gtsam { | |||
| 	public: | ||||
| 
 | ||||
| 		// typedefs
 | ||||
| 		typedef T Value_t; | ||||
| 		typedef T Value; | ||||
| 
 | ||||
| 		// Constructors:
 | ||||
| 
 | ||||
|  |  | |||
|  | @ -52,7 +52,7 @@ namespace gtsam { | |||
| 
 | ||||
|   /* ************************************************************************* */ | ||||
|   template<class J> | ||||
|   const typename J::Value_t& LieValues<J>::at(const J& j) const { | ||||
|   const typename J::Value& LieValues<J>::at(const J& j) const { | ||||
|     const_iterator it = values_.find(j); | ||||
|     if (it == values_.end()) throw std::invalid_argument("invalid j: " + (string)j); | ||||
|     else return it->second; | ||||
|  | @ -77,7 +77,7 @@ namespace gtsam { | |||
| 
 | ||||
|   /* ************************************************************************* */ | ||||
|   template<class J> | ||||
|   void LieValues<J>::insert(const J& name, const typename J::Value_t& val) { | ||||
|   void LieValues<J>::insert(const J& name, const typename J::Value& val) { | ||||
|     values_.insert(make_pair(name, val)); | ||||
|   } | ||||
| 
 | ||||
|  | @ -92,14 +92,14 @@ namespace gtsam { | |||
|   template<class J> | ||||
|   void LieValues<J>::update(const LieValues<J>& cfg) { | ||||
| 	  BOOST_FOREACH(const KeyValuePair& v, values_) { | ||||
| 	  	boost::optional<typename J::Value_t> t = cfg.exists_(v.first); | ||||
| 	  	boost::optional<typename J::Value> t = cfg.exists_(v.first); | ||||
| 	  	if (t) values_[v.first] = *t; | ||||
| 	  } | ||||
|   } | ||||
| 
 | ||||
|   /* ************************************************************************* */ | ||||
|   template<class J> | ||||
|   void LieValues<J>::update(const J& j, const typename J::Value_t& val) { | ||||
|   void LieValues<J>::update(const J& j, const typename J::Value& val) { | ||||
| 	  	values_[j] = val; | ||||
|   } | ||||
| 
 | ||||
|  | @ -133,10 +133,10 @@ namespace gtsam { | |||
|   template<class J> | ||||
|   LieValues<J> LieValues<J>::expmap(const VectorValues& delta, const Ordering& ordering) const { | ||||
| 		LieValues<J> newValues; | ||||
| 		typedef pair<J,typename J::Value_t> KeyValue; | ||||
| 		typedef pair<J,typename J::Value> KeyValue; | ||||
| 		BOOST_FOREACH(const KeyValue& value, this->values_) { | ||||
| 			const J& j = value.first; | ||||
| 			const typename J::Value_t& pj = value.second; | ||||
| 			const typename J::Value& pj = value.second; | ||||
| 			const Vector& dj = delta[ordering[j]]; | ||||
| 			newValues.insert(j, pj.expmap(dj)); | ||||
| 		} | ||||
|  | @ -170,10 +170,10 @@ namespace gtsam { | |||
| //    }
 | ||||
| //    LieValues<J> newValues;
 | ||||
| //    int delta_offset = 0;
 | ||||
| //		typedef pair<J,typename J::Value_t> KeyValue;
 | ||||
| //		typedef pair<J,typename J::Value> KeyValue;
 | ||||
| //		BOOST_FOREACH(const KeyValue& value, this->values_) {
 | ||||
| //			const J& j = value.first;
 | ||||
| //			const typename J::Value_t& pj = value.second;
 | ||||
| //			const typename J::Value& pj = value.second;
 | ||||
| //      int cur_dim = pj.dim();
 | ||||
| //      newValues.insert(j,pj.expmap(sub(delta, delta_offset, delta_offset+cur_dim)));
 | ||||
| //      delta_offset += cur_dim;
 | ||||
|  | @ -194,7 +194,7 @@ namespace gtsam { | |||
|   /* ************************************************************************* */ | ||||
|   template<class J> | ||||
|   void LieValues<J>::logmap(const LieValues<J>& cp, const Ordering& ordering, VectorValues& delta) const { | ||||
|     typedef pair<J,typename J::Value_t> KeyValue; | ||||
|     typedef pair<J,typename J::Value> KeyValue; | ||||
|     BOOST_FOREACH(const KeyValue& value, cp) { | ||||
|       assert(this->exists(value.first)); | ||||
|       delta[ordering[value.first]] = this->at(value.first).logmap(value.second); | ||||
|  |  | |||
|  | @ -34,7 +34,7 @@ namespace gtsam { | |||
| 	 * | ||||
| 	 * Key concept: | ||||
| 	 *  The key will be assumed to be sortable, and must have a | ||||
| 	 *  typedef called "Value_t" with the type of the value the key | ||||
| 	 *  typedef called "Value" with the type of the value the key | ||||
| 	 *  labels (example: Pose2, Point2, etc) | ||||
| 	 */ | ||||
|   template<class J> | ||||
|  | @ -46,7 +46,7 @@ namespace gtsam { | |||
|      * Typedefs | ||||
|      */ | ||||
|   	typedef J Key; | ||||
|   	typedef typename J::Value_t Value; | ||||
|   	typedef typename J::Value Value; | ||||
|     typedef std::map<J,Value, std::less<J>, boost::fast_pool_allocator<std::pair<const J,Value> > > KeyValueMap; | ||||
|     typedef typename KeyValueMap::value_type KeyValuePair; | ||||
|     typedef typename KeyValueMap::iterator iterator; | ||||
|  |  | |||
|  | @ -99,7 +99,7 @@ template <class Values, class Key> | |||
| class NonlinearConstraint1 : public NonlinearConstraint<Values> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key::Value_t X; | ||||
| 	typedef typename Key::Value X; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearConstraint1<Values,Key> This; | ||||
|  | @ -172,7 +172,7 @@ template <class Values, class Key> | |||
| class NonlinearEqualityConstraint1 : public NonlinearConstraint1<Values, Key> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key::Value_t X; | ||||
| 	typedef typename Key::Value X; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearEqualityConstraint1<Values,Key> This; | ||||
|  | @ -194,8 +194,8 @@ template <class Values, class Key1, class Key2> | |||
| class NonlinearConstraint2 : public NonlinearConstraint<Values> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key1::Value_t X1; | ||||
| 	typedef typename Key2::Value_t X2; | ||||
| 	typedef typename Key1::Value X1; | ||||
| 	typedef typename Key2::Value X2; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearConstraint2<Values,Key1,Key2> This; | ||||
|  | @ -275,8 +275,8 @@ template <class Values, class Key1, class Key2> | |||
| class NonlinearEqualityConstraint2 : public NonlinearConstraint2<Values, Key1, Key2> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key1::Value_t X1; | ||||
| 	typedef typename Key2::Value_t X2; | ||||
| 	typedef typename Key1::Value X1; | ||||
| 	typedef typename Key2::Value X2; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearEqualityConstraint2<Values,Key1,Key2> This; | ||||
|  | @ -299,9 +299,9 @@ template <class Values, class Key1, class Key2, class Key3> | |||
| class NonlinearConstraint3 : public NonlinearConstraint<Values> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key1::Value_t X1; | ||||
| 	typedef typename Key2::Value_t X2; | ||||
| 	typedef typename Key3::Value_t X3; | ||||
| 	typedef typename Key1::Value X1; | ||||
| 	typedef typename Key2::Value X2; | ||||
| 	typedef typename Key3::Value X3; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearConstraint3<Values,Key1,Key2,Key3> This; | ||||
|  | @ -389,9 +389,9 @@ template <class Values, class Key1, class Key2, class Key3> | |||
| class NonlinearEqualityConstraint3 : public NonlinearConstraint3<Values, Key1, Key2, Key3> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key1::Value_t X1; | ||||
| 	typedef typename Key2::Value_t X2; | ||||
| 	typedef typename Key3::Value_t X3; | ||||
| 	typedef typename Key1::Value X1; | ||||
| 	typedef typename Key2::Value X2; | ||||
| 	typedef typename Key3::Value X3; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearEqualityConstraint3<Values,Key1,Key2,Key3> This; | ||||
|  | @ -415,7 +415,7 @@ template<class Values, class Key> | |||
| class NonlinearEquality1 : public NonlinearEqualityConstraint1<Values, Key> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename Key::Value_t X; | ||||
| 	typedef typename Key::Value X; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearEqualityConstraint1<Values, Key> Base; | ||||
|  | @ -446,7 +446,7 @@ public: | |||
| template<class Values, class Key> | ||||
| class NonlinearEquality2 : public NonlinearEqualityConstraint2<Values, Key, Key> { | ||||
| public: | ||||
| 	typedef typename Key::Value_t X; | ||||
| 	typedef typename Key::Value X; | ||||
| 
 | ||||
| protected: | ||||
| 	typedef NonlinearEqualityConstraint2<Values, Key, Key> Base; | ||||
|  |  | |||
|  | @ -34,7 +34,7 @@ namespace gtsam { | |||
| 	class NonlinearEquality: public NonlinearFactor1<Values, Key> { | ||||
| 
 | ||||
| 	public: | ||||
| 		typedef typename Key::Value_t T; | ||||
| 		typedef typename Key::Value T; | ||||
| 
 | ||||
| 	private: | ||||
| 
 | ||||
|  |  | |||
|  | @ -152,7 +152,7 @@ namespace gtsam { | |||
| 	public: | ||||
| 
 | ||||
| 		// typedefs for value types pulled from keys
 | ||||
| 		typedef typename Key::Value_t X; | ||||
| 		typedef typename Key::Value X; | ||||
| 
 | ||||
| 	protected: | ||||
| 
 | ||||
|  | @ -262,8 +262,8 @@ namespace gtsam { | |||
| 	  public: | ||||
| 
 | ||||
| 		// typedefs for value types pulled from keys
 | ||||
| 		typedef typename Key1::Value_t X1; | ||||
| 		typedef typename Key2::Value_t X2; | ||||
| 		typedef typename Key1::Value X1; | ||||
| 		typedef typename Key2::Value X2; | ||||
| 
 | ||||
| 	protected: | ||||
| 
 | ||||
|  | @ -398,9 +398,9 @@ namespace gtsam { | |||
|   public: | ||||
| 
 | ||||
| 	// typedefs for value types pulled from keys
 | ||||
| 	typedef typename Key1::Value_t X1; | ||||
| 	typedef typename Key2::Value_t X2; | ||||
| 	typedef typename Key3::Value_t X3; | ||||
| 	typedef typename Key1::Value X1; | ||||
| 	typedef typename Key2::Value X2; | ||||
| 	typedef typename Key3::Value X3; | ||||
| 
 | ||||
|   protected: | ||||
| 
 | ||||
|  |  | |||
|  | @ -138,17 +138,17 @@ namespace gtsam { | |||
| 
 | ||||
| 	  /** a variant of exists */ | ||||
| 	  template<class Key> | ||||
| 	  boost::optional<typename Key::Value_t> 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); } | ||||
| 
 | ||||
| 	  /** access operator */ | ||||
| 	  template<class Key> | ||||
| 	  const typename Key::Value_t & 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]; } | ||||
| 
 | ||||
| 	  /** at access function */ | ||||
| 	  template<class Key> | ||||
| 	  const typename Key::Value_t & 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); } | ||||
| 
 | ||||
| 	  /** direct config access */ | ||||
|  |  | |||
|  | @ -17,7 +17,7 @@ namespace gtsam { | |||
| 	template<class Values, class Key> | ||||
| 	class BetweenConstraint : public NonlinearEqualityConstraint2<Values, Key, Key> { | ||||
| 	public: | ||||
| 		typedef typename Key::Value_t X; | ||||
| 		typedef typename Key::Value X; | ||||
| 
 | ||||
| 	protected: | ||||
| 		typedef NonlinearEqualityConstraint2<Values, Key, Key> Base; | ||||
|  |  | |||
|  | @ -23,7 +23,7 @@ namespace gtsam { | |||
| 	class BetweenFactor: public NonlinearFactor2<Values, Key1, Key2> { | ||||
| 
 | ||||
| 	public: | ||||
| 		typedef typename Key1::Value_t T; | ||||
| 		typedef typename Key1::Value T; | ||||
| 
 | ||||
| 	private: | ||||
| 
 | ||||
|  |  | |||
|  | @ -19,7 +19,7 @@ namespace gtsam { | |||
| 	 */ | ||||
| 	template<class Cfg, class Key> | ||||
| 	struct BoundingConstraint1: public NonlinearConstraint1<Cfg, Key> { | ||||
| 		typedef typename Key::Value_t X; | ||||
| 		typedef typename Key::Value X; | ||||
| 		typedef NonlinearConstraint1<Cfg, Key> Base; | ||||
| 		typedef boost::shared_ptr<BoundingConstraint1<Cfg, Key> > shared_ptr; | ||||
| 
 | ||||
|  | @ -64,8 +64,8 @@ namespace gtsam { | |||
| 	 */ | ||||
| 	template<class Cfg, class Key1, class Key2> | ||||
| 	struct BoundingConstraint2: public NonlinearConstraint2<Cfg, Key1, Key2> { | ||||
| 		typedef typename Key1::Value_t X1; | ||||
| 		typedef typename Key2::Value_t X2; | ||||
| 		typedef typename Key1::Value X1; | ||||
| 		typedef typename Key2::Value X2; | ||||
| 
 | ||||
| 		typedef NonlinearConstraint2<Cfg, Key1, Key2> Base; | ||||
| 		typedef boost::shared_ptr<BoundingConstraint2<Cfg, Key1, Key2> > shared_ptr; | ||||
|  |  | |||
|  | @ -22,7 +22,7 @@ class LinearApproxFactor : public NonlinearFactor<Values> { | |||
| 
 | ||||
| public: | ||||
| 	/** type for the variable */ | ||||
| 	typedef typename Key::Value_t X; | ||||
| 	typedef typename Key::Value X; | ||||
| 
 | ||||
| 	/** base type */ | ||||
| 	typedef NonlinearFactor<Values> Base; | ||||
|  |  | |||
|  | @ -24,7 +24,7 @@ namespace gtsam { | |||
| 	class PriorFactor: public NonlinearFactor1<Values, Key> { | ||||
| 
 | ||||
| 	public: | ||||
| 		typedef typename Key::Value_t T; | ||||
| 		typedef typename Key::Value T; | ||||
| 
 | ||||
| 	private: | ||||
| 
 | ||||
|  |  | |||
|  | @ -29,8 +29,8 @@ template<class Values, class PKey, class TKey> | |||
| class TransformConstraint : public NonlinearEqualityConstraint3<Values, PKey, TKey, PKey> { | ||||
| 
 | ||||
| public: | ||||
| 	typedef typename PKey::Value_t Point; | ||||
| 	typedef typename TKey::Value_t Transform; | ||||
| 	typedef typename PKey::Value Point; | ||||
| 	typedef typename TKey::Value Transform; | ||||
| 
 | ||||
| 	typedef NonlinearEqualityConstraint3<Values, PKey, TKey, PKey> Base; | ||||
| 	typedef TransformConstraint<Values, PKey, TKey> This; | ||||
|  |  | |||
|  | @ -57,7 +57,7 @@ namespace gtsam { | |||
| 		template<class Cfg = Values, class Key = PoseKey> | ||||
| 		struct GenericPrior: public NonlinearFactor1<Cfg, Key> { | ||||
| 			typedef boost::shared_ptr<GenericPrior<Cfg, Key> > shared_ptr; | ||||
| 			typedef typename Key::Value_t Pose; | ||||
| 			typedef typename Key::Value Pose; | ||||
| 			Pose z_; | ||||
| 
 | ||||
| 			GenericPrior(const Pose& z, const SharedGaussian& model, const Key& key) : | ||||
|  | @ -77,7 +77,7 @@ namespace gtsam { | |||
| 		template<class Cfg = Values, class Key = PoseKey> | ||||
| 		struct GenericOdometry: public NonlinearFactor2<Cfg, Key, Key> { | ||||
| 			typedef boost::shared_ptr<GenericOdometry<Cfg, Key> > shared_ptr; | ||||
| 			typedef typename Key::Value_t Pose; | ||||
| 			typedef typename Key::Value Pose; | ||||
| 			Pose z_; | ||||
| 
 | ||||
| 			GenericOdometry(const Pose& z, const SharedGaussian& model, | ||||
|  | @ -99,8 +99,8 @@ namespace gtsam { | |||
| 		class GenericMeasurement: public NonlinearFactor2<Cfg, XKey, LKey> { | ||||
| 		public: | ||||
| 			typedef boost::shared_ptr<GenericMeasurement<Cfg, XKey, LKey> > shared_ptr; | ||||
| 			typedef typename XKey::Value_t Pose; | ||||
| 			typedef typename LKey::Value_t Point; | ||||
| 			typedef typename XKey::Value Pose; | ||||
| 			typedef typename LKey::Value Point; | ||||
| 
 | ||||
| 			Point z_; | ||||
| 
 | ||||
|  |  | |||
		Loading…
	
		Reference in New Issue