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

some question about code and paper difference in LsqBundleAdjustmentFactor #30

Open
gyarnet opened this issue Oct 29, 2024 · 4 comments

Comments

@gyarnet
Copy link

gyarnet commented Oct 29, 2024

the jacobi in line 171 is wrong, but if i correct it, the optimization is worse.

    gtsam::Matrix36 H2_;
    H2_.block<3, 3>(0, 0) = R_k * -gtsam::SO3::Hat(mean_k);
    H2_.block<3, 3>(0, 3) = R_k * gtsam::Matrix3::Identity();

Screenshot from 2024-10-29 15-55-19

@koide3
Copy link
Owner

koide3 commented Oct 29, 2024

How did you correct it?

@gyarnet
Copy link
Author

gyarnet commented Oct 29, 2024

How did you correct it?

remove the R_k in the 171 line

@koide3
Copy link
Owner

koide3 commented Oct 30, 2024

I think the implementation is correct. You can confirm the SE3 derivatives by seeing the GTSAM code: https://github.com/borglab/gtsam/blob/d48b1fc8402e28d5b6af8f59cce8dbe87e66cf0c/gtsam/geometry/Pose3.cpp#L353.

@gyarnet
Copy link
Author

gyarnet commented Oct 30, 2024

thanks for your answer, I mistakenly take the gtsam::Pose3 as SO(3) + R3 instead of SE(3). I learn a lot from your code.

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