diff --git a/gtsam/gtsam.i b/gtsam/gtsam.i index 52f5901ee..d8297c43b 100644 --- a/gtsam/gtsam.i +++ b/gtsam/gtsam.i @@ -390,6 +390,7 @@ class LieVector { // Lie group static gtsam::LieVector Expmap(Vector v); static Vector Logmap(const gtsam::LieVector& p); + Vector logmap(const gtsam::LieVector& p); // enabling serialization functionality void serialize() const; @@ -422,6 +423,7 @@ class LieMatrix { // Lie group static gtsam::LieMatrix Expmap(Vector v); static Vector Logmap(const gtsam::LieMatrix& p); + Vector logmap(const gtsam::LieMatrix& p); // enabling serialization functionality void serialize() const; @@ -567,6 +569,7 @@ class Rot2 { // Lie Group static gtsam::Rot2 Expmap(Vector v); static Vector Logmap(const gtsam::Rot2& p); + Vector logmap(const gtsam::Rot2& p); // Group Action on Point2 gtsam::Point2 rotate(const gtsam::Point2& point) const; @@ -727,6 +730,7 @@ class Rot3 { // Standard Interface static gtsam::Rot3 Expmap(Vector v); static Vector Logmap(const gtsam::Rot3& p); + Vector logmap(const gtsam::Rot3& p); Matrix matrix() const; Matrix transpose() const; gtsam::Point3 column(size_t index) const; @@ -772,6 +776,7 @@ class Pose2 { // Lie Group static gtsam::Pose2 Expmap(Vector v); static Vector Logmap(const gtsam::Pose2& p); + Vector logmap(const gtsam::Pose2& p); static Matrix ExpmapDerivative(Vector v); static Matrix LogmapDerivative(const gtsam::Pose2& v); Matrix AdjointMap() const; @@ -825,6 +830,7 @@ class Pose3 { // Lie Group static gtsam::Pose3 Expmap(Vector v); static Vector Logmap(const gtsam::Pose3& pose); + Vector logmap(const gtsam::Pose3& pose); Matrix AdjointMap() const; Vector Adjoint(Vector xi) const; static Matrix adjointMap_(Vector xi);