mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
AP_AHRS: add semaphore around set_home()
added semaphore around set_home() to avoid thread racing
This commit is contained in:
parent
d1a228b086
commit
16f7348f96
@ -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)
|
bool AP_AHRS_DCM::set_home(const Location &loc)
|
||||||
{
|
{
|
||||||
|
WITH_SEMAPHORE(_rsem);
|
||||||
// check location is valid
|
// check location is valid
|
||||||
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
|
if (loc.lat == 0 && loc.lng == 0 && loc.alt == 0) {
|
||||||
return false;
|
return false;
|
||||||
|
Loading…
Reference in New Issue
Block a user