diff --git a/ArduPlane/GCS_Mavlink.cpp b/ArduPlane/GCS_Mavlink.cpp index 751544d915..aabe9cfbe5 100644 --- a/ArduPlane/GCS_Mavlink.cpp +++ b/ArduPlane/GCS_Mavlink.cpp @@ -781,25 +781,25 @@ void GCS_MAVLINK_Plane::packetReceived(const mavlink_status_t &status, } -bool GCS_MAVLINK_Plane::set_home_to_current_location(bool _lock) +bool Plane::set_home_to_current_location(bool _lock) { - if (!plane.set_home_persistently(AP::gps().location())) { + if (!set_home_persistently(AP::gps().location())) { return false; } if (_lock) { AP::ahrs().lock_home(); } - if ((plane.control_mode == &plane.mode_rtl) + if ((control_mode == &mode_rtl) #if HAL_QUADPLANE_ENABLED - || (plane.control_mode == &plane.mode_qrtl) + || (control_mode == &mode_qrtl) #endif ) { // if in RTL head to the updated home location - plane.control_mode->enter(); + control_mode->enter(); } return true; } -bool GCS_MAVLINK_Plane::set_home(const Location& loc, bool _lock) +bool Plane::set_home(const Location& loc, bool _lock) { if (!AP::ahrs().set_home(loc)) { return false; @@ -807,13 +807,13 @@ bool GCS_MAVLINK_Plane::set_home(const Location& loc, bool _lock) if (_lock) { AP::ahrs().lock_home(); } - if ((plane.control_mode == &plane.mode_rtl) + if ((control_mode == &mode_rtl) #if HAL_QUADPLANE_ENABLED - || (plane.control_mode == &plane.mode_qrtl) + || (control_mode == &mode_qrtl) #endif ) { // if in RTL head to the updated home location - plane.control_mode->enter(); + control_mode->enter(); } return true; } diff --git a/ArduPlane/GCS_Mavlink.h b/ArduPlane/GCS_Mavlink.h index b3b59cb2d8..da77d1b357 100644 --- a/ArduPlane/GCS_Mavlink.h +++ b/ArduPlane/GCS_Mavlink.h @@ -42,8 +42,6 @@ protected: bool persist_streamrates() const override { return true; } - bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; - bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; uint64_t capabilities() const override; void send_nav_controller_output() const override; diff --git a/ArduPlane/Plane.h b/ArduPlane/Plane.h index 189189e9dc..71b450256c 100644 --- a/ArduPlane/Plane.h +++ b/ArduPlane/Plane.h @@ -986,6 +986,8 @@ private: // set home location and store it persistently: bool set_home_persistently(const Location &loc) WARN_IF_UNUSED; + bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; + bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; // control_modes.cpp void read_control_switch();