RonaldSun / VI-Stereo-DSO

Direct sparse odometry combined with stereo cameras and IMU
387 stars 124 forks source link

You have mixed different SE3 Jacobian types #30

Open tanjunyao7 opened 4 years ago

tanjunyao7 commented 4 years ago

DSO evaluates the Jacobian of the photometric error with left Jacobian of SE3. The update step of poses is also done in the left-multiplication way. However, your jacobians of IMU residuals, which probably originates from https://github.com/jingpang/LearnVIORB, adopt right Jacobian. I just wonder why the optimization still converges.

studennis911988 commented 4 years ago

The author derived the right to left Jacobian, which is also mentioned in issue28. However, I have no idea how he derived that.

tanjunyao7 commented 4 years ago

The author derived the right to left Jacobian, which is also mentioned in issue28. However, I have no idea how he derived that.

OK, I see. I havn't read through the code before. The deriviation may be formulated as follows: _exp(d_xi_l) T = T exp(d_xir) _exp(d_xi_l) = T exp(d_xi_r) T^(-1) = exp(Adj(T) d_xir) _d_xi_l = Adj(T) d_xir

studennis911988 commented 4 years ago

@tanjunyao7 Your derivation really makes sense, thanks a lot!