mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 14:08:45 -04:00
AP_Compass: don't wait more than 1ms for compass sample
this prevents 5ms delays in compass accumulate
This commit is contained in:
parent
42255ebbc6
commit
1ccd6bb7ef
@ -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…
Reference in New Issue
Block a user