-
Notifications
You must be signed in to change notification settings - Fork 777
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
IMUFactor example noise/bias units #213
Comments
Did you solve the myth @Jason420Git |
For what it's worth, here's a relevant disucssion from the mailing list last fall. A quick summary could be, "Read the IMU noise model wiki page over at the ETHZ Kalibr project", and, "converting between different units is hard." If you take a look at that datasheet from Bosch, two numbers that jump out at me that will be relevant for you are, 'Output noise' (top of page 9) a) get that from the manufacturer with low-quality IMUs, guessing is not insane. The manufacturer will usually include a 'bias stability' or 'bias instability' number, and once you understand how Allan variance plots work, you can use that bias instability as an upper bound for the gyro random walk and accel random walk values. Good luck! |
So I have made some progress on this, but not enough to have a satisfactory answer for everyone. Unfortunately, I have a deadline coming up next week so I am going to have to push this back until then. I am assigning this to myself though and you can rest assured I will figure this out. :) |
So, I thought that the submitter was trying to find appropriate numerical values; if they just want the units, I would be shocked if they do not correspond to the IMU noise model at the Kalibr wiki. that is:
This is strongly implied by Forster et al., TRO '16 in footnote 2 on page 10, where the IMU parameters for the simulations are listed and match the units from the Kalibr wiki. Also, Kalibr is mentioned in the paper, although not explicitly in the context of calibrating IMU measurements. As @dellaert said in the e-mail chain I linked above, Forster and Luca Carlone (cc @lucacarlone ) are probably the only ones that know for sure. |
@mikesheffler : correct! the variables accel_noise_sigma, gyro_noise_sigma, accel_bias_rw_sigma, gyro_bias_rw_sigma are the continuous-time noise densities of the imu noise and the random walks (the discretization happens inside the factors). Therefore the units are the same as the ones mentioned in the Kalibr wiki, except a couple of (minor) typos in the Kalibr github: ethz-asl/kalibr#354 |
So after spending a lot of time deep in the trenches with the code, and even understanding noise derivation via Allan Deviation plots, I can confirm what @lucacarlone already mentioned. The units are:
@dellaert please recommend where should I put this info? |
Love you guys! This helped me a lot 👍 |
@varunagrawal I am a little confused about this. |
Yes, there is a conversion necessary. I don't believe the conversion involves the IMU frequency. Take a look at this post on the Analog Devices forum . That person is talking about a gyroscope instead of an accelerometer, but their question is fundamentally similar to yours. Look at NevadaMark's answer. There, he's talking about values related to the (root) Allan variance curve, which (the units from the curve) are specified in deg / s. He's then converting those numbers to units to talk about values in deg / sqrt(hr) and deg / hr. Your problem doesn't involve units of hours, but note how he uses the sqrt in his conversion because of the units of the angle random walk vs the units of the bias stability. |
No. Source: IEEE Standard 952-2020 for Specifying and Testing Single-Axis Interferometric Fiber Optic Gyros (page 18f)
Unfortunately the IEEE standard is only concerned with gyroscopes, not accelerometers. However, if we substitute
These units are consistent with the following table from the Kalibr wiki (modified by me): Q and R are irrelevant for most practical applications, so mostly an IMU is only modeled using N, B and K or just N and K (but never N and B). I am pretty sure that gtsam only uses N and K. Unfortunately, there's a lot of different terms for the same thing:
For Accelerometers, you have to substitute "angle" → "velocity" and "rate" → "acceleration" Most IMU datasheets only list N and B. Also, sometimes they list rms (root mean squared error), which is not what we want; we want the standard deviation. @mikesheffler wrote:
Yes, this is correct. @varunagrawal wrote:
Not quite, at least from what I understand. I think this would be correct:
|
Hi, I am trying to use GTSAM to create a system using IMU and GPS measurements together in a factor graph.
I was following the example IMUFactor. It has the following values which were being computed from the sensor specifications
However there are no units attached to these. I am trying to better model the IMU I am using which is Bosch BMI160. I cannot find any values which resemble these.
https://ae-bst.resource.bosch.com/media/_tech/media/datasheets/BST-BMI160-DS000.pdf
Any help in adapting the sample to use this IMU would be of great help!
The text was updated successfully, but these errors were encountered: