mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 06:58:39 -04:00
AP_AHRS: retry sending home/origin if it fails
This commit is contained in:
parent
ace5192852
commit
6fd687e861
@ -1055,8 +1055,8 @@ bool AP_AHRS_DCM::set_home(const Location &loc)
|
||||
Log_Write_Home_And_Origin();
|
||||
|
||||
// send new home and ekf origin to GCS
|
||||
gcs().send_home();
|
||||
gcs().send_ekf_origin();
|
||||
gcs().send_message(MSG_HOME);
|
||||
gcs().send_message(MSG_ORIGIN);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user