Skip to content

Commit

Permalink
Merge pull request #1219 from HViktorTsoi/develop
Browse files Browse the repository at this point in the history
  • Loading branch information
varunagrawal committed Jun 10, 2022
2 parents 9a1eb02 + 5ac71d2 commit 08aed0b
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 5 deletions.
2 changes: 2 additions & 0 deletions gtsam/geometry/Rot3.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -228,6 +228,7 @@ double Rot3::yaw(OptionalJacobian<1, 3> H) const {
}

/* ************************************************************************* */
#ifdef GTSAM_ALLOW_DEPRECATED_SINCE_V42
Vector Rot3::quaternion() const {
gtsam::Quaternion q = toQuaternion();
Vector v(4);
Expand All @@ -237,6 +238,7 @@ Vector Rot3::quaternion() const {
v(3) = q.z();
return v;
}
#endif

/* ************************************************************************* */
pair<Unit3, double> Rot3::axisAngle() const {
Expand Down
7 changes: 6 additions & 1 deletion gtsam/geometry/Rot3.h
Original file line number Diff line number Diff line change
Expand Up @@ -515,11 +515,16 @@ class GTSAM_EXPORT Rot3 : public LieGroup<Rot3, 3> {
*/
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
Expand Down
2 changes: 1 addition & 1 deletion gtsam/geometry/geometry.i
Original file line number Diff line number Diff line change
Expand Up @@ -355,7 +355,7 @@ class Rot3 {
double yaw() const;
pair<gtsam::Unit3, double> axisAngle() 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;

// enabling serialization functionality
Expand Down
6 changes: 3 additions & 3 deletions gtsam_unstable/timing/timeShonanAveraging.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -79,9 +79,9 @@ void saveG2oResult(string name, const Values& values, std::map<Key, Pose3> poses
myfile << "VERTEX_SE3:QUAT" << " ";
myfile << i << " ";
myfile << poses[i].x() << " " << poses[i].y() << " " << poses[i].z() << " ";
Vector quaternion = Rot3(R).quaternion();
myfile << quaternion(3) << " " << quaternion(2) << " " << quaternion(1)
<< " " << quaternion(0);
Quaternion quaternion = Rot3(R).toQuaternion();
myfile << quaternion.x() << " " << quaternion.y() << " " << quaternion.z()
<< " " << quaternion.w();
myfile << "\n";
}
myfile.close();
Expand Down

0 comments on commit 08aed0b

Please sign in to comment.