Browse Source

AP_Compass: don't wait more than 1ms for compass sample

this prevents 5ms delays in compass accumulate
mission-4.1.18
Andrew Tridgell 11 years ago
parent
commit
1ccd6bb7ef
  1. 2
      libraries/AP_Compass/AP_Compass_HMC5843.cpp

2
libraries/AP_Compass/AP_Compass_HMC5843.cpp

@ -128,7 +128,7 @@ void AP_Compass_HMC5843::accumulate(void) @@ -128,7 +128,7 @@ void AP_Compass_HMC5843::accumulate(void)
return;
}
if (!_i2c_sem->take(5)) {
if (!_i2c_sem->take(1)) {
// the bus is busy - try again later
return;
}

Loading…
Cancel
Save