AP_Airspeed: switched to recursive semaphore

this is needed by the SDP3X driver. It is the simplest fix for the
issue
This commit is contained in:
Andrew Tridgell 2019-11-10 16:45:48 +11:00
parent c7b5a24047
commit dafd030904
1 changed files with 1 additions and 1 deletions

View File

@ -46,7 +46,7 @@ protected:
} }
// semaphore for access to shared frontend data // semaphore for access to shared frontend data
HAL_Semaphore sem; HAL_Semaphore_Recursive sem;
float get_airspeed_ratio(void) const { float get_airspeed_ratio(void) const {
return frontend.get_airspeed_ratio(instance); return frontend.get_airspeed_ratio(instance);