mirror of https://github.com/ArduPilot/ardupilot
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:
parent
c7b5a24047
commit
dafd030904
|
@ -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);
|
||||||
|
|
Loading…
Reference in New Issue