Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Possible quaternion conversion bug #1588

Closed
WZG3661 opened this issue Jul 22, 2023 · 3 comments
Closed

Possible quaternion conversion bug #1588

WZG3661 opened this issue Jul 22, 2023 · 3 comments

Comments

@WZG3661
Copy link

WZG3661 commented Jul 22, 2023

#include <iostream>

#include <Eigen/Eigen>
#include <gtsam/geometry/Pose3.h>

int main() {
  Eigen::Quaterniond quat;
  quat.w() = 1.0;
  quat.x() = 2.0;
  quat.y() = 3.0;
  quat.z() = 4.0;
  std::cout << "Eigen:" << std::endl;
  std::cout << "w " << quat.w() << std::endl;
  std::cout << "x " << quat.x() << std::endl;
  std::cout << "y " << quat.y() << std::endl;
  std::cout << "z " << quat.z() << std::endl;

  gtsam::Pose3 pose(gtsam::Rot3(quat), gtsam::Vector3(0, 0, 0));
  std::cout << "GTSAM:" << std::endl;
  std::cout << "w " << pose.rotation().quaternion().w() << std::endl;
  std::cout << "x " << pose.rotation().quaternion().x() << std::endl;
  std::cout << "y " << pose.rotation().quaternion().y() << std::endl;
  std::cout << "z " << pose.rotation().quaternion().z() << std::endl;

  return 0;
}

the output is:

Eigen:
w 1
x 2
y 3
z 4
GTSAM:
w 4
x 1
y 2
z 3
@dellaert
Copy link
Member

Hi anonymous,
I’ll look into whether this is a real bug - in which case it’s embarrassing, for sure.
But I’d request to be respectful in reporting it and even help us pinpoint the bug.
Best
Frank Dellaert

@dellaert dellaert changed the title Are you kidding me? Possible quaternion conversion bug Jul 22, 2023
@dellaert
Copy link
Member

This was discussed at length in #1219
Since version 4.2a8 the method .quaternion() is deprecated (and even removed in develop, pre 4.3), in favor of toQuaternion. In develop this test succeeds:

TEST(Rot3, ConvertQuaternion) {
  Eigen::Quaterniond eigenQuaternion;
  eigenQuaternion.w() = 1.0;
  eigenQuaternion.x() = 2.0;
  eigenQuaternion.y() = 3.0;
  eigenQuaternion.z() = 4.0;
  EXPECT_DOUBLES_EQUAL(1, eigenQuaternion.w(), 1e-9);
  EXPECT_DOUBLES_EQUAL(2, eigenQuaternion.x(), 1e-9);
  EXPECT_DOUBLES_EQUAL(3, eigenQuaternion.y(), 1e-9);
  EXPECT_DOUBLES_EQUAL(4, eigenQuaternion.z(), 1e-9);

  Rot3 R(eigenQuaternion);
  EXPECT_DOUBLES_EQUAL(1, R.toQuaternion().w(), 1e-9);
  EXPECT_DOUBLES_EQUAL(2, R.toQuaternion().x(), 1e-9);
  EXPECT_DOUBLES_EQUAL(3, R.toQuaternion().y(), 1e-9);
  EXPECT_DOUBLES_EQUAL(4, R.toQuaternion().z(), 1e-9);
}

I'll add a PR with it.

@WZG3661
Copy link
Author

WZG3661 commented Jul 22, 2023

Sorry for my inappropriate wording. Thanks for your answer!

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
None yet
Development

No branches or pull requests

2 participants