Added deprecated methods back in for MATLAB toolbox
parent
ee4dbfec4b
commit
eb5d619729
|
@ -31,7 +31,7 @@
|
|||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* @deprecated: LieScalar, LieVector and LieMatrix are obsolete in GTSAM 4.0 as
|
||||
* @deprecated: LieMatrix, LieVector and LieMatrix are obsolete in GTSAM 4.0 as
|
||||
* we can directly add double, Vector, and Matrix into values now, because of
|
||||
* gtsam::traits.
|
||||
*/
|
||||
|
@ -83,6 +83,26 @@ struct LieMatrix : public Matrix {
|
|||
}
|
||||
|
||||
/// @}
|
||||
|
||||
/// @name Group
|
||||
/// @{
|
||||
LieMatrix compose(const LieMatrix& q) { return (*this)+q;}
|
||||
LieMatrix between(const LieMatrix& q) { return q-(*this);}
|
||||
LieMatrix inverse() { return -(*this);}
|
||||
/// @}
|
||||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
Vector localCoordinates(const LieMatrix& q) { return between(q).vector();}
|
||||
LieMatrix retract(const Vector& v) {return compose(LieMatrix(v));}
|
||||
/// @}
|
||||
|
||||
/// @name Lie Group
|
||||
/// @{
|
||||
static Vector Logmap(const LieMatrix& p) {return p.vector();}
|
||||
static LieMatrix Expmap(const Vector& v) { return LieMatrix(v);}
|
||||
/// @}
|
||||
|
||||
/// @name VectorSpace requirements
|
||||
/// @{
|
||||
|
||||
|
|
|
@ -49,17 +49,36 @@ namespace gtsam {
|
|||
/** Automatic conversion to underlying value */
|
||||
operator double() const { return d_; }
|
||||
|
||||
/** convert vector */
|
||||
Vector1 vector() const { Vector1 v; v<<d_; return v; }
|
||||
|
||||
/// @name Testable
|
||||
/// @{
|
||||
|
||||
/** print @param name optional string naming the object */
|
||||
void print(const std::string& name="") const;
|
||||
|
||||
/** equality up to tolerance */
|
||||
bool equals(const LieScalar& expected, double tol=1e-5) const {
|
||||
return fabs(expected.d_ - d_) <= tol;
|
||||
}
|
||||
/// @}
|
||||
|
||||
/// @name Group
|
||||
/// @{
|
||||
static LieScalar identity() { return LieScalar(0);}
|
||||
LieScalar compose(const LieScalar& q) { return (*this)+q;}
|
||||
LieScalar between(const LieScalar& q) { return q-(*this);}
|
||||
LieScalar inverse() { return -(*this);}
|
||||
/// @}
|
||||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
size_t dim() const { return 1; }
|
||||
Vector1 localCoordinates(const LieScalar& q) { return between(q).vector();}
|
||||
LieScalar retract(const Vector1& v) {return compose(LieScalar(v[0]));}
|
||||
/// @}
|
||||
|
||||
/// @name Lie Group
|
||||
/// @{
|
||||
static Vector1 Logmap(const LieScalar& p) { return p.vector();}
|
||||
static LieScalar Expmap(const Vector1& v) { return LieScalar(v[0]);}
|
||||
/// @}
|
||||
|
||||
private:
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
namespace gtsam {
|
||||
|
||||
/**
|
||||
* @deprecated: LieScalar, LieVector and LieMatrix are obsolete in GTSAM 4.0 as
|
||||
* @deprecated: LieVector, LieVector and LieMatrix are obsolete in GTSAM 4.0 as
|
||||
* we can directly add double, Vector, and Matrix into values now, because of
|
||||
* gtsam::traits.
|
||||
*/
|
||||
|
@ -60,16 +60,31 @@ struct LieVector : public Vector {
|
|||
|
||||
/// @name Testable
|
||||
/// @{
|
||||
|
||||
/** print @param name optional string naming the object */
|
||||
GTSAM_EXPORT void print(const std::string& name="") const;
|
||||
|
||||
/** equality up to tolerance */
|
||||
bool equals(const LieVector& expected, double tol=1e-5) const {
|
||||
return gtsam::equal(vector(), expected.vector(), tol);
|
||||
}
|
||||
|
||||
/// @}
|
||||
|
||||
/// @name Group
|
||||
/// @{
|
||||
LieVector compose(const LieVector& q) { return (*this)+q;}
|
||||
LieVector between(const LieVector& q) { return q-(*this);}
|
||||
LieVector inverse() { return -(*this);}
|
||||
/// @}
|
||||
|
||||
/// @name Manifold
|
||||
/// @{
|
||||
Vector localCoordinates(const LieVector& q) { return between(q).vector();}
|
||||
LieVector retract(const Vector& v) {return compose(LieVector(v));}
|
||||
/// @}
|
||||
|
||||
/// @name Lie Group
|
||||
/// @{
|
||||
static Vector Logmap(const LieVector& p) {return p.vector();}
|
||||
static LieVector Expmap(const Vector& v) { return LieVector(v);}
|
||||
/// @}
|
||||
|
||||
/// @name VectorSpace requirements
|
||||
/// @{
|
||||
|
||||
|
|
|
@ -160,10 +160,18 @@ public:
|
|||
Vector2 vector() const { return Vector2(x_, y_); }
|
||||
|
||||
/// @}
|
||||
/// @name Deprecated (non-const, non-functional style. Do not use).
|
||||
|
||||
/// @name Deprecated
|
||||
/// @{
|
||||
inline void operator += (const Point2& q) {x_+=q.x_;y_+=q.y_;}
|
||||
inline void operator *= (double s) {x_*=s;y_*=s;}
|
||||
Point2 inverse() { return -(*this);}
|
||||
Point2 compose(const Point2& q) { return (*this)+q;}
|
||||
Point2 between(const Point2& q) { return q-(*this);}
|
||||
Vector2 localCoordinates(const Point2& q) { return between(q).vector();}
|
||||
Point2 retract(const Vector2& v) {return compose(Point2(v));}
|
||||
static Vector2 Logmap(const Point2& p) {return p.vector();}
|
||||
static Point2 Expmap(const Vector2& v) { return Point2(v);}
|
||||
/// @}
|
||||
|
||||
/// Streaming
|
||||
|
|
|
@ -162,6 +162,17 @@ namespace gtsam {
|
|||
/// Output stream operator
|
||||
GTSAM_EXPORT friend std::ostream &operator<<(std::ostream &os, const Point3& p);
|
||||
|
||||
/// @name Deprecated
|
||||
/// @{
|
||||
Point3 inverse() { return -(*this);}
|
||||
Point3 compose(const Point3& q) { return (*this)+q;}
|
||||
Point3 between(const Point3& q) { return q-(*this);}
|
||||
Vector3 localCoordinates(const Point3& q) { return between(q).vector();}
|
||||
Point3 retract(const Vector3& v) {return compose(Point3(v));}
|
||||
static Vector3 Logmap(const Point3& p) {return p.vector();}
|
||||
static Point3 Expmap(const Vector3& v) { return Point3(v);}
|
||||
/// @}
|
||||
|
||||
private:
|
||||
|
||||
/// @name Advanced Interface
|
||||
|
|
|
@ -159,6 +159,17 @@ namespace imuBias {
|
|||
|
||||
/// @}
|
||||
|
||||
/// @name Deprecated
|
||||
/// @{
|
||||
ConstantBias inverse() { return -(*this);}
|
||||
ConstantBias compose(const ConstantBias& q) { return (*this)+q;}
|
||||
ConstantBias between(const ConstantBias& q) { return q-(*this);}
|
||||
Vector6 localCoordinates(const ConstantBias& q) { return between(q).vector();}
|
||||
ConstantBias retract(const Vector6& v) {return compose(ConstantBias(v));}
|
||||
static Vector6 Logmap(const ConstantBias& p) {return p.vector();}
|
||||
static ConstantBias Expmap(const Vector6& v) { return ConstantBias(v);}
|
||||
/// @}
|
||||
|
||||
private:
|
||||
|
||||
/// @name Advanced Interface
|
||||
|
|
Loading…
Reference in New Issue