Merge pull request #1219 from HViktorTsoi/develop

release/4.3a0
Varun Agrawal 2022-06-09 20:14:37 -04:00 committed by GitHub
commit 08aed0b946
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
4 changed files with 12 additions and 5 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

View File

@ -355,7 +355,7 @@ class Rot3 {
double yaw() const; double yaw() const;
pair<gtsam::Unit3, double> axisAngle() const; pair<gtsam::Unit3, double> axisAngle() const;
gtsam::Quaternion toQuaternion() const; gtsam::Quaternion toQuaternion() const;
Vector quaternion() const; // Vector quaternion() const; // @deprecated, see https://github.com/borglab/gtsam/pull/1219
gtsam::Rot3 slerp(double t, const gtsam::Rot3& other) const; gtsam::Rot3 slerp(double t, const gtsam::Rot3& other) const;
// enabling serialization functionality // enabling serialization functionality

View File

@ -79,9 +79,9 @@ void saveG2oResult(string name, const Values& values, std::map<Key, Pose3> poses
myfile << "VERTEX_SE3:QUAT" << " "; myfile << "VERTEX_SE3:QUAT" << " ";
myfile << i << " "; myfile << i << " ";
myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " "; myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " ";
Vector quaternion = Rot3(R).quaternion(); Quaternion quaternion = Rot3(R).toQuaternion();
myfile << quaternion(3) << " " << quaternion(2) << " " << quaternion(1) myfile << quaternion.x() << " " << quaternion.y() << " " << quaternion.z()
<< " " << quaternion(0); << " " << quaternion.w();
myfile << "\n"; myfile << "\n";
} }
myfile.close(); myfile.close();