minwoo0611 / MA-LIO

Asynchronous Multiple LiDAR-Inertial Odometry using Point-wise Inter-LiDAR Uncertainty Propagation
GNU General Public License v2.0
287 stars 36 forks source link

Question about the "compoundPoseWithCov" #24

Closed gunheeShin closed 3 months ago

gunheeShin commented 3 months ago

Hello! @minwoo0611 Thanks for the great work.

I'm currently trying to understand the propagating uncertainty through a compounding of two transformation matrices.

I refer "Associating Uncertainty With Three-Dimensional Poses for Use in Estimation Problems" this paper as a guide to grasp the compoundPoseWithCov function in your code.

However, I've noticed some discrepancies between your code and the equation (55) presented in the paper. Here are a few questions i hope you could clarify:

  1. This is the flow how i understand your code. image Could you explain how the final uncertainty equation in your code is derived? image

  2. Regarding to the compoundInvPoseWithCov function, could you share the reason why you set cov_1_prime like this way? image

Thanks for the advices!

minwoo0611 commented 3 months ago

Dear @gunheeShin

Thank you for reaching out and for your kind words regarding our work. It's always encouraging to see engagement with our code and research!

Regarding your inquiry about the discrepancies between the code and Equation (55) from the paper "Associating Uncertainty With Three-Dimensional Poses for Use in Estimation Problems," you've brought up an important point. The derivation of the final uncertainty equation in our code should indeed mirror the approach outlined in the paper, where the compounded pose uncertainty takes into account the covariance of each pose and their respective transformations.

(1) Upon reviewing your query and our code, it appears there was a typographical error in our implementation of the covariance calculation. Specifically, the equation should be represented as:

cov_cp = cov_1_prime + cov_2 + (A1 cov_2 + cov_2 A1.transpose() + A2 cov_1_prime + cov_1_prime A2.transpose()) /12 + B/4

This corrects the approach to be in alignment with Equation (55) from the paper and ensures that the compounded uncertainty accurately reflects the transformations applied to each pose. It should calculate samely in the compoundInvPoseWithCov function.

I truly appreciate you pointing out these discrepancies and are committed to correcting them promptly. We will update the code to reflect these corrections and clarify the methodology used. Should you wish, I welcome any pull requests on this matter, as community contributions greatly enhance the quality and accuracy of the project.

(2) For your second question about calculating covariance using adjoint matrix, I attach the equations as below.

20240328_005736.jpg

I hope this image can help you understand. Also, sorry for the bad handwriting :)

Again, thank you for your detailed analysis and for contributing to the improvement of our work. Your engagement is invaluable to us.

Best regards, Minwoo

gunheeShin commented 3 months ago

Dear @minwoo0611, Thank you for your prompt and detailed reply!

Regarding question 1, I'm truly grateful to be able to contribute to your code. I will request the pull on this matter promptly.

And for the question 2, I have clearly understood the points I was curious about.

Thank you again for your response.