AP_Compass: removed incorrect semaphore take() in QMC5883L driver

This commit is contained in:
Andrew Tridgell 2018-10-16 19:18:58 +11:00 committed by Lucas De Marchi
parent 686d92aac5
commit 0b9d0a4559

View File

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