Browse Source

AP_Compass: removed incorrect semaphore take() in QMC5883L driver

master
Andrew Tridgell 6 years ago committed by Lucas De Marchi
parent
commit
0b9d0a4559
  1. 4
      libraries/AP_Compass/AP_Compass_QMC5883L.cpp

4
libraries/AP_Compass/AP_Compass_QMC5883L.cpp

@ -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…
Cancel
Save