Move Rot3::quaternion to the deprecated block

release/4.3a0
HViktorTsoi 2022-06-08 16:30:10 +08:00
parent 9a1eb022a9
commit f911ccf176
2 changed files with 8 additions and 1 deletions

View File

@ -228,6 +228,7 @@ double Rot3::yaw(OptionalJacobian<1, 3> H) const {
} }
/* ************************************************************************* */ /* ************************************************************************* */
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
Vector Rot3::quaternion() const { Vector Rot3::quaternion() const {
gtsam::Quaternion q = toQuaternion(); gtsam::Quaternion q = toQuaternion();
Vector v(4); Vector v(4);
@ -237,6 +238,7 @@ Vector Rot3::quaternion() const {
v(3) = q.z(); v(3) = q.z();
return v; return v;
} }
#endif
/* ************************************************************************* */ /* ************************************************************************* */
pair<Unit3, double> Rot3::axisAngle() const { pair<Unit3, double> Rot3::axisAngle() const {

View File

@ -515,11 +515,16 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
*/ */
gtsam::Quaternion toQuaternion() const; gtsam::Quaternion toQuaternion() const;
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
/** /**
* Converts to a generic matrix to allow for use with matlab * Converts to a generic matrix to allow for use with matlab
* In format: w x y z * 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 * @brief Spherical Linear intERPolation between *this and other