mirror of https://github.com/ArduPilot/ardupilot
AP_AHRS: remove call to get_home()
this is our object, we don't need permission
This commit is contained in:
parent
6ef131c0f9
commit
b95bd8f19d
|
@ -1822,7 +1822,7 @@ void AP_AHRS::get_relative_position_D_home(float &posD) const
|
|||
const auto &gps = AP::gps();
|
||||
if (_gps_use == GPSUse::EnableWithHeight &&
|
||||
gps.status() >= AP_GPS::GPS_OK_FIX_3D) {
|
||||
posD = (get_home().alt - gps.location().alt) * 0.01;
|
||||
posD = (_home.alt - gps.location().alt) * 0.01;
|
||||
return;
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -257,7 +257,7 @@ void AP_AHRS::Log_Write_Home_And_Origin()
|
|||
Write_Origin(LogOriginType::ekf_origin, ekf_orig);
|
||||
}
|
||||
|
||||
if (home_is_set()) {
|
||||
if (_home_is_set) {
|
||||
Write_Origin(LogOriginType::ahrs_home, _home);
|
||||
}
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue