From 92e575f8c134e2fc3ed618c7613a0a0f3161cc61 Mon Sep 17 00:00:00 2001 From: Richard Roberts Date: Sat, 11 Aug 2012 02:53:56 +0000 Subject: [PATCH] Wrapped LieScalar --- gtsam.h | 35 ++++++++++++++++++++++++++++++++--- 1 file changed, 32 insertions(+), 3 deletions(-) diff --git a/gtsam.h b/gtsam.h index 14e3d175f..fd36a28c0 100644 --- a/gtsam.h +++ b/gtsam.h @@ -101,6 +101,35 @@ virtual class Value { size_t dim() const; }; +#include +virtual class LieScalar : gtsam::Value { + // Standard constructors + LieScalar(); + LieScalar(double d); + + // Standard interface + double value() const; + + // Testable + void print(string s) const; + bool equals(const gtsam::LieScalar& expected, double tol) const; + + // Group + static gtsam::LieScalar identity(); + gtsam::LieScalar inverse() const; + gtsam::LieScalar compose(const gtsam::LieScalar& p) const; + gtsam::LieScalar between(const gtsam::LieScalar& l2) const; + + // Manifold + size_t dim() const; + gtsam::LieScalar retract(Vector v) const; + Vector localCoordinates(const gtsam::LieScalar& t2) const; + + // Lie group + static gtsam::LieScalar Expmap(Vector v); + static Vector Logmap(const gtsam::LieScalar& p); +}; + #include virtual class LieVector : gtsam::Value { // Standard constructors @@ -1451,21 +1480,21 @@ class NonlinearISAM { #include #include -template +template virtual class PriorFactor : gtsam::NonlinearFactor { PriorFactor(size_t key, const T& prior, const gtsam::noiseModel::Base* noiseModel); }; #include -template +template virtual class BetweenFactor : gtsam::NonlinearFactor { BetweenFactor(size_t key1, size_t key2, const T& relativePose, const gtsam::noiseModel::Base* noiseModel); }; #include -template +template virtual class NonlinearEquality : gtsam::NonlinearFactor { // Constructor - forces exact evaluation NonlinearEquality(size_t j, const T& feasible);