Browse Source

AP_AHRS: ensure home is always stored in ALT_FRAME_ABSOLUTE

mission-4.1.18
Peter Barker 6 years ago committed by Andrew Tridgell
parent
commit
3959780999
  1. 9
      libraries/AP_AHRS/AP_AHRS_DCM.cpp

9
libraries/AP_AHRS/AP_AHRS_DCM.cpp

@ -1040,8 +1040,15 @@ bool AP_AHRS_DCM::set_home(const Location &loc)
if (!check_latlng(loc)) { if (!check_latlng(loc)) {
return false; return false;
} }
// home must always be global frame at the moment as .alt is
// accessed directly by the vehicles and they may not be rigorous
// in checking the frame type.
Location tmp = loc;
if (!tmp.change_alt_frame(Location::ALT_FRAME_ABSOLUTE)) {
return false;
}
_home = loc; _home = tmp;
_home_is_set = true; _home_is_set = true;
// log ahrs home and ekf origin dataflash // log ahrs home and ekf origin dataflash

Loading…
Cancel
Save