From a52591c65722feaa724c350836bce41f360967f7 Mon Sep 17 00:00:00 2001 From: HViktorTsoi Date: Wed, 8 Jun 2022 16:14:05 +0800 Subject: [PATCH] Move Rot3::quaternion to the deprecated block --- gtsam/geometry/Rot3.cpp | 4 +++- gtsam/geometry/Rot3.h | 7 ++++++- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/gtsam/geometry/Rot3.cpp b/gtsam/geometry/Rot3.cpp index 08213b065f..0ab41f2619 100644 --- a/gtsam/geometry/Rot3.cpp +++ b/gtsam/geometry/Rot3.cpp @@ -228,7 +228,8 @@ double Rot3::yaw(OptionalJacobian<1, 3> H) const { } /* ************************************************************************* */ -Vector Rot3::quaternion() const { +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 +Vector GTSAM_DEPRECATED Rot3::quaternion() const { gtsam::Quaternion q = toQuaternion(); Vector v(4); v(0) = q.w(); @@ -237,6 +238,7 @@ Vector Rot3::quaternion() const { v(3) = q.z(); return v; } +#endif /* ************************************************************************* */ pair Rot3::axisAngle() const { diff --git a/gtsam/geometry/Rot3.h b/gtsam/geometry/Rot3.h index 18bd88b52c..01ca7778c6 100644 --- a/gtsam/geometry/Rot3.h +++ b/gtsam/geometry/Rot3.h @@ -515,11 +515,16 @@ class GTSAM_EXPORT Rot3 : public LieGroup { */ gtsam::Quaternion toQuaternion() const; +#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42 /** * Converts to a generic matrix to allow for use with matlab * In format: w x y z + * @deprecated: use Rot3::toQuaternion() instead. + * If still using this API, remind that in the returned Vector `V`, + * `V.x()` denotes the actual `qw`, `V.y()` denotes 'qx', `V.z()` denotes `qy`, and `V.w()` denotes 'qz'. */ - Vector quaternion() const; + Vector GTSAM_DEPRECATED quaternion() const; +#endif /** * @brief Spherical Linear intERPolation between *this and other