rpng / open_vins

An open source platform for visual-inertial navigation research.
https://docs.openvins.com
GNU General Public License v3.0
2.13k stars 630 forks source link

Clarification on IMU propagation #247

Closed mhuzai closed 2 years ago

mhuzai commented 2 years ago

Hello,

I'm trying to understand the IMU propagator and going through Propagator.cpp. This comment and this comment are exactly the same but the code that follows each is quite different. Could you clarify which method is doing what?

Additionally, this formula is the same as this one, but the one used here is different. Why is that, and which one should be used for extrapolating the pose into the future?

Thank you!

goldbattle commented 2 years ago

To your first question, the fast propagation is just a copy-pasted code of the normal propagation since the existing code will modify the state estimate which is undesirable since for fast propagate we just want to take whatever the most recent state estimate is and predict what the pose is at the IMU rate quickly.

As for you second question, make sure you note that one is a quaternion and the other is SO(3). These are different matrix exponentials exp() that are in use here. They should be approximately equivalent to each other and interchangeable. These are found through integrating (in respect to time) the derivative of the quaternion or the rotation matrix. For example we walk through how to do this quaternion integration on the docs: image


This can also be performed for the SO(3) matrix (Joan Sol`a report has some details too). Note that we have a negative, which is the same as a rotation transpose image


You can try for yourself if there is a different by comment this line in and comparing the two predicted values: https://github.com/rpng/open_vins/blob/d84a51c2b914b5739ed6eaff30eb74e7d6a687a3/ov_msckf/src/state/Propagator.cpp#L463-L471