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

Confusion regarding IMU Orientation Error Propagation #251

Closed mateicodrul closed 2 years ago

mateicodrul commented 2 years ago

Hello,

I have some questions regarding the orientation error propagation in discrete time for the IMU. In the documentation, you write the following:

imu_1

My first question concerns the line:

imu_2

Why do we write the rotation from I{k} to I{k+1} as an exponential instead of using the small angle approximation, as we do for the rotation from G to I_{k}? Is writing this exponential (and later expressing it using the right Jacobian) simply a better approximation and that is why we do it?

Secondly, on the next line

imu_3

we separate the exponential and use the right Jacobian, but is the separation correct? Shouldn't the order in which we write the 2 exponentials be reversed, since we use the global-to-local rotation convention (as we actually state on the very first line in the first picture)? It seems to me that the effect the right Jacobian has must be expressed in frame I{k+1}. That means, it must be applied to the left of the mean rotation from I{k} to I_{k+1}, not to the right.

Thank you very much in advance!

Edit: Additionally, perhaps you would be so kind as to clarify the meaning of the vector theta. Is the associated angle defined from the frame at the bottom index to the frame at the top index (e.g.: from G to I, in the first line of the first picture), or the other way around? If the bottom to top convention is used (which was my guess), then it seems to me you forgot one minus in the argument of J_r in the following:

imu_5

because the original argument of J_r in the previous equation had a negative sign (please see below)

imu_4

goldbattle commented 2 years ago

Sorry for not responding, as I was at a conference. I can formulate a more detail response when I find time, but I think I can point you towards the book that can help you clarify your understanding of rotations.

State Estimation for Robotics by Timothy D. Barfoot http://asrl.utias.utoronto.ca/~tdb/bib/barfoot_ser17.pdf

Specifically equation 7.75 for how we use Jr / Jl. image

In the first equation you posted, we are doing two perturbations in respect to some omegatilda and on the G to I{k} rotation. These are not equal as you pointed out as one perturbation is in the tangent space of the Lie group, while the other we are perturbing by a multiplicative error exp(delta_theta)*exp(theta) does not equal exp(delta_theta+theta) (this is a key property of Lie groups).

We perturb in the tangent space as we want to compute the error in respect the the angular velocity white noise, and bias bg that is inside the exponential. This means the actual error is in the tangent space here.

As for your edited question the definition of theta. For SO(3) the theta is the negative of the angle you want to rotate. So if you want to rotate 30 degrees, the matrix will be R = exp(-30). You can try this out in 2d to prove why this is the case. Thus the theta_IktoIk+1 will be the angular velocity time DT negated. Hope this helps.