kriswiner / MPU9250

Arduino sketches for MPU9250 9DoF with AHRS sensor fusion
1.02k stars 469 forks source link

Dynamic accelerometer gravity bias detection #382

Open Tezirg opened 5 years ago

Tezirg commented 5 years ago

Hi Kriswiner,

Thanks for sharing your driver implementation, that was quite useful to do my SPI implementation.

I have made an improvement you may be interested in, regarding the accelerometer bias :

Instead of removing the accelerometer resolution from the z bias value, as done here : https://github.com/kriswiner/MPU9250/blob/master/AK8963_as_slave/MPU9250.cpp#L528

I use a dynamic approach to detect which axis is sensing the gravity and remove the resolution from this axis bias. This allows for the sensor initial orientation to be anything, as long as it is orthogonal to the ground plane.

    // Detect the axis sensing the gravity                                      
    // Remove gravity from this axis accelerometer bias                         
    uint32_t acc_res_upper = (uint32_t)(accelsensitivity * 1.15f);
    uint32_t acc_res_lower = (uint32_t)(accelsensitivity * 0.85f);
    for (uint8_t i = 0; i < 3; i++)
    {
      uint32_t acc_b_abs = (uint32_t)(accel_bias[i] & 0x7FFFFFFF);
      if (acc_b_abs < acc_res_upper && acc_b_abs > acc_res_lower)
      {
        if (accel_bias[i] > 0L)
          accel_bias[i] -= (int32_t)accelsensitivity;
        else
          accel_bias[i] += (int32_t)accelsensitivity;
      }
    }

I'm using a threshold of 15%, from my tests, it works well. But I may be missing something causing problems in the future, so I'd love feedback on this. Thanks

kriswiner commented 5 years ago

Yes, I do something similar with either 20 02 25% but the problem comes when the device is at an odd angle, i.e., no plane is orthogonal to the gravity axis, then two of the axes or none can meet this criterion and the result is wrong. So this kind of thing will only work when one of the axes is close to orthogonal. I have not found a general method for always getting this right. The easy way is to have the sensor flat and motionless during calibration, and this always works.

On Sun, Jul 28, 2019 at 7:02 AM Tezirg notifications@github.com wrote:

Hi Kriswiner,

Thanks for sharing your driver implementation, that was quite useful to do my SPI implementation.

I have made an improvement you may be interested in, regarding the accelerometer bias :

Instead of removing the accelerometer resolution from the z bias value, as done here :

https://github.com/kriswiner/MPU9250/blob/master/AK8963_as_slave/MPU9250.cpp#L528

I use a dynamic approach to detect which axis is sensing the gravity and remove the resolution from this axis bias. This allows for the sensor initial orientation to be anything, as long as it is orthogonal to the ground plane.

// Detect the axis sensing the gravity
// Remove gravity from this axis accelerometer bias
uint32_t acc_res_upper = (uint32_t)(accelsensitivity * 1.15f);
uint32_t acc_res_lower = (uint32_t)(accelsensitivity * 0.85f);
for (uint8_t i = 0; i < 3; i++)
{
  uint32_t acc_b_abs = (uint32_t)(accel_bias[i] & 0x7FFFFFFF);
  if (acc_b_abs < acc_res_upper && acc_b_abs > acc_res_lower)
  {
    if (accel_bias[i] > 0L)
      accel_bias[i] -= (int32_t)accelsensitivity;
    else
      accel_bias[i] += (int32_t)accelsensitivity;
  }
}

I'm using a threshold of 15%, from my tests, it works well. But I may be missing something causing problems in the future, so I'd love feedback on this. Thanks

— You are receiving this because you are subscribed to this thread. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/382?email_source=notifications&email_token=ABTDLKSBJLSEQN5JK4LOL3TQBWRHBA5CNFSM4IHMSDN2YY3PNVWWK3TUL52HS4DFUVEXG43VMWVGG33NNVSW45C7NFSM4HB4Z7GQ, or mute the thread https://github.com/notifications/unsubscribe-auth/ABTDLKUUZZTPQ6O6HMYVGVLQBWRHBANCNFSM4IHMSDNQ .

Tezirg commented 5 years ago

Great, thanks for confirming.

I'll have a go at solving the general case. I think it is possible by using a bit of memory (40 3 int16_t): A - Compute FIFO values mean B - Remove mean from FIFO values C - Compute mean from updated FIFO values D - Use updated mean as bias

I'll update this issue with my results, if that's of interest.

kriswiner commented 5 years ago

Of course, once you get a quaternion solution it is possible to estimate gravity with fairly high accuracy, so you could also do a two step process:

1) initial calibration

2) estimate quaternions

3) estimate gravity

4) final calibration

It is just easier to make sure of the flat and motionless orientation before calibration. In fact we have developed a calibration fixture which allows precise 24-position placement so that cross-axis error as well as offset bias of both accel and mag can be corrected. It works very well, affording routine < 1 degree heading accuracy. We'll be selling this on Tindie before long at < $100.

On Sun, Jul 28, 2019 at 7:29 AM Tezirg notifications@github.com wrote:

Great, thanks for confirming.

I'll have a go at solving the general case. I think it is possible by using a bit of memory (40 3 int16_t): A - Compute FIFO values mean B - Remove mean from FIFO values C - Compute mean from updated FIFO values D - Use updated mean as bias

I'll update this issue with my results, if that's of interest.

— You are receiving this because you commented. Reply to this email directly, view it on GitHub https://github.com/kriswiner/MPU9250/issues/382?email_source=notifications&email_token=ABTDLKVJMXUJBL5WG4TTFDTQBWUOBA5CNFSM4IHMSDN2YY3PNVWWK3TUL52HS4DFVREXG43VMVBW63LNMVXHJKTDN5WW2ZLOORPWSZGOD267ZEQ#issuecomment-515767442, or mute the thread https://github.com/notifications/unsubscribe-auth/ABTDLKXIMOWQC4KO4DEXQWLQBWUOBANCNFSM4IHMSDNQ .

Tezirg commented 5 years ago

Alright, please let me know when you do; I may be interested.

Also, I just implemented and tested the proposed general case algorithm (ABCD). I seems to work for any starting orientations at the expense of an extra 41 3 sizeof(int16_t) on the calibrate function stack.