From 76f5db93dce8cfedea8729a4a1672993252a41a0 Mon Sep 17 00:00:00 2001 From: CallanDaniel Date: Tue, 22 Jun 2021 14:26:20 +0200 Subject: [PATCH] AP_AHRS: add semaphore around set_home() added semaphore around set_home() to avoid thread racing --- libraries/AP_AHRS/AP_AHRS_DCM.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/libraries/AP_AHRS/AP_AHRS_DCM.cpp b/libraries/AP_AHRS/AP_AHRS_DCM.cpp index 6f6486b42e..4d1e73af1c 100644 --- a/libraries/AP_AHRS/AP_AHRS_DCM.cpp +++ b/libraries/AP_AHRS/AP_AHRS_DCM.cpp @@ -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;