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

this prevents 5ms delays in compass accumulate
This commit is contained in:
Andrew Tridgell 2013-10-08 11:28:05 +11:00
parent 42255ebbc6
commit 1ccd6bb7ef
1 changed files with 1 additions and 1 deletions

View File

@ -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;
}