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

Endow NavState with group operations #1930

Merged
merged 7 commits into from
Dec 15, 2024
Merged

Conversation

dellaert
Copy link
Member

@dellaert dellaert commented Dec 14, 2024

This is a smaller PR than #1613 that adds $SE_2(3)$ group operations to NavState. Be careful though: we use R,t,v order.
A lot of this code is written by @varunagrawal and possibly @ProfFan.

This PR:

  • Takes all unit-tested changes from Add Lie group capabilities to NavState #1613 except transposes and todos
  • Adds ExpmapTranslation to Pose3, whose derivative with respect to angular velocity is exactly Q
  • Uses that in both Pose3::Expmap and NavState::Expmap

ExpmapTranslation avoids code duplication and clearly exposes the structure of the exponential map Jacobian. NavState::Expmap is also faster because we don't create the 3x3 W matrices unless the derivative is asked for.

Copy link
Collaborator

@ProfFan ProfFan left a comment

Choose a reason for hiding this comment

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

Approving sans some comments. I verified most equations against my notes but I haven't verified formally the adjoint's Jacobians, no bandwidth for that.

I am still very concerned about the use of epsilon around the repository. I fixed (while leaving some side effects unsolved) Rot3 in #780, and I am pretty sure there could be more. But this is not super related to this PR, so we can always check later.

0.5 * ((1 - phi2 / 2 - c) / phi4 - 3 * (phi - s - phi3 / 6.) / phi5) *
(WVW * W + W * WVW);

// TODO(Frank): this threshold is *different*. Why?
Copy link
Collaborator

Choose a reason for hiding this comment

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

The following is probably not correct, refer to #780. Have no bandwidth to look into this more carefully.

Copy link
Member Author

Choose a reason for hiding this comment

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

You're right! And epsilon hides it: we never use it, actually :-) So, I removed epsilon, use same threshold in both cases, and corrected as

v + 0.5 * w.cross(v)

gtsam/navigation/NavState.cpp Outdated Show resolved Hide resolved
gtsam/navigation/tests/testNavState.cpp Outdated Show resolved Hide resolved
EXPECT(assert_equal(t2, t1.retract(d12)));
Vector d21 = t2.localCoordinates(t1);
EXPECT(assert_equal(t1, t2.retract(d21)));
// EXPECT(assert_equal(d12, -d21));
Copy link
Collaborator

Choose a reason for hiding this comment

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

Check

Copy link
Member Author

Choose a reason for hiding this comment

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

Not expected for retractions

gtsam/navigation/tests/testNavState.cpp Outdated Show resolved Hide resolved
@dellaert dellaert merged commit bb7b6b3 into develop Dec 15, 2024
33 checks passed
@dellaert dellaert deleted the feature/NavStateGroup branch December 15, 2024 18:24
dellaert added a commit that referenced this pull request Dec 16, 2024
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.

2 participants