diff --git a/gtsam/base/ChartValue.h b/gtsam/base/ChartValue.h new file mode 100644 index 000000000..6f0cf1406 --- /dev/null +++ b/gtsam/base/ChartValue.h @@ -0,0 +1,190 @@ +/* ---------------------------------------------------------------------------- + + * 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 ChartValue.h + * @date Jan 26, 2012 + * @author Michael Bosse, Abel Gawel, Renaud Dube + * based on DrivedValue.h by Duy Nguyen Ta + */ + +#pragma once + +#include +#include +#include + +////////////////// +// The following includes windows.h in some MSVC versions, so we undef min, max, and ERROR +#include + +#ifdef min +#undef min +#endif + +#ifdef max +#undef max +#endif + +#ifdef ERROR +#undef ERROR +#endif +////////////////// + + +namespace gtsam { + +// ChartValue is derived from GenericValue and Chart so that Chart can be zero sized (as in DefaultChart) +// if the Chart is a member variable then it won't ever be zero sized. +template > +class ChartValue : public GenericValue, public Chart_ { + BOOST_CONCEPT_ASSERT((ChartConcept)); + public: + typedef T type; + typedef Chart_ Chart; + + public: + ChartValue() : GenericValue(T()) {} + ChartValue(const T& value) : GenericValue(value) {} + template + ChartValue(const T& value, C chart_initializer) : GenericValue(value), Chart(chart_initializer) {} + + virtual ~ChartValue() {} + + /** + * Create a duplicate object returned as a pointer to the generic Value interface. + * For the sake of performance, this function use singleton pool allocator instead of the normal heap allocator. + * The result must be deleted with Value::deallocate_, not with the 'delete' operator. + */ + virtual Value* clone_() const { + void *place = boost::singleton_pool::malloc(); + ChartValue* ptr = new(place) ChartValue(*this); // calls copy constructor to fill in + return ptr; + } + + /** + * Destroy and deallocate this object, only if it was originally allocated using clone_(). + */ + virtual void deallocate_() const { + this->~ChartValue(); // Virtual destructor cleans up the derived object + boost::singleton_pool::free((void*)this); // Release memory from pool + } + + /** + * Clone this value (normal clone on the heap, delete with 'delete' operator) + */ + virtual boost::shared_ptr clone() const { + return boost::make_shared(*this); + } + + /// just use the equals_ defined in GenericValue + // virtual bool equals_(const Value& p, double tol = 1e-9) const { + // } + + /// Chart Value interface version of retract + virtual Value* retract_(const Vector& delta) const { + // Call retract on the derived class using the retract trait function + const T retractResult = Chart::retract(GenericValue::value(), delta); + + // Create a Value pointer copy of the result + void* resultAsValuePlace = boost::singleton_pool::malloc(); + Value* resultAsValue = new(resultAsValuePlace) ChartValue(retractResult, static_cast(*this)); + + // Return the pointer to the Value base class + return resultAsValue; + } + + /// Generic Value interface version of localCoordinates + virtual Vector localCoordinates_(const Value& value2) const { + // Cast the base class Value pointer to a templated generic class pointer + const GenericValue& genericValue2 = static_cast&>(value2); + + // Return the result of calling localCoordinates trait on the derived class + return Chart::local(GenericValue::value(), genericValue2.value()); + } + + /// Non-virtual version of retract + ChartValue retract(const Vector& delta) const { + return ChartValue(Chart::retract(GenericValue::value(), delta),static_cast(*this)); + } + + /// Non-virtual version of localCoordinates + Vector localCoordinates(const ChartValue& value2) const { + return localCoordinates_(value2); + } + + virtual size_t dim() const { + return Chart::getDimension(GenericValue::value()); // need functional form here since the dimension may be dynamic + } + + /// Assignment operator + virtual Value& operator=(const Value& rhs) { + // Cast the base class Value pointer to a derived class pointer + const ChartValue& derivedRhs = static_cast(rhs); + + // Do the assignment and return the result + *this = ChartValue(derivedRhs); // calls copy constructor + return *this; + } + +protected: + // implicit assignment operator for (const ChartValue& rhs) works fine here + /// Assignment operator, protected because only the Value or DERIVED + /// assignment operators should be used. + // DerivedValue& operator=(const DerivedValue& rhs) { + // // Nothing to do, do not call base class assignment operator + // return *this; + // } + +private: + /// Fake Tag struct for singleton pool allocator. In fact, it is never used! + struct PoolTag { }; + +private: + + /// @} + /// @name Advanced Interface + /// @{ + + /** Serialization function */ + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + // ar & boost::serialization::make_nvp("value",); + // todo: implement a serialization for charts + ar & boost::serialization::make_nvp("GenericValue", boost::serialization::base_object< GenericValue >(*this)); + } + + /// @} + +}; + +namespace traits { +template +struct dimension > : public dimension {}; +} + +template +const Chart& Value::getChart() const { +// define Value::cast here since now ChartValue has been declared + return dynamic_cast(*this); + } + +/// Convenience function that can be used to make an expression to convert a value to a chart +template +ChartValue convertToChartValue(const T& value, boost::optional::value, traits::dimension::value >& > H=boost::none) { + if (H) { + *H = Eigen::Matrix::value, traits::dimension::value >::Identity(); + } + return ChartValue(value); +} + +} /* namespace gtsam */ diff --git a/gtsam/base/GenericValue.h b/gtsam/base/GenericValue.h new file mode 100644 index 000000000..0869769c4 --- /dev/null +++ b/gtsam/base/GenericValue.h @@ -0,0 +1,89 @@ +/* ---------------------------------------------------------------------------- + + * 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 GenericValue.h + * @date Jan 26, 2012 + * @author Michael Bosse, Abel Gawel, Renaud Dube + * based on DrivedValue.h by Duy Nguyen Ta + */ + +#pragma once + +#include + +namespace gtsam { + +namespace traits { + +// trait to wrap the default equals of types +template + bool equals(const T& a, const T& b, double tol) { + return a.equals(b,tol); + } + +template +void print(const T& obj, const std::string& str) { + obj.print(str); +} + +} + +template +class GenericValue : public Value { +public: + typedef T type; +protected: + T value_; + +public: + GenericValue(const T& value) : value_(value) {} + + const T& value() const { return value_; } + T& value() { return value_; } + + virtual ~GenericValue() {} + + /// equals implementing generic Value interface + virtual bool equals_(const Value& p, double tol = 1e-9) const { + // Cast the base class Value pointer to a templated generic class pointer + const GenericValue& genericValue2 = static_cast(p); + // Return the result of using the equals traits for the derived class + return traits::equals(this->value_, genericValue2.value_, tol); + } + + // non virtual equals function + bool equals(const GenericValue &other, double tol = 1e-9) const { + return traits::equals(this->value(),other.value(),tol); + } + + virtual void print(const std::string& str) const { + traits::print(value_,str); + } + friend class boost::serialization::access; + template + void serialize(ARCHIVE & ar, const unsigned int version) { + ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value); + ar & BOOST_SERIALIZATION_NVP(value_); + } +protected: + /// Assignment operator for this class not needed since GenricValue is an abstract class + +}; + +// define Value::cast here since now GenericValue has been declared +template + const ValueType& Value::cast() const { + return dynamic_cast&>(*this).value(); + } + + +} /* namespace gtsam */ diff --git a/gtsam/base/LieMatrix.h b/gtsam/base/LieMatrix.h index 2a8d4bc41..5d4f89f48 100644 --- a/gtsam/base/LieMatrix.h +++ b/gtsam/base/LieMatrix.h @@ -29,7 +29,7 @@ namespace gtsam { /** * LieVector is a wrapper around vector to allow it to be a Lie type */ -struct LieMatrix : public Matrix, public DerivedValue { +struct LieMatrix : public Matrix { /// @name Constructors /// @{ @@ -166,8 +166,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("LieMatrix", - boost::serialization::base_object(*this)); ar & boost::serialization::make_nvp("Matrix", boost::serialization::base_object(*this)); @@ -179,7 +177,7 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> diff --git a/gtsam/base/LieScalar.h b/gtsam/base/LieScalar.h index 750a8a21f..1d4aa86e2 100644 --- a/gtsam/base/LieScalar.h +++ b/gtsam/base/LieScalar.h @@ -26,7 +26,7 @@ namespace gtsam { /** * LieScalar is a wrapper around double to allow it to be a Lie type */ - struct GTSAM_EXPORT LieScalar : public DerivedValue { + struct GTSAM_EXPORT LieScalar { /** default constructor */ LieScalar() : d_(0.0) {} @@ -116,15 +116,15 @@ namespace gtsam { namespace traits { template<> - struct is_group : public std::true_type { + struct is_group : public boost::true_type { }; template<> - struct is_manifold : public std::true_type { + struct is_manifold : public boost::true_type { }; template<> - struct dimension : public std::integral_constant { + struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 8286c95a6..99b351ff5 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -26,7 +26,7 @@ namespace gtsam { /** * LieVector is a wrapper around vector to allow it to be a Lie type */ -struct LieVector : public Vector, public DerivedValue { +struct LieVector : public Vector { /** default constructor - should be unnecessary */ LieVector() {} @@ -123,8 +123,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("LieVector", - boost::serialization::base_object(*this)); ar & boost::serialization::make_nvp("Vector", boost::serialization::base_object(*this)); } @@ -134,7 +132,7 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> diff --git a/gtsam/base/Manifold.h b/gtsam/base/Manifold.h index 63390ec1f..4fe6c9d99 100644 --- a/gtsam/base/Manifold.h +++ b/gtsam/base/Manifold.h @@ -20,7 +20,7 @@ #include #include -#include +#include #include namespace gtsam { @@ -50,7 +50,7 @@ namespace traits { // is group, by default this is false template -struct is_group: public std::false_type { +struct is_group: public boost::false_type { }; // identity, no default provided, by default given by default constructor @@ -63,16 +63,17 @@ struct identity { // is manifold, by default this is false template -struct is_manifold: public std::false_type { +struct is_manifold: public boost::false_type { }; // dimension, can return Eigen::Dynamic (-1) if not known at compile time +typedef boost::integral_constant Dynamic; template -struct dimension; +struct dimension : public Dynamic {}; //default to dynamic /** * zero::value is intended to be the origin of a canonical coordinate system - * with canonical(t) == DefaultChart(zero::value).apply(t) + * with canonical(t) == DefaultChart::local(zero::value, t) * Below we provide the group identity as zero *in case* it is a group */ template struct zero: public identity { @@ -82,15 +83,15 @@ template struct zero: public identity { // double template<> -struct is_group : public std::true_type { +struct is_group : public boost::true_type { }; template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> @@ -103,17 +104,15 @@ struct zero { // Fixed size Eigen::Matrix type template -struct is_group > : public std::true_type { +struct is_group > : public boost::true_type { }; template -struct is_manifold > : public std::true_type { +struct is_manifold > : public boost::true_type { }; // TODO: Could be more sophisticated using Eigen traits and SFINAE? -typedef std::integral_constant Dynamic; - template struct dimension > : public Dynamic { }; @@ -127,12 +126,12 @@ struct dimension > : public Dy }; template -struct dimension > : public std::integral_constant< +struct dimension > : public boost::integral_constant< int, M * N> { }; template -struct zero > : public std::integral_constant< +struct zero > : public boost::integral_constant< int, M * N> { BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic), "traits::zero is only supported for fixed-size matrices"); @@ -141,62 +140,105 @@ struct zero > : public std::integral_consta } }; +template struct is_chart : public boost::false_type {}; + } // \ namespace traits // Chart is a map from T -> vector, retract is its inverse template struct DefaultChart { - BOOST_STATIC_ASSERT(traits::is_manifold::value); + //BOOST_STATIC_ASSERT(traits::is_manifold::value); + typedef T type; typedef Eigen::Matrix::value, 1> vector; - T t_; - DefaultChart(const T& t) : - t_(t) { + + static vector local(const T& origin, const T& other) { + return origin.localCoordinates(other); } - vector apply(const T& other) { - return t_.localCoordinates(other); + static T retract(const T& origin, const vector& d) { + return origin.retract(d); } - T retract(const vector& d) { - return t_.retract(d); + static int getDimension(const T& origin) { + return origin.dim(); } }; +namespace traits { +// populate default traits +template struct is_chart > : public boost::true_type {}; +template struct dimension > : public dimension {}; +} + +template +struct ChartConcept { + public: + typedef typename C::type type; + typedef typename C::vector vector; + + BOOST_CONCEPT_USAGE(ChartConcept) { + // is_chart trait should be true + BOOST_STATIC_ASSERT((traits::is_chart::value)); + + /** + * Returns Retraction update of val_ + */ + type retract_ret = C::retract(val_, vec_); + + /** + * Returns local coordinates of another object + */ + vec_ = C::local(val_, retract_ret); + + // a way to get the dimension that is compatible with dynamically sized types + dim_ = C::getDimension(val_); + } + + private: + type val_; + vector vec_; + int dim_; +}; + + /** - * Canonical::value is a chart around zero::value + * CanonicalChart > is a chart around zero::value + * Canonical is CanonicalChart > * An example is Canonical */ -template struct Canonical { - typedef T type; - typedef typename DefaultChart::vector vector; - DefaultChart chart; - Canonical() : - chart(traits::zero::value()) { - } +template struct CanonicalChart { + BOOST_CONCEPT_ASSERT((ChartConcept)); + + typedef C Chart; + typedef typename Chart::type type; + typedef typename Chart::vector vector; + // Convert t of type T into canonical coordinates - vector apply(const T& t) { - return chart.apply(t); + vector local(const type& t) { + return Chart::local(traits::zero::value(), t); } // Convert back from canonical coordinates to T - T retract(const vector& v) { - return chart.retract(v); + type retract(const vector& v) { + return Chart::retract(traits::zero::value(), v); } }; +template struct Canonical : public CanonicalChart > {}; // double template<> struct DefaultChart { + typedef double type; typedef Eigen::Matrix vector; - double t_; - DefaultChart(double t) : - t_(t) { - } - vector apply(double other) { + + static vector local(double origin, double other) { vector d; - d << other - t_; + d << other - origin; return d; } - double retract(const vector& d) { - return t_ + d[0]; + static double retract(double origin, const vector& d) { + return origin + d[0]; + } + static const int getDimension(double) { + return 1; } }; @@ -204,22 +246,23 @@ struct DefaultChart { template struct DefaultChart > { - typedef Eigen::Matrix T; + typedef Eigen::Matrix type; + typedef type T; typedef Eigen::Matrix::value, 1> vector; BOOST_STATIC_ASSERT_MSG((M!=Eigen::Dynamic && N!=Eigen::Dynamic), "DefaultChart has not been implemented yet for dynamically sized matrices"); - T t_; - DefaultChart(const T& t) : - t_(t) { - } - vector apply(const T& other) { - T diff = other - t_; + static vector local(const T& origin, const T& other) { + T diff = other - origin; Eigen::Map map(diff.data()); return vector(map); + // Why is this function not : return other - origin; ?? what is the Eigen::Map used for? } - T retract(const vector& d) { + static T retract(const T& origin, const vector& d) { Eigen::Map map(d.data()); - return t_ + map; + return origin + map; + } + static int getDimension(const T&origin) { + return origin.rows()*origin.cols(); } }; @@ -227,16 +270,16 @@ struct DefaultChart > { template<> struct DefaultChart { typedef Vector T; + typedef T type; typedef T vector; - T t_; - DefaultChart(const T& t) : - t_(t) { + static vector local(const T& origin, const T& other) { + return other - origin; } - vector apply(const T& other) { - return other - t_; + static T retract(const T& origin, const vector& d) { + return origin + d; } - T retract(const vector& d) { - return t_ + d; + static int getDimension(const T& origin) { + return origin.size(); } }; diff --git a/gtsam/base/Value.h b/gtsam/base/Value.h index 4d7104ad7..99d40b060 100644 --- a/gtsam/base/Value.h +++ b/gtsam/base/Value.h @@ -120,7 +120,16 @@ namespace gtsam { virtual Vector localCoordinates_(const Value& value) const = 0; /** Assignment operator */ - virtual Value& operator=(const Value& rhs) = 0; + virtual Value& operator=(const Value& rhs) { + //needs a empty definition so recursion in implicit derived assignment operators work + return *this; + } + /** Cast to known ValueType */ + template + const ValueType& cast() const; + + template + const Chart& getChart() const; /** Virutal destructor */ virtual ~Value() {} diff --git a/gtsam/base/numericalDerivative.h b/gtsam/base/numericalDerivative.h index 87c912e57..9339c9c7b 100644 --- a/gtsam/base/numericalDerivative.h +++ b/gtsam/base/numericalDerivative.h @@ -73,7 +73,7 @@ Vector numericalGradient(boost::function h, const X& x, typedef typename ChartX::vector TangentX; // get chart at x - ChartX chartX(x); + ChartX chartX; // Prepare a tangent vector to perturb x with, only works for fixed size TangentX d; @@ -82,9 +82,9 @@ Vector numericalGradient(boost::function h, const X& x, Vector g = zero(N); // Can be fixed size for (int j = 0; j < N; j++) { d(j) = delta; - double hxplus = h(chartX.retract(d)); + double hxplus = h(chartX.retract(x, d)); d(j) = -delta; - double hxmin = h(chartX.retract(d)); + double hxmin = h(chartX.retract(x, d)); d(j) = 0; g(j) = (hxplus - hxmin) * factor; } @@ -121,14 +121,14 @@ Matrix numericalDerivative11(boost::function h, const X& x, // get value at x, and corresponding chart Y hx = h(x); - ChartY chartY(hx); + ChartY chartY; // Bit of a hack for now to find number of rows - TangentY zeroY = chartY.apply(hx); + TangentY zeroY = chartY.local(hx, hx); size_t m = zeroY.size(); // get chart at x - ChartX chartX(x); + ChartX chartX; // Prepare a tangent vector to perturb x with, only works for fixed size TangentX dx; @@ -139,9 +139,9 @@ Matrix numericalDerivative11(boost::function h, const X& x, double factor = 1.0 / (2.0 * delta); for (int j = 0; j < N; j++) { dx(j) = delta; - TangentY dy1 = chartY.apply(h(chartX.retract(dx))); + TangentY dy1 = chartY.local(hx, h(chartX.retract(x, dx))); dx(j) = -delta; - TangentY dy2 = chartY.apply(h(chartX.retract(dx))); + TangentY dy2 = chartY.local(hx, h(chartX.retract(x, dx))); dx(j) = 0; H.col(j) << (dy1 - dy2) * factor; } diff --git a/gtsam/geometry/Cal3Bundler.h b/gtsam/geometry/Cal3Bundler.h index 793f195d5..db06c7aca 100644 --- a/gtsam/geometry/Cal3Bundler.h +++ b/gtsam/geometry/Cal3Bundler.h @@ -28,7 +28,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Cal3Bundler: public DerivedValue { +class GTSAM_EXPORT Cal3Bundler { private: double f_; ///< focal length @@ -172,9 +172,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar - & boost::serialization::make_nvp("Cal3Bundler", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(f_); ar & BOOST_SERIALIZATION_NVP(k1_); ar & BOOST_SERIALIZATION_NVP(k2_); @@ -190,11 +187,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/Cal3DS2.h b/gtsam/geometry/Cal3DS2.h index d716d398e..4179a76e0 100644 --- a/gtsam/geometry/Cal3DS2.h +++ b/gtsam/geometry/Cal3DS2.h @@ -37,7 +37,7 @@ namespace gtsam { * k3 (rr + 2 Pn.y^2) + 2*k4 pn.x pn.y ] * pi = K*pn */ -class GTSAM_EXPORT Cal3DS2 : public DerivedValue { +class GTSAM_EXPORT Cal3DS2 { protected: @@ -153,8 +153,6 @@ private: template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Cal3DS2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); @@ -172,11 +170,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Cal3Unified.h b/gtsam/geometry/Cal3Unified.h index ad8e7b904..b75efff94 100644 --- a/gtsam/geometry/Cal3Unified.h +++ b/gtsam/geometry/Cal3Unified.h @@ -131,8 +131,6 @@ private: template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Cal3Unified", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(xi_); } @@ -142,11 +140,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/Cal3_S2.h b/gtsam/geometry/Cal3_S2.h index a87a30e36..cd1add116 100644 --- a/gtsam/geometry/Cal3_S2.h +++ b/gtsam/geometry/Cal3_S2.h @@ -31,7 +31,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Cal3_S2: public DerivedValue { +class GTSAM_EXPORT Cal3_S2 { private: double fx_, fy_, s_, u0_, v0_; @@ -226,9 +226,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar - & boost::serialization::make_nvp("Cal3_S2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(fx_); ar & BOOST_SERIALIZATION_NVP(fy_); ar & BOOST_SERIALIZATION_NVP(s_); @@ -244,11 +241,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/CalibratedCamera.h b/gtsam/geometry/CalibratedCamera.h index 6e7b5a114..66d1c5125 100644 --- a/gtsam/geometry/CalibratedCamera.h +++ b/gtsam/geometry/CalibratedCamera.h @@ -39,7 +39,7 @@ public: * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT CalibratedCamera: public DerivedValue { +class GTSAM_EXPORT CalibratedCamera { private: Pose3 pose_; // 6DOF pose @@ -214,12 +214,28 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar - & boost::serialization::make_nvp("CalibratedCamera", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(pose_); } /// @} - };} +}; + +// Define GTSAM traits +namespace traits { + +template<> +struct is_group : public boost::true_type { +}; + +template<> +struct is_manifold : public boost::true_type { +}; + +template<> +struct dimension : public boost::integral_constant { +}; + +} + +} diff --git a/gtsam/geometry/EssentialMatrix.h b/gtsam/geometry/EssentialMatrix.h index a973f9cec..e23b22093 100644 --- a/gtsam/geometry/EssentialMatrix.h +++ b/gtsam/geometry/EssentialMatrix.h @@ -20,7 +20,7 @@ namespace gtsam { * but here we choose instead to parameterize it as a (Rot3,Unit3) pair. * We can then non-linearly optimize immediately on this 5-dimensional manifold. */ -class GTSAM_EXPORT EssentialMatrix: public DerivedValue { +class GTSAM_EXPORT EssentialMatrix { private: @@ -176,8 +176,6 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("EssentialMatrix", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(aRb_); ar & BOOST_SERIALIZATION_NVP(aTb_); @@ -200,11 +198,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/PinholeCamera.h b/gtsam/geometry/PinholeCamera.h index c2fea07e0..83851e8c0 100644 --- a/gtsam/geometry/PinholeCamera.h +++ b/gtsam/geometry/PinholeCamera.h @@ -37,7 +37,7 @@ namespace gtsam { * \nosubgrouping */ template -class PinholeCamera: public DerivedValue > { +class PinholeCamera { private: Pose3 pose_; Calibration K_; @@ -653,7 +653,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & BOOST_SERIALIZATION_BASE_OBJECT_NVP(Value); ar & BOOST_SERIALIZATION_NVP(pose_); ar & BOOST_SERIALIZATION_NVP(K_); } @@ -664,11 +663,11 @@ private: namespace traits { template -struct is_manifold > : public std::true_type { +struct is_manifold > : public boost::true_type { }; template -struct dimension > : public std::integral_constant< +struct dimension > : public boost::integral_constant< int, dimension::value + dimension::value> { }; diff --git a/gtsam/geometry/Point2.h b/gtsam/geometry/Point2.h index 7d1fab133..59a18aed7 100644 --- a/gtsam/geometry/Point2.h +++ b/gtsam/geometry/Point2.h @@ -32,7 +32,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Point2 : public DerivedValue { +class GTSAM_EXPORT Point2 { private: @@ -237,8 +237,6 @@ private: template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Point2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); } @@ -254,15 +252,15 @@ inline Point2 operator*(double s, const Point2& p) {return p*s;} namespace traits { template<> -struct is_group : public std::true_type { +struct is_group : public boost::true_type { }; template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Point3.h b/gtsam/geometry/Point3.h index d69ceb861..af54e0459 100644 --- a/gtsam/geometry/Point3.h +++ b/gtsam/geometry/Point3.h @@ -36,7 +36,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Point3 : public DerivedValue { + class GTSAM_EXPORT Point3 { private: @@ -228,8 +228,6 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Point3", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(x_); ar & BOOST_SERIALIZATION_NVP(y_); ar & BOOST_SERIALIZATION_NVP(z_); @@ -246,15 +244,15 @@ namespace gtsam { namespace traits { template<> - struct is_group : public std::true_type { + struct is_group : public boost::true_type { }; template<> - struct is_manifold : public std::true_type { + struct is_manifold : public boost::true_type { }; template<> - struct dimension : public std::integral_constant { + struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Pose2.h b/gtsam/geometry/Pose2.h index b6a2314ff..7aad66710 100644 --- a/gtsam/geometry/Pose2.h +++ b/gtsam/geometry/Pose2.h @@ -33,7 +33,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Pose2 : public DerivedValue { +class GTSAM_EXPORT Pose2 { public: @@ -301,8 +301,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Pose2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(t_); ar & BOOST_SERIALIZATION_NVP(r_); } @@ -325,11 +323,11 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs); namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Pose3.h b/gtsam/geometry/Pose3.h index 5f99b25ac..001edb563 100644 --- a/gtsam/geometry/Pose3.h +++ b/gtsam/geometry/Pose3.h @@ -39,7 +39,7 @@ class Pose2; * @addtogroup geometry * \nosubgrouping */ -class GTSAM_EXPORT Pose3: public DerivedValue { +class GTSAM_EXPORT Pose3{ public: /** Pose Concept requirements */ @@ -326,8 +326,6 @@ public: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Pose3", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(R_); ar & BOOST_SERIALIZATION_NVP(t_); } @@ -358,15 +356,15 @@ GTSAM_EXPORT boost::optional align(const std::vector& pairs); namespace traits { template<> -struct is_group : public std::true_type { +struct is_group : public boost::true_type { }; template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Rot2.h b/gtsam/geometry/Rot2.h index 4142d4473..c5d6141b6 100644 --- a/gtsam/geometry/Rot2.h +++ b/gtsam/geometry/Rot2.h @@ -31,7 +31,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Rot2 : public DerivedValue { + class GTSAM_EXPORT Rot2 { public: /** get the dimension by the type */ @@ -235,8 +235,6 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Rot2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(c_); ar & BOOST_SERIALIZATION_NVP(s_); } @@ -247,15 +245,15 @@ namespace gtsam { namespace traits { template<> - struct is_group : public std::true_type { + struct is_group : public boost::true_type { }; template<> - struct is_manifold : public std::true_type { + struct is_manifold : public boost::true_type { }; template<> - struct dimension : public std::integral_constant { + struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 7215e159f..4f40d164d 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -58,7 +58,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT Rot3 : public DerivedValue { + class GTSAM_EXPORT Rot3 { private: @@ -456,8 +456,6 @@ namespace gtsam { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Rot3", - boost::serialization::base_object(*this)); #ifndef GTSAM_USE_QUATERNIONS ar & boost::serialization::make_nvp("rot11", rot_(0,0)); ar & boost::serialization::make_nvp("rot12", rot_(0,1)); @@ -494,15 +492,15 @@ namespace gtsam { namespace traits { template<> - struct is_group : public std::true_type { + struct is_group : public boost::true_type { }; template<> - struct is_manifold : public std::true_type { + struct is_manifold : public boost::true_type { }; template<> - struct dimension : public std::integral_constant { + struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/StereoCamera.h b/gtsam/geometry/StereoCamera.h index 82914f6ab..6b290edac 100644 --- a/gtsam/geometry/StereoCamera.h +++ b/gtsam/geometry/StereoCamera.h @@ -36,7 +36,7 @@ public: * A stereo camera class, parameterize by left camera pose and stereo calibration * @addtogroup geometry */ -class GTSAM_EXPORT StereoCamera : public DerivedValue { +class GTSAM_EXPORT StereoCamera { private: Pose3 leftCamPose_; @@ -147,8 +147,6 @@ private: friend class boost::serialization::access; template void serialize(Archive & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("StereoCamera", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(leftCamPose_); ar & BOOST_SERIALIZATION_NVP(K_); } @@ -159,11 +157,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/StereoPoint2.h b/gtsam/geometry/StereoPoint2.h index 000f7d16f..d62a3f067 100644 --- a/gtsam/geometry/StereoPoint2.h +++ b/gtsam/geometry/StereoPoint2.h @@ -28,7 +28,7 @@ namespace gtsam { * @addtogroup geometry * \nosubgrouping */ - class GTSAM_EXPORT StereoPoint2 : public DerivedValue { + class GTSAM_EXPORT StereoPoint2 { public: static const size_t dimension = 3; private: @@ -162,8 +162,6 @@ namespace gtsam { friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("StereoPoint2", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(uL_); ar & BOOST_SERIALIZATION_NVP(uR_); ar & BOOST_SERIALIZATION_NVP(v_); @@ -177,15 +175,15 @@ namespace gtsam { namespace traits { template<> - struct is_group : public std::true_type { + struct is_group : public boost::true_type { }; template<> - struct is_manifold : public std::true_type { + struct is_manifold : public boost::true_type { }; template<> - struct dimension : public std::integral_constant { + struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/geometry/Unit3.h b/gtsam/geometry/Unit3.h index bb2ee318a..3be83aa15 100644 --- a/gtsam/geometry/Unit3.h +++ b/gtsam/geometry/Unit3.h @@ -27,7 +27,7 @@ namespace gtsam { /// Represents a 3D point on a unit sphere. -class GTSAM_EXPORT Unit3: public DerivedValue { +class GTSAM_EXPORT Unit3{ private: @@ -146,8 +146,6 @@ private: friend class boost::serialization::access; template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("Unit3", - boost::serialization::base_object(*this)); ar & BOOST_SERIALIZATION_NVP(p_); ar & BOOST_SERIALIZATION_NVP(B_); } @@ -160,11 +158,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam/geometry/tests/testRot3.cpp b/gtsam/geometry/tests/testRot3.cpp index 9761dfd74..973ec895f 100644 --- a/gtsam/geometry/tests/testRot3.cpp +++ b/gtsam/geometry/tests/testRot3.cpp @@ -142,7 +142,7 @@ TEST( Rot3, retract) // test Canonical coordinates Canonical chart; - Vector v2 = chart.apply(R); + Vector v2 = chart.local(R); CHECK(assert_equal(R, chart.retract(v2))); } diff --git a/gtsam/navigation/ImuBias.h b/gtsam/navigation/ImuBias.h index 8301a0a6b..9bc24c152 100644 --- a/gtsam/navigation/ImuBias.h +++ b/gtsam/navigation/ImuBias.h @@ -39,7 +39,7 @@ namespace gtsam { /// All bias models live in the imuBias namespace namespace imuBias { - class ConstantBias : public DerivedValue { + class ConstantBias { private: Vector3 biasAcc_; Vector3 biasGyro_; @@ -205,8 +205,7 @@ namespace imuBias { template void serialize(ARCHIVE & ar, const unsigned int version) { - ar & boost::serialization::make_nvp("imuBias::ConstantBias", - boost::serialization::base_object(*this)); + ar & boost::serialization::make_nvp("imuBias::ConstantBias",*this); ar & BOOST_SERIALIZATION_NVP(biasAcc_); ar & BOOST_SERIALIZATION_NVP(biasGyro_); } @@ -222,15 +221,15 @@ namespace imuBias { namespace traits { template<> -struct is_group : public std::true_type { +struct is_group : public boost::true_type { }; template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam/nonlinear/Values-inl.h b/gtsam/nonlinear/Values-inl.h index 7b812551e..49ea03e9f 100644 --- a/gtsam/nonlinear/Values-inl.h +++ b/gtsam/nonlinear/Values-inl.h @@ -33,6 +33,7 @@ namespace gtsam { + /* ************************************************************************* */ template struct _ValuesKeyValuePair { @@ -52,6 +53,36 @@ namespace gtsam { _ValuesConstKeyValuePair(const _ValuesKeyValuePair& rhs) : key(rhs.key), value(rhs.value) {} }; + /* ************************************************************************* */ + + // Cast helpers for making _Values[Const]KeyValuePair's from Values::[Const]KeyValuePair + // need to use a struct here for later partial specialization + template + struct ValuesCastHelper { + static CastedKeyValuePairType cast(KeyValuePairType key_value) { + // Static cast because we already checked the type during filtering + return CastedKeyValuePairType(key_value.key, const_cast&>(static_cast&>(key_value.value)).value()); + } + }; + // partial specialized version for ValueType == Value + template + struct ValuesCastHelper { + static CastedKeyValuePairType cast(KeyValuePairType key_value) { + // Static cast because we already checked the type during filtering + // in this case the casted and keyvalue pair are essentially the same type (key, Value&) so perhaps this could be done with just a cast of the key_value? + return CastedKeyValuePairType(key_value.key, key_value.value); + } + }; + // partial specialized version for ValueType == Value + template + struct ValuesCastHelper { + static CastedKeyValuePairType cast(KeyValuePairType key_value) { + // Static cast because we already checked the type during filtering + // in this case the casted and keyvalue pair are essentially the same type (key, Value&) so perhaps this could be done with just a cast of the key_value? + return CastedKeyValuePairType(key_value.key, key_value.value); + } + }; + /* ************************************************************************* */ template class Values::Filtered { @@ -99,19 +130,19 @@ namespace gtsam { begin_(boost::make_transform_iterator( boost::make_filter_iterator( filter, values.begin(), values.end()), - &castHelper)), + &ValuesCastHelper::cast)), end_(boost::make_transform_iterator( boost::make_filter_iterator( filter, values.end(), values.end()), - &castHelper)), + &ValuesCastHelper::cast)), constBegin_(boost::make_transform_iterator( boost::make_filter_iterator( filter, ((const Values&)values).begin(), ((const Values&)values).end()), - &castHelper)), + &ValuesCastHelper::cast)), constEnd_(boost::make_transform_iterator( boost::make_filter_iterator( filter, ((const Values&)values).end(), ((const Values&)values).end()), - &castHelper)) {} + &ValuesCastHelper::cast)) {} friend class Values; iterator begin_; @@ -175,7 +206,7 @@ namespace gtsam { Values::Values(const Values::Filtered& view) { BOOST_FOREACH(const typename Filtered::KeyValuePair& key_value, view) { Key key = key_value.key; - insert(key, key_value.value); + insert(key, static_cast(key_value.value)); } } @@ -184,7 +215,7 @@ namespace gtsam { Values::Values(const Values::ConstFiltered& view) { BOOST_FOREACH(const typename ConstFiltered::KeyValuePair& key_value, view) { Key key = key_value.key; - insert(key, key_value.value); + insert(key, key_value.value); } } @@ -214,6 +245,13 @@ namespace gtsam { return ConstFiltered(boost::bind(&filterHelper, filterFcn, _1), *this); } + /* ************************************************************************* */ + template<> + inline bool Values::filterHelper(const boost::function filter, const ConstKeyValuePair& key_value) { + // Filter and check the type + return filter(key_value.key); + } + /* ************************************************************************* */ template const ValueType& Values::at(Key j) const { @@ -225,11 +263,11 @@ namespace gtsam { throw ValuesKeyDoesNotExist("retrieve", j); // Check the type and throw exception if incorrect - if(typeid(*item->second) != typeid(ValueType)) + try { + return dynamic_cast&>(*item->second).value(); + } catch (std::bad_cast &) { throw ValuesIncorrectType(j, typeid(*item->second), typeid(ValueType)); - - // We have already checked the type, so do a "blind" static_cast, not dynamic_cast - return static_cast(*item->second); + } } /* ************************************************************************* */ @@ -239,15 +277,49 @@ namespace gtsam { KeyValueMap::const_iterator item = values_.find(j); if(item != values_.end()) { - // Check the type and throw exception if incorrect - if(typeid(*item->second) != typeid(ValueType)) + // dynamic cast the type and throw exception if incorrect + try { + return dynamic_cast&>(*item->second).value(); + } catch (std::bad_cast &) { throw ValuesIncorrectType(j, typeid(*item->second), typeid(ValueType)); - - // We have already checked the type, so do a "blind" static_cast, not dynamic_cast - return static_cast(*item->second); - } else { + } + } else { return boost::none; } } + /* ************************************************************************* */ + // insert a plain value using the default chart + template + void Values::insert(Key j, const ValueType& val) { + insert(j, static_cast(ChartValue >(val))); + } + + // insert with custom chart type + template + void Values::insert(Key j, const ValueType& val) { + insert(j, static_cast(ChartValue(val))); + } + // overloaded insert with chart initializer + template + void Values::insert(Key j, const ValueType& val, ChartInit chart) { + insert(j, static_cast(ChartValue(val, chart))); + } + + // update with default chart + template + void Values::update(Key j, const ValueType& val) { + update(j, static_cast(ChartValue >(val))); + } + // update with custom chart + template + void Values::update(Key j, const ValueType& val) { + update(j, static_cast(ChartValue(val))); + } + // update with chart initializer, /todo: perhaps there is a way to init chart from old value... + template + void Values::update(Key j, const ValueType& val, ChartInit chart) { + update(j, static_cast(ChartValue(val, chart))); + } + } diff --git a/gtsam/nonlinear/Values.h b/gtsam/nonlinear/Values.h index 811846f79..e31bfa941 100644 --- a/gtsam/nonlinear/Values.h +++ b/gtsam/nonlinear/Values.h @@ -44,7 +44,7 @@ #include #include -#include +#include #include #include @@ -251,6 +251,19 @@ namespace gtsam { /** Add a set of variables, throws KeyAlreadyExists if a key is already present */ void insert(const Values& values); + /** Templated verion to add a variable with the given j, + * throws KeyAlreadyExists if j is already present + * if no chart is specified, the DefaultChart is used + */ + template + void insert(Key j, const ValueType& val); + template + void insert(Key j, const ValueType& val); + // overloaded insert version that also specifies a chart initializer + template + void insert(Key j, const ValueType& val, ChartInit chart); + + /** insert that mimics the STL map insert - if the value already exists, the map is not modified * and an iterator to the existing value is returned, along with 'false'. If the value did not * exist, it is inserted and an iterator pointing to the new element, along with 'true', is @@ -260,6 +273,17 @@ namespace gtsam { /** single element change of existing element */ void update(Key j, const Value& val); + /** Templated verion to update a variable with the given j, + * throws KeyAlreadyExists if j is already present + * if no chart is specified, the DefaultChart is used + */ + template + void update(Key j, const T& val); + template + void update(Key j, const T& val); + template + void update(Key j, const T& val, ChartInit chart); + /** update the current available values without adding new ones */ void update(const Values& values); @@ -369,15 +393,9 @@ namespace gtsam { // supplied \c filter function. template static bool filterHelper(const boost::function filter, const ConstKeyValuePair& key_value) { + BOOST_STATIC_ASSERT((!boost::is_same::value)); // Filter and check the type - return filter(key_value.key) && (typeid(ValueType) == typeid(key_value.value) || typeid(ValueType) == typeid(Value)); - } - - // Cast to the derived ValueType - template - static CastedKeyValuePairType castHelper(KeyValuePairType key_value) { - // Static cast because we already checked the type during filtering - return CastedKeyValuePairType(key_value.key, static_cast(key_value.value)); + return filter(key_value.key) && (dynamic_cast*>(&key_value.value)); } /** Serialization function */ diff --git a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp index ee2f0d793..a8f287d1e 100644 --- a/gtsam/nonlinear/tests/testSerializationNonlinear.cpp +++ b/gtsam/nonlinear/tests/testSerializationNonlinear.cpp @@ -32,20 +32,37 @@ using namespace gtsam::serializationTestHelpers; /* ************************************************************************* */ // Export all classes derived from Value -BOOST_CLASS_EXPORT(gtsam::Cal3_S2) -BOOST_CLASS_EXPORT(gtsam::Cal3Bundler) -BOOST_CLASS_EXPORT(gtsam::Point3) -BOOST_CLASS_EXPORT(gtsam::Pose3) -BOOST_CLASS_EXPORT(gtsam::Rot3) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) -BOOST_CLASS_EXPORT(gtsam::PinholeCamera) +BOOST_CLASS_EXPORT(gtsam::Cal3_S2); +BOOST_CLASS_EXPORT(gtsam::Cal3Bundler); +BOOST_CLASS_EXPORT(gtsam::Point3); +BOOST_CLASS_EXPORT(gtsam::Pose3); +BOOST_CLASS_EXPORT(gtsam::Rot3); +BOOST_CLASS_EXPORT(gtsam::PinholeCamera); +BOOST_CLASS_EXPORT(gtsam::PinholeCamera); +BOOST_CLASS_EXPORT(gtsam::PinholeCamera); + +namespace detail { +template struct pack { + typedef T type; +}; +} +#define CHART_VALUE_EXPORT(UNIQUE_NAME, TYPE) \ + typedef gtsam::ChartValue > UNIQUE_NAME; \ + BOOST_CLASS_EXPORT( UNIQUE_NAME ); + /* ************************************************************************* */ typedef PinholeCamera PinholeCal3S2; typedef PinholeCamera PinholeCal3DS2; typedef PinholeCamera PinholeCal3Bundler; +CHART_VALUE_EXPORT(gtsamPoint3Chart, gtsam::Point3); +CHART_VALUE_EXPORT(Cal3S2Chart, PinholeCal3S2); +CHART_VALUE_EXPORT(Cal3DS2Chart, PinholeCal3DS2); +CHART_VALUE_EXPORT(Cal3BundlerChart, PinholeCal3Bundler); + + + /* ************************************************************************* */ static Point3 pt3(1.0, 2.0, 3.0); static Rot3 rt3 = Rot3::RzRyRx(1.0, 3.0, 2.0); @@ -56,12 +73,27 @@ static Cal3DS2 cal2(1.0, 2.0, 3.0, 4.0, 5.0, 6.0, 7.0, 8.0, 9.0); static Cal3Bundler cal3(1.0, 2.0, 3.0); TEST (Serialization, TemplatedValues) { + std::cout << __LINE__ << std::endl; + EXPECT(equalsObj(pt3)); + std::cout << __LINE__ << std::endl; + ChartValue chv1(pt3); + std::cout << __LINE__ << std::endl; + EXPECT(equalsObj(chv1)); + std::cout << __LINE__ << std::endl; + PinholeCal3S2 pc(pose3,cal1); + EXPECT(equalsObj(pc)); + std::cout << __LINE__ << std::endl; Values values; + values.insert(1,pt3); + std::cout << __LINE__ << std::endl; + EXPECT(equalsObj(values)); + std::cout << __LINE__ << std::endl; values.insert(Symbol('a',0), PinholeCal3S2(pose3, cal1)); values.insert(Symbol('s',5), PinholeCal3DS2(pose3, cal2)); values.insert(Symbol('d',47), PinholeCal3Bundler(pose3, cal3)); values.insert(Symbol('a',5), PinholeCal3S2(pose3, cal1)); EXPECT(equalsObj(values)); + std::cout << __LINE__ << std::endl; EXPECT(equalsXML(values)); EXPECT(equalsBinary(values)); } diff --git a/gtsam/nonlinear/tests/testValues.cpp b/gtsam/nonlinear/tests/testValues.cpp index 041ea0387..9b9e8d0e0 100644 --- a/gtsam/nonlinear/tests/testValues.cpp +++ b/gtsam/nonlinear/tests/testValues.cpp @@ -38,7 +38,7 @@ static double inf = std::numeric_limits::infinity(); using symbol_shorthand::X; using symbol_shorthand::L; -const Symbol key1('v',1), key2('v',2), key3('v',3), key4('v',4); +const Symbol key1('v', 1), key2('v', 2), key3('v', 3), key4('v', 4); class TestValueData { @@ -51,26 +51,35 @@ public: }; int TestValueData::ConstructorCount = 0; int TestValueData::DestructorCount = 0; -class TestValue : public DerivedValue { +class TestValue { TestValueData data_; public: - virtual void print(const std::string& str = "") const {} + void print(const std::string& str = "") const {} bool equals(const TestValue& other, double tol = 1e-9) const { return true; } - virtual size_t dim() const { return 0; } + size_t dim() const { return 0; } TestValue retract(const Vector&) const { return TestValue(); } Vector localCoordinates(const TestValue&) const { return Vector(); } }; +namespace gtsam { +namespace traits { +template <> +struct is_manifold : public boost::true_type {}; +template <> +struct dimension : public boost::integral_constant {}; +} +} + /* ************************************************************************* */ TEST( Values, equals1 ) { Values expected; LieVector v((Vector(3) << 5.0, 6.0, 7.0)); - expected.insert(key1,v); + expected.insert(key1, v); Values actual; - actual.insert(key1,v); - CHECK(assert_equal(expected,actual)); + actual.insert(key1, v); + CHECK(assert_equal(expected, actual)); } /* ************************************************************************* */ @@ -260,7 +269,7 @@ TEST(Values, expmap_d) CHECK(config0.equals(config0)); Values poseconfig; - poseconfig.insert(key1, Pose2(1,2,3)); + poseconfig.insert(key1, Pose2(1, 2, 3)); poseconfig.insert(key2, Pose2(0.3, 0.4, 0.5)); CHECK(equal(config0, config0)); @@ -330,7 +339,7 @@ TEST(Values, update) Values expected; expected.insert(key1, LieVector((Vector(1) << -1.))); expected.insert(key2, LieVector((Vector(1) << -2.))); - CHECK(assert_equal(expected,config0)); + CHECK(assert_equal(expected, config0)); } /* ************************************************************************* */ @@ -353,12 +362,14 @@ TEST(Values, filter) { BOOST_FOREACH(const Values::Filtered<>::KeyValuePair& key_value, filtered) { if(i == 0) { LONGS_EQUAL(2, (long)key_value.key); - EXPECT(typeid(Pose2) == typeid(key_value.value)); - EXPECT(assert_equal(pose2, dynamic_cast(key_value.value))); + try {key_value.value.cast();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose2");} + THROWS_EXCEPTION(key_value.value.cast()); + EXPECT(assert_equal(pose2, key_value.value.cast())); } else if(i == 1) { LONGS_EQUAL(3, (long)key_value.key); - EXPECT(typeid(Pose3) == typeid(key_value.value)); - EXPECT(assert_equal(pose3, dynamic_cast(key_value.value))); + try {key_value.value.cast();} catch (const std::bad_cast& e) { FAIL("can't cast Value to Pose3");} + THROWS_EXCEPTION(key_value.value.cast()); + EXPECT(assert_equal(pose3, key_value.value.cast())); } else { EXPECT(false); } @@ -408,18 +419,18 @@ TEST(Values, Symbol_filter) { Values values; values.insert(X(0), pose0); - values.insert(Symbol('y',1), pose1); + values.insert(Symbol('y', 1), pose1); values.insert(X(2), pose2); - values.insert(Symbol('y',3), pose3); + values.insert(Symbol('y', 3), pose3); int i = 0; BOOST_FOREACH(const Values::Filtered::KeyValuePair& key_value, values.filter(Symbol::ChrTest('y'))) { if(i == 0) { LONGS_EQUAL(Symbol('y', 1), (long)key_value.key); - EXPECT(assert_equal(pose1, dynamic_cast(key_value.value))); + EXPECT(assert_equal(pose1, key_value.value.cast())); } else if(i == 1) { LONGS_EQUAL(Symbol('y', 3), (long)key_value.key); - EXPECT(assert_equal(pose3, dynamic_cast(key_value.value))); + EXPECT(assert_equal(pose3, key_value.value.cast())); } else { EXPECT(false); } @@ -441,11 +452,15 @@ TEST(Values, Destructors) { values.insert(0, value1); values.insert(1, value2); } - LONGS_EQUAL(4, (long)TestValueData::ConstructorCount); - LONGS_EQUAL(2, (long)TestValueData::DestructorCount); + // additional 2 con/destructor counts for the temporary + // GenericValue in insert() + // but I'm sure some advanced programmer can figure out + // a way to avoid the temporary, or optimize it out + LONGS_EQUAL(4+2, (long)TestValueData::ConstructorCount); + LONGS_EQUAL(2+2, (long)TestValueData::DestructorCount); } - LONGS_EQUAL(4, (long)TestValueData::ConstructorCount); - LONGS_EQUAL(4, (long)TestValueData::DestructorCount); + LONGS_EQUAL(4+2, (long)TestValueData::ConstructorCount); + LONGS_EQUAL(4+2, (long)TestValueData::DestructorCount); } /* ************************************************************************* */ diff --git a/gtsam/slam/dataset.cpp b/gtsam/slam/dataset.cpp index db85c65bf..388d712e7 100644 --- a/gtsam/slam/dataset.cpp +++ b/gtsam/slam/dataset.cpp @@ -1,5 +1,4 @@ /* ---------------------------------------------------------------------------- - * GTSAM Copyright 2010, Georgia Tech Research Corporation, * Atlanta, Georgia 30332-0415 * All Rights Reserved @@ -330,8 +329,9 @@ void save2D(const NonlinearFactorGraph& graph, const Values& config, fstream stream(filename.c_str(), fstream::out); // save poses + BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, config) { - const Pose2& pose = dynamic_cast(key_value.value); + const Pose2& pose = key_value.value.cast(); stream << "VERTEX2 " << key_value.key << " " << pose.x() << " " << pose.y() << " " << pose.theta() << endl; } @@ -373,25 +373,22 @@ GraphAndValues readG2o(const string& g2oFile, const bool is3D, /* ************************************************************************* */ void writeG2o(const NonlinearFactorGraph& graph, const Values& estimate, const string& filename) { - fstream stream(filename.c_str(), fstream::out); // save 2D & 3D poses - BOOST_FOREACH(const Values::ConstKeyValuePair& key_value, estimate) { + Values::ConstFiltered viewPose2 = estimate.filter(); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, viewPose2) { + stream << "VERTEX_SE2 " << key_value.key << " " << key_value.value.x() << " " + << key_value.value.y() << " " << key_value.value.theta() << endl; + } - const Pose2* pose2D = dynamic_cast(&key_value.value); - if(pose2D){ - stream << "VERTEX_SE2 " << key_value.key << " " << pose2D->x() << " " - << pose2D->y() << " " << pose2D->theta() << endl; - } - const Pose3* pose3D = dynamic_cast(&key_value.value); - if(pose3D){ - Point3 p = pose3D->translation(); - Rot3 R = pose3D->rotation(); + Values::ConstFiltered viewPose3 = estimate.filter(); + BOOST_FOREACH(const Values::ConstFiltered::KeyValuePair& key_value, viewPose3) { + Point3 p = key_value.value.translation(); + Rot3 R = key_value.value.rotation(); stream << "VERTEX_SE3:QUAT " << key_value.key << " " << p.x() << " " << p.y() << " " << p.z() << " " << R.toQuaternion().x() << " " << R.toQuaternion().y() << " " << R.toQuaternion().z() << " " << R.toQuaternion().w() << endl; - } } // save edges (2D or 3D) diff --git a/gtsam_unstable/dynamics/PoseRTV.h b/gtsam_unstable/dynamics/PoseRTV.h index 80729e8a2..ae4ddade4 100644 --- a/gtsam_unstable/dynamics/PoseRTV.h +++ b/gtsam_unstable/dynamics/PoseRTV.h @@ -19,7 +19,7 @@ typedef Point3 Velocity3; * Robot state for use with IMU measurements * - contains translation, translational velocity and rotation */ -class GTSAM_UNSTABLE_EXPORT PoseRTV : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT PoseRTV { protected: Pose3 Rt_; @@ -187,11 +187,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; template<> diff --git a/gtsam_unstable/geometry/BearingS2.h b/gtsam_unstable/geometry/BearingS2.h index d48490ccc..4c84bbe56 100644 --- a/gtsam_unstable/geometry/BearingS2.h +++ b/gtsam_unstable/geometry/BearingS2.h @@ -15,7 +15,7 @@ namespace gtsam { -class GTSAM_UNSTABLE_EXPORT BearingS2 : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT BearingS2 { protected: Rot2 azimuth_, elevation_; diff --git a/gtsam_unstable/geometry/Pose3Upright.h b/gtsam_unstable/geometry/Pose3Upright.h index c1e12b4a7..22aab5d44 100644 --- a/gtsam_unstable/geometry/Pose3Upright.h +++ b/gtsam_unstable/geometry/Pose3Upright.h @@ -22,7 +22,7 @@ namespace gtsam { * @ingroup geometry * \nosubgrouping */ -class GTSAM_UNSTABLE_EXPORT Pose3Upright : public DerivedValue { +class GTSAM_UNSTABLE_EXPORT Pose3Upright { public: static const size_t dimension = 4; @@ -144,11 +144,11 @@ private: namespace traits { template<> -struct is_manifold : public std::true_type { +struct is_manifold : public boost::true_type { }; template<> -struct dimension : public std::integral_constant { +struct dimension : public boost::integral_constant { }; } diff --git a/gtsam_unstable/nonlinear/AdaptAutoDiff.h b/gtsam_unstable/nonlinear/AdaptAutoDiff.h index fc1f98064..96978d9cf 100644 --- a/gtsam_unstable/nonlinear/AdaptAutoDiff.h +++ b/gtsam_unstable/nonlinear/AdaptAutoDiff.h @@ -59,8 +59,8 @@ public: using ceres::internal::AutoDiff; // Make arguments - Vector1 v1 = chart1.apply(a1); - Vector2 v2 = chart2.apply(a2); + Vector1 v1 = chart1.local(a1); + Vector2 v2 = chart2.local(a2); bool success; VectorT result; diff --git a/gtsam_unstable/nonlinear/Expression-inl.h b/gtsam_unstable/nonlinear/Expression-inl.h index b4cbb8728..215525bb9 100644 --- a/gtsam_unstable/nonlinear/Expression-inl.h +++ b/gtsam_unstable/nonlinear/Expression-inl.h @@ -311,8 +311,9 @@ public: //----------------------------------------------------------------------------- /// Leaf Expression -template +template > class LeafExpression: public ExpressionNode { + typedef ChartValue value_type; // perhaps this can be something else like a std::pair ?? /// The key into values Key key_; @@ -321,6 +322,53 @@ class LeafExpression: public ExpressionNode { LeafExpression(Key key) : key_(key) { } + // todo: do we need a virtual destructor here too? + + friend class Expression ; + +public: + + /// Return keys that play in this expression + virtual std::set keys() const { + std::set keys; + keys.insert(key_); + return keys; + } + + /// Return dimensions for each argument + virtual void dims(std::map& map) const { + // get dimension from the chart; only works for fixed dimension charts + map[key_] = traits::dimension::value; + } + + /// Return value + virtual const value_type& value(const Values& values) const { + return dynamic_cast(values.at(key_)); + } + + /// Construct an execution trace for reverse AD + virtual const value_type& traceExecution(const Values& values, ExecutionTrace& trace, + char* raw) const { + trace.setLeaf(key_); + return dynamic_cast(values.at(key_)); + } + +}; + +//----------------------------------------------------------------------------- +/// Leaf Expression, if no chart is given, assume default chart and value_type is just the plain value +template +class LeafExpression >: public ExpressionNode { + typedef T value_type; + + /// The key into values + Key key_; + + /// Constructor with a single key + LeafExpression(Key key) : + key_(key) { + } + // todo: do we need a virtual destructor here too? friend class Expression ; @@ -392,7 +440,7 @@ struct Jacobian { /// meta-function to generate JacobianTA optional reference template -struct Optional { +struct OptionalJacobian { typedef Eigen::Matrix::value, traits::dimension::value> Jacobian; typedef boost::optional type; @@ -522,7 +570,7 @@ struct FunctionalNode { // Argument types and derived, note these are base 0 ! typedef TYPES Arguments; typedef typename boost::mpl::transform >::type Jacobians; - typedef typename boost::mpl::transform >::type Optionals; + typedef typename boost::mpl::transform >::type Optionals; /// Reset expression shared pointer template @@ -577,7 +625,7 @@ class UnaryExpression: public FunctionalNode >::type { public: - typedef boost::function::type)> Function; + typedef boost::function::type)> Function; typedef typename FunctionalNode >::type Base; typedef typename Base::Record Record; @@ -622,8 +670,8 @@ class BinaryExpression: public FunctionalNode >::t public: typedef boost::function< - T(const A1&, const A2&, typename Optional::type, - typename Optional::type)> Function; + T(const A1&, const A2&, typename OptionalJacobian::type, + typename OptionalJacobian::type)> Function; typedef typename FunctionalNode >::type Base; typedef typename Base::Record Record; @@ -676,8 +724,8 @@ class TernaryExpression: public FunctionalNode public: typedef boost::function< - T(const A1&, const A2&, const A3&, typename Optional::type, - typename Optional::type, typename Optional::type)> Function; + T(const A1&, const A2&, const A3&, typename OptionalJacobian::type, + typename OptionalJacobian::type, typename OptionalJacobian::type)> Function; typedef typename FunctionalNode >::type Base; typedef typename Base::Record Record; diff --git a/gtsam_unstable/nonlinear/Expression.h b/gtsam_unstable/nonlinear/Expression.h index a1f617b8f..fc1efeb87 100644 --- a/gtsam_unstable/nonlinear/Expression.h +++ b/gtsam_unstable/nonlinear/Expression.h @@ -61,7 +61,7 @@ public: /// Construct a nullary method expression template Expression(const Expression& expression, - T (A::*method)(typename Optional::type) const) : + T (A::*method)(typename OptionalJacobian::type) const) : root_(new UnaryExpression(boost::bind(method, _1, _2), expression)) { } @@ -75,8 +75,8 @@ public: /// Construct a unary method expression template Expression(const Expression& expression1, - T (A1::*method)(const A2&, typename Optional::type, - typename Optional::type) const, + T (A1::*method)(const A2&, typename OptionalJacobian::type, + typename OptionalJacobian::type) const, const Expression& expression2) : root_( new BinaryExpression(boost::bind(method, _1, _2, _3, _4), diff --git a/gtsam_unstable/nonlinear/tests/testAdaptAutoDiff.cpp b/gtsam_unstable/nonlinear/tests/testAdaptAutoDiff.cpp index f26a1e61d..0c9046d6c 100644 --- a/gtsam_unstable/nonlinear/tests/testAdaptAutoDiff.cpp +++ b/gtsam_unstable/nonlinear/tests/testAdaptAutoDiff.cpp @@ -202,7 +202,7 @@ TEST(Expression, Snavely) { #ifdef GTSAM_USE_QUATERNIONS EXPECT_LONGS_EQUAL(480,expression.traceSize()); // Todo, should be zero #else - EXPECT_LONGS_EQUAL(448,expression.traceSize()); // Todo, should be zero + EXPECT_LONGS_EQUAL(432,expression.traceSize()); // Todo, should be zero #endif set expected = list_of(1)(2); EXPECT(expected == expression.keys()); diff --git a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp index fa2e5cadb..ce8d6ac06 100644 --- a/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpressionFactor.cpp @@ -147,19 +147,19 @@ TEST(ExpressionFactor, Binary) { // traceRaw will fill raw with [Trace | Binary::Record] EXPECT_LONGS_EQUAL(8, sizeof(double)); - EXPECT_LONGS_EQUAL(24, sizeof(Point2)); - EXPECT_LONGS_EQUAL(48, sizeof(Cal3_S2)); + EXPECT_LONGS_EQUAL(16, sizeof(Point2)); + EXPECT_LONGS_EQUAL(40, sizeof(Cal3_S2)); EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); EXPECT_LONGS_EQUAL(16, sizeof(ExecutionTrace)); EXPECT_LONGS_EQUAL(2*5*8, sizeof(Jacobian::type)); EXPECT_LONGS_EQUAL(2*2*8, sizeof(Jacobian::type)); - size_t expectedRecordSize = 24 + 24 + 48 + 2 * 16 + 80 + 32; - EXPECT_LONGS_EQUAL(expectedRecordSize, sizeof(Binary::Record)); + size_t expectedRecordSize = 16 + 16 + 40 + 2 * 16 + 80 + 32; + EXPECT_LONGS_EQUAL(expectedRecordSize + 8, sizeof(Binary::Record)); // Check size size_t size = binary.traceSize(); CHECK(size); - EXPECT_LONGS_EQUAL(expectedRecordSize, size); + EXPECT_LONGS_EQUAL(expectedRecordSize + 8, size); // Use Variable Length Array, allocated on stack by gcc // Note unclear for Clang: http://clang.llvm.org/compatibility.html#vla char raw[size]; @@ -211,8 +211,8 @@ TEST(ExpressionFactor, Shallow) { EXPECT_LONGS_EQUAL(464, sizeof(Binary::Record)); LONGS_EQUAL(112+464, expectedTraceSize); #else - EXPECT_LONGS_EQUAL(432, sizeof(Binary::Record)); - LONGS_EQUAL(112+432, expectedTraceSize); + EXPECT_LONGS_EQUAL(400, sizeof(Binary::Record)); + LONGS_EQUAL(112+400, expectedTraceSize); #endif size_t size = expression.traceSize(); CHECK(size); diff --git a/gtsam_unstable/nonlinear/tests/testExpressionMeta.cpp b/gtsam_unstable/nonlinear/tests/testExpressionMeta.cpp index ecc343384..84a1ca720 100644 --- a/gtsam_unstable/nonlinear/tests/testExpressionMeta.cpp +++ b/gtsam_unstable/nonlinear/tests/testExpressionMeta.cpp @@ -201,7 +201,7 @@ Pose3 pose; // Now, let's create the optional Jacobian arguments typedef Point3 T; typedef boost::mpl::vector TYPES; - typedef boost::mpl::transform >::type Optionals; + typedef boost::mpl::transform >::type Optionals; // Unfortunately this is moot: we need a pointer to a function with the // optional derivatives; I don't see a way of calling a function that we diff --git a/tests/testManifold.cpp b/tests/testManifold.cpp index a55e2fdea..55a5f5af0 100644 --- a/tests/testManifold.cpp +++ b/tests/testManifold.cpp @@ -17,6 +17,7 @@ * @brief unit tests for Block Automatic Differentiation */ +#include #include #include #include @@ -65,48 +66,48 @@ TEST(Manifold, _dimension) { // charts TEST(Manifold, DefaultChart) { - DefaultChart chart1(Point2(0, 0)); - EXPECT(chart1.apply(Point2(1,0))==Vector2(1,0)); - EXPECT(chart1.retract(Vector2(1,0))==Point2(1,0)); + DefaultChart chart1; + EXPECT(chart1.local(Point2(0, 0), Point2(1, 0)) == Vector2(1, 0)); + EXPECT(chart1.retract(Point2(0, 0), Vector2(1, 0)) == Point2(1, 0)); Vector v2(2); v2 << 1, 0; - DefaultChart chart2(Vector2(0, 0)); - EXPECT(assert_equal(v2,chart2.apply(Vector2(1,0)))); - EXPECT(chart2.retract(v2)==Vector2(1,0)); + DefaultChart chart2; + EXPECT(assert_equal(v2, chart2.local(Vector2(0, 0), Vector2(1, 0)))); + EXPECT(chart2.retract(Vector2(0, 0), v2) == Vector2(1, 0)); - DefaultChart chart3(0); + DefaultChart chart3; Vector v1(1); v1 << 1; - EXPECT(assert_equal(v1,chart3.apply(1))); - EXPECT_DOUBLES_EQUAL(chart3.retract(v1), 1, 1e-9); + EXPECT(assert_equal(v1, chart3.local(0, 1))); + EXPECT_DOUBLES_EQUAL(chart3.retract(0, v1), 1, 1e-9); // Dynamic does not work yet ! Vector z = zero(2), v(2); v << 1, 0; - DefaultChart chart4(z); - EXPECT(assert_equal(chart4.apply(v),v)); - EXPECT(assert_equal(chart4.retract(v),v)); + DefaultChart chart4; + EXPECT(assert_equal(chart4.local(z, v), v)); + EXPECT(assert_equal(chart4.retract(z, v), v)); Vector v3(3); v3 << 1, 1, 1; Rot3 I = Rot3::identity(); Rot3 R = I.retract(v3); - DefaultChart chart5(I); - EXPECT(assert_equal(v3,chart5.apply(R))); - EXPECT(assert_equal(chart5.retract(v3),R)); + DefaultChart chart5; + EXPECT(assert_equal(v3, chart5.local(I, R))); + EXPECT(assert_equal(chart5.retract(I, v3), R)); // Check zero vector - DefaultChart chart6(R); - EXPECT(assert_equal(zero(3),chart6.apply(R))); + DefaultChart chart6; + EXPECT(assert_equal(zero(3), chart6.local(R, R))); } /* ************************************************************************* */ // zero TEST(Manifold, _zero) { - EXPECT(assert_equal(Pose3(),traits::zero::value())); + EXPECT(assert_equal(Pose3(), traits::zero::value())); Cal3Bundler cal(0, 0, 0); - EXPECT(assert_equal(cal,traits::zero::value())); - EXPECT(assert_equal(Camera(Pose3(),cal),traits::zero::value())); + EXPECT(assert_equal(cal, traits::zero::value())); + EXPECT(assert_equal(Camera(Pose3(), cal), traits::zero::value())); } /* ************************************************************************* */ @@ -114,48 +115,48 @@ TEST(Manifold, _zero) { TEST(Manifold, Canonical) { Canonical chart1; - EXPECT(chart1.apply(Point2(1,0))==Vector2(1,0)); - EXPECT(chart1.retract(Vector2(1,0))==Point2(1,0)); + EXPECT(chart1.local(Point2(1, 0))==Vector2(1, 0)); + EXPECT(chart1.retract(Vector2(1, 0))==Point2(1, 0)); Vector v2(2); v2 << 1, 0; Canonical chart2; - EXPECT(assert_equal(v2,chart2.apply(Vector2(1,0)))); - EXPECT(chart2.retract(v2)==Vector2(1,0)); + EXPECT(assert_equal(v2, chart2.local(Vector2(1, 0)))); + EXPECT(chart2.retract(v2)==Vector2(1, 0)); Canonical chart3; Eigen::Matrix v1; v1 << 1; - EXPECT(chart3.apply(1)==v1); + EXPECT(chart3.local(1)==v1); EXPECT_DOUBLES_EQUAL(chart3.retract(v1), 1, 1e-9); Canonical chart4; Point3 point(1, 2, 3); Vector v3(3); v3 << 1, 2, 3; - EXPECT(assert_equal(v3,chart4.apply(point))); - EXPECT(assert_equal(chart4.retract(v3),point)); + EXPECT(assert_equal(v3, chart4.local(point))); + EXPECT(assert_equal(chart4.retract(v3), point)); Canonical chart5; Pose3 pose(Rot3::identity(), point); Vector v6(6); v6 << 0, 0, 0, 1, 2, 3; - EXPECT(assert_equal(v6,chart5.apply(pose))); - EXPECT(assert_equal(chart5.retract(v6),pose)); + EXPECT(assert_equal(v6, chart5.local(pose))); + EXPECT(assert_equal(chart5.retract(v6), pose)); Canonical chart6; Cal3Bundler cal0(0, 0, 0); Camera camera(Pose3(), cal0); Vector z9 = Vector9::Zero(); - EXPECT(assert_equal(z9,chart6.apply(camera))); - EXPECT(assert_equal(chart6.retract(z9),camera)); + EXPECT(assert_equal(z9, chart6.local(camera))); + EXPECT(assert_equal(chart6.retract(z9), camera)); Cal3Bundler cal; // Note !! Cal3Bundler() != zero::value() Camera camera2(pose, cal); Vector v9(9); v9 << 0, 0, 0, 1, 2, 3, 1, 0, 0; - EXPECT(assert_equal(v9,chart6.apply(camera2))); - EXPECT(assert_equal(chart6.retract(v9),camera2)); + EXPECT(assert_equal(v9, chart6.local(camera2))); + EXPECT(assert_equal(chart6.retract(v9), camera2)); } /* ************************************************************************* */