AP_Baro: prevent a race condition in the SITL baro driver

This commit is contained in:
Andrew Tridgell 2013-10-17 17:21:36 +11:00
parent 86afc26609
commit 3393a5c99e
2 changed files with 3 additions and 1 deletions

View File

@ -19,6 +19,7 @@ uint8_t AP_Baro_HIL::read()
uint8_t result = 0;
if (_count != 0) {
hal.scheduler->suspend_timer_procs();
result = 1;
Press = ((float)_pressure_sum) / _count;
Temp = ((float)_temperature_sum) / _count;
@ -26,6 +27,7 @@ uint8_t AP_Baro_HIL::read()
_count = 0;
_pressure_sum = 0;
_temperature_sum = 0;
hal.scheduler->resume_timer_procs();
}
return result;

View File

@ -13,7 +13,7 @@ private:
float Press;
int32_t _pressure_sum;
int32_t _temperature_sum;
uint8_t _count;
volatile uint8_t _count;
public:
bool init();