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

Bump version and switch Pose3 expmap default #417

Merged
merged 2 commits into from
Jul 22, 2020

Conversation

ProfFan
Copy link
Collaborator

@ProfFan ProfFan commented Jul 21, 2020

This PR will:

  1. Bump version to 4.0.3
  2. Switch default Pose3 expmap to full, and Rot3 to full, for consistency.

@dellaert @varunagrawal

#412

@ProfFan ProfFan requested a review from dellaert July 21, 2020 22:16
@ProfFan
Copy link
Collaborator Author

ProfFan commented Jul 21, 2020

After this PR we will merge current develop to release/4.0.3.

@ProfFan
Copy link
Collaborator Author

ProfFan commented Jul 21, 2020

Also note that there will be one unit test failure in AdaptAutoDiff, which should be dealt with first before merging.

Copy link
Collaborator

@varunagrawal varunagrawal left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

LGTM

@dellaert
Copy link
Member

Also note that there will be one unit test failure in AdaptAutoDiff, which should be dealt with first before merging.

How/a add it to tracking issue... do you have a solution?

Copy link
Member

@dellaert dellaert left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Approved, but please explain, for the record, why the unit test had to be changed and why you think it’s correct.

@ProfFan
Copy link
Collaborator Author

ProfFan commented Jul 22, 2020

@dellaert Because the localCoordinates of a Camera is a the (6+3=9) dim vector <pose.local, cal.local>, so after the expmap change the local coordinate of the pose difference changed (P in code). Because P changed, the result of Snavely also changed, thus the #ifdefs are required and correct.

Proof:

>>> import gtsam as g
>>> import numpy as np
>>> p1=g.Pose3.Expmap(np.array([0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539]))
>>> r1=p1.rotation()
>>> g.Rot3.Logmap(r1)
array([0.1, 0.2, 0.3])
>>> t1=p1.translation()
>>> t1
[-1.99681e-11, 5, 2.22441e-12]'

Quote:

namespace example {
Camera camera(Pose3(Rot3().retract(Vector3(0.1, 0.2, 0.3)), Point3(0, 5, 0)),
              Cal3Bundler0(1, 0, 0));
Point3 point(10, 0, -5);  // negative Z-axis convention of Snavely!
Vector9 P = Camera().localCoordinates(camera);
Vector3 X = point;
#ifdef GTSAM_POSE3_EXPMAP
Vector2 expectedMeasurement(1.3124675, 1.2057287);
#else
Vector2 expectedMeasurement(1.2431567, 1.2525694);
#endif
Matrix E1 = numericalDerivative21<Vector2, Vector9, Vector3>(adapted, P, X);
Matrix E2 = numericalDerivative22<Vector2, Vector9, Vector3>(adapted, P, X);
}

/* ************************************************************************* */
// Check that Local worked as expected
TEST(AdaptAutoDiff, Local) {
  using namespace example;
#ifdef GTSAM_POSE3_EXPMAP
  Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0.7583528428, 4.9582357859, -0.224941471539, 1, 0, 0).finished();
#else
  Vector9 expectedP = (Vector9() << 0.1, 0.2, 0.3, 0, 5, 0, 1, 0, 0).finished();
#endif
  EXPECT(equal_with_abs_tol(expectedP, P));
  Vector3 expectedX(10, 0, -5);  // negative Z-axis convention of Snavely!
  EXPECT(equal_with_abs_tol(expectedX, X));
}

@ProfFan ProfFan merged commit 905be41 into develop Jul 22, 2020
@ProfFan
Copy link
Collaborator Author

ProfFan commented Jul 22, 2020

Since there is no objection, I will merge this and checkout 4.0.3 release :)

@ProfFan ProfFan deleted the feature/new_expmap_default branch July 22, 2020 16:19
@dellaert
Copy link
Member

Since there is no objection, I will merge this and checkout 4.0.3 release :)

By "checkout" you mean merge in develop and release it?

@ProfFan
Copy link
Collaborator Author

ProfFan commented Jul 22, 2020

@dellaert Yes

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

Successfully merging this pull request may close these issues.

3 participants