From e4b29b8d8b3df977f4734621b8b1e621999c9bd5 Mon Sep 17 00:00:00 2001 From: Duy-Nguyen Ta Date: Tue, 30 Apr 2013 17:15:42 +0000 Subject: [PATCH] move print function to cpp file for LieVector to solve the "same-name-different-type" problem in matlab wrapper. --- gtsam/base/LieVector.cpp | 19 ++++++++++++------- gtsam/base/LieVector.h | 26 ++++++++++++-------------- 2 files changed, 24 insertions(+), 21 deletions(-) diff --git a/gtsam/base/LieVector.cpp b/gtsam/base/LieVector.cpp index d5ae5d504..17aeff73a 100644 --- a/gtsam/base/LieVector.cpp +++ b/gtsam/base/LieVector.cpp @@ -32,13 +32,18 @@ LieVector::LieVector(size_t m, const double* const data) LieVector::LieVector(size_t m, ...) : Vector(m) { - va_list ap; - va_start(ap, m); - for( size_t i = 0 ; i < m ; i++) { - double value = va_arg(ap, double); - (*this)(i) = value; - } - va_end(ap); + va_list ap; + va_start(ap, m); + for( size_t i = 0 ; i < m ; i++) { + double value = va_arg(ap, double); + (*this)(i) = value; + } + va_end(ap); +} + +/* ************************************************************************* */ +void LieVector::print(const std::string& name) const { + gtsam::print(vector(), name); } } // \namespace gtsam diff --git a/gtsam/base/LieVector.h b/gtsam/base/LieVector.h index 5f31b0df4..3bb0ffd39 100644 --- a/gtsam/base/LieVector.h +++ b/gtsam/base/LieVector.h @@ -48,35 +48,33 @@ struct LieVector : public Vector, public DerivedValue { GTSAM_EXPORT LieVector(size_t m, ...); /** get the underlying vector */ - inline Vector vector() const { + Vector vector() const { return static_cast(*this); } /** print @param name optional string naming the object */ - inline void print(const std::string& name="") const { - gtsam::print(vector(), name); - } + void print(const std::string& name="") const; /** equality up to tolerance */ - inline bool equals(const LieVector& expected, double tol=1e-5) const { + bool equals(const LieVector& expected, double tol=1e-5) const { return gtsam::equal(vector(), expected.vector(), tol); } // Manifold requirements /** Returns dimensionality of the tangent space */ - inline size_t dim() const { return this->size(); } + size_t dim() const { return this->size(); } /** Update the LieVector with a tangent space update */ - inline LieVector retract(const Vector& v) const { return LieVector(vector() + v); } + LieVector retract(const Vector& v) const { return LieVector(vector() + v); } /** @return the local coordinates of another object */ - inline Vector localCoordinates(const LieVector& t2) const { return LieVector(t2 - vector()); } + Vector localCoordinates(const LieVector& t2) const { return LieVector(t2 - vector()); } // Group requirements /** identity - NOTE: no known size at compile time - so zero length */ - inline static LieVector identity() { + static LieVector identity() { throw std::runtime_error("LieVector::identity(): Don't use this function"); return LieVector(); } @@ -86,7 +84,7 @@ struct LieVector : public Vector, public DerivedValue { // instead of the gtsam::Matrix class. This is related to deriving this class from an Eigen Vector // as the other geometry objects (Point3, Rot3, etc.) have this problem /** compose with another object */ - inline LieVector compose(const LieVector& p, + LieVector compose(const LieVector& p, boost::optional H1=boost::none, boost::optional H2=boost::none) const { if(H1) *H1 = eye(dim()); @@ -96,7 +94,7 @@ struct LieVector : public Vector, public DerivedValue { } /** between operation */ - inline LieVector between(const LieVector& l2, + LieVector between(const LieVector& l2, boost::optional H1=boost::none, boost::optional H2=boost::none) const { if(H1) *H1 = -eye(dim()); @@ -105,7 +103,7 @@ struct LieVector : public Vector, public DerivedValue { } /** invert the object and yield a new one */ - inline LieVector inverse(boost::optional H=boost::none) const { + LieVector inverse(boost::optional H=boost::none) const { if(H) *H = -eye(dim()); return LieVector(-1.0 * vector()); @@ -114,10 +112,10 @@ struct LieVector : public Vector, public DerivedValue { // Lie functions /** Expmap around identity */ - static inline LieVector Expmap(const Vector& v) { return LieVector(v); } + static LieVector Expmap(const Vector& v) { return LieVector(v); } /** Logmap around identity - just returns with default cast back */ - static inline Vector Logmap(const LieVector& p) { return p; } + static Vector Logmap(const LieVector& p) { return p; } private: