AP_AHRS: add semaphore around set_home()

added semaphore around set_home() to avoid thread racing
This commit is contained in:
CallanDaniel 2021-06-22 14:26:20 +02:00 committed by Randy Mackay
parent a617175881
commit 76f5db93dc
1 changed files with 1 additions and 0 deletions

View File

@ -1089,6 +1089,7 @@ bool AP_AHRS_DCM::airspeed_estimate(uint8_t airspeed_index, float &airspeed_ret)
bool AP_AHRS_DCM::set_home(const Location &loc)
{
WITH_SEMAPHORE(_rsem);
// check location is valid
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
return false;