diff --git a/ArduCopter/commands.cpp b/ArduCopter/commands.cpp index 0ba6457bb8ecc..6c3f72d8003b0 100644 --- a/ArduCopter/commands.cpp +++ b/ArduCopter/commands.cpp @@ -37,18 +37,16 @@ void Copter::set_home_to_current_location_inflight() { } // set_home_to_current_location - set home to current GPS location -bool Copter::set_home_to_current_location(bool lock) { - // get current location from EKF - Location temp_loc; - if (ahrs.get_location(temp_loc)) { - if (!set_home(temp_loc, lock)) { - return false; - } - // we have successfully set AHRS home, set it for SmartRTL +bool Copter::set_home_to_current_location(bool lock) +{ + if (!AP_Vehicle::set_home_to_current_location(lock)) { + return false; + } + + // we have successfully set AHRS home, set it for SmartRTL #if MODE_SMARTRTL_ENABLED == ENABLED - g2.smart_rtl.set_home(true); + g2.smart_rtl.set_home(true); #endif - return true; - } - return false; + + return true; }