diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 129cc8c329fc6f..f38e8f3dd04989 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -656,14 +656,6 @@ MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlin return GCS_MAVLINK::_handle_command_preflight_calibration(packet, msg); } -bool GCS_MAVLINK_Rover::set_home_to_current_location(bool _lock) { - return rover.set_home_to_current_location(_lock); -} - -bool GCS_MAVLINK_Rover::set_home(const Location& loc, bool _lock) { - return rover.set_home(loc, _lock); -} - MAV_RESULT GCS_MAVLINK_Rover::handle_command_int_packet(const mavlink_command_int_t &packet, const mavlink_message_t &msg) { switch (packet.command) { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index 048bb86969a4e5..2d4ca700a29db8 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -31,8 +31,6 @@ class GCS_MAVLINK_Rover : public GCS_MAVLINK bool persist_streamrates() const override { return true; } - bool set_home_to_current_location(bool lock) override; - bool set_home(const Location& loc, bool lock) override; uint64_t capabilities() const override; void send_nav_controller_output() const override; diff --git a/Rover/Rover.h b/Rover/Rover.h index e12ed2db608b85..8873b844e2946c 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -295,8 +295,8 @@ class Rover : public AP_Vehicle { bool is_balancebot() const; // commands.cpp - 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; void update_home(); // crash_check.cpp