From 2b76f66ebcb616ab676c9ea30bc94b8619349c8d Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Apr 2024 21:40:31 +1100 Subject: [PATCH] Rover: move handling of DO_SET_HOME up to GCS_MAVLink base class --- Rover/GCS_Mavlink.cpp | 8 -------- Rover/GCS_Mavlink.h | 2 -- Rover/Rover.h | 4 ++-- 3 files changed, 2 insertions(+), 12 deletions(-) diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index 129cc8c329..f38e8f3dd0 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 048bb86969..2d4ca700a2 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -31,8 +31,6 @@ protected: 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 e12ed2db60..8873b844e2 100644 --- a/Rover/Rover.h +++ b/Rover/Rover.h @@ -295,8 +295,8 @@ private: 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