mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Compass: removed incorrect semaphore take() in QMC5883L driver
This commit is contained in:
parent
686d92aac5
commit
0b9d0a4559
@ -200,10 +200,6 @@ void AP_Compass_QMC5883L::timer()
|
|||||||
|
|
||||||
void AP_Compass_QMC5883L::read()
|
void AP_Compass_QMC5883L::read()
|
||||||
{
|
{
|
||||||
if (!_sem->take_nonblocking()) {
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
drain_accumulated_samples(_instance);
|
drain_accumulated_samples(_instance);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user