From 3393a5c99ef091d05516dcc9add0782dbbc7a16a Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 17 Oct 2013 17:21:36 +1100 Subject: [PATCH] AP_Baro: prevent a race condition in the SITL baro driver --- libraries/AP_Baro/AP_Baro_HIL.cpp | 2 ++ libraries/AP_Baro/AP_Baro_HIL.h | 2 +- 2 files changed, 3 insertions(+), 1 deletion(-) diff --git a/libraries/AP_Baro/AP_Baro_HIL.cpp b/libraries/AP_Baro/AP_Baro_HIL.cpp index 5f12548152..9692d0bc4b 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.cpp +++ b/libraries/AP_Baro/AP_Baro_HIL.cpp @@ -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; diff --git a/libraries/AP_Baro/AP_Baro_HIL.h b/libraries/AP_Baro/AP_Baro_HIL.h index 63d9b1cafc..9607f63944 100644 --- a/libraries/AP_Baro/AP_Baro_HIL.h +++ b/libraries/AP_Baro/AP_Baro_HIL.h @@ -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();