diff --git a/ArduSub/GCS_Mavlink.cpp b/ArduSub/GCS_Mavlink.cpp index 90e146760f..dbea46d35c 100644 --- a/ArduSub/GCS_Mavlink.cpp +++ b/ArduSub/GCS_Mavlink.cpp @@ -480,13 +480,6 @@ MAV_RESULT GCS_MAVLINK_Sub::handle_command_do_set_roi(const Location &roi_loc) return MAV_RESULT_ACCEPTED; } -bool GCS_MAVLINK_Sub::set_home_to_current_location(bool _lock) { - return sub.set_home_to_current_location(_lock); -} -bool GCS_MAVLINK_Sub::set_home(const Location& loc, bool _lock) { - return sub.set_home(loc, _lock); -} - MAV_RESULT GCS_MAVLINK_Sub::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch(packet.command) { diff --git a/ArduSub/GCS_Mavlink.h b/ArduSub/GCS_Mavlink.h index f02c782cd0..4ca41e1d8c 100644 --- a/ArduSub/GCS_Mavlink.h +++ b/ArduSub/GCS_Mavlink.h @@ -29,9 +29,6 @@ protected: int32_t global_position_int_alt() const override; int32_t global_position_int_relative_alt() const override; - bool set_home_to_current_location(bool lock) override WARN_IF_UNUSED; - bool set_home(const Location& loc, bool lock) override WARN_IF_UNUSED; - void send_banner() override; void send_nav_controller_output() const override; diff --git a/ArduSub/Sub.h b/ArduSub/Sub.h index fee135282e..98d36db4c2 100644 --- a/ArduSub/Sub.h +++ b/ArduSub/Sub.h @@ -423,8 +423,8 @@ private: void userhook_SuperSlowLoop(); void update_home_from_EKF(); void set_home_to_current_location_inflight(); - bool set_home_to_current_location(bool lock) WARN_IF_UNUSED; - bool set_home(const Location& loc, bool lock) 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; bool far_from_EKF_origin(const Location& loc); float get_alt_rel() const WARN_IF_UNUSED; float get_alt_msl() const WARN_IF_UNUSED;