mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-10 09:58:28 -04:00
AP_Baro: prevent a race condition in the SITL baro driver
This commit is contained in:
parent
86afc26609
commit
3393a5c99e
@ -19,6 +19,7 @@ uint8_t AP_Baro_HIL::read()
|
|||||||
uint8_t result = 0;
|
uint8_t result = 0;
|
||||||
|
|
||||||
if (_count != 0) {
|
if (_count != 0) {
|
||||||
|
hal.scheduler->suspend_timer_procs();
|
||||||
result = 1;
|
result = 1;
|
||||||
Press = ((float)_pressure_sum) / _count;
|
Press = ((float)_pressure_sum) / _count;
|
||||||
Temp = ((float)_temperature_sum) / _count;
|
Temp = ((float)_temperature_sum) / _count;
|
||||||
@ -26,6 +27,7 @@ uint8_t AP_Baro_HIL::read()
|
|||||||
_count = 0;
|
_count = 0;
|
||||||
_pressure_sum = 0;
|
_pressure_sum = 0;
|
||||||
_temperature_sum = 0;
|
_temperature_sum = 0;
|
||||||
|
hal.scheduler->resume_timer_procs();
|
||||||
}
|
}
|
||||||
|
|
||||||
return result;
|
return result;
|
||||||
|
@ -13,7 +13,7 @@ private:
|
|||||||
float Press;
|
float Press;
|
||||||
int32_t _pressure_sum;
|
int32_t _pressure_sum;
|
||||||
int32_t _temperature_sum;
|
int32_t _temperature_sum;
|
||||||
uint8_t _count;
|
volatile uint8_t _count;
|
||||||
|
|
||||||
public:
|
public:
|
||||||
bool init();
|
bool init();
|
||||||
|
Loading…
Reference in New Issue
Block a user