ArduCopter: eliminate AP::ahrs().get_location

This commit is contained in:
Peter Barker 2021-08-27 13:04:59 +10:00 committed by Andrew Tridgell
parent 34ff53f158
commit a38879f77e

View File

@ -24,7 +24,7 @@ void Copter::set_home_to_current_location_inflight() {
// get current location from EKF
Location temp_loc;
Location ekf_origin;
if (ahrs.get_location(temp_loc) && ahrs.get_origin(ekf_origin)) {
if (ahrs.get_position(temp_loc) && ahrs.get_origin(ekf_origin)) {
temp_loc.alt = ekf_origin.alt;
if (!set_home(temp_loc, false)) {
return;
@ -40,7 +40,7 @@ void Copter::set_home_to_current_location_inflight() {
bool Copter::set_home_to_current_location(bool lock) {
// get current location from EKF
Location temp_loc;
if (ahrs.get_location(temp_loc)) {
if (ahrs.get_position(temp_loc)) {
if (!set_home(temp_loc, lock)) {
return false;
}