From 5d41125b49a24b5cba93253fcf9ffad8b6fff3e9 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 3 Apr 2024 21:40:30 +1100 Subject: [PATCH] ArduCopter: move handling of DO_SET_HOME up to GCS_MAVLink base class --- ArduCopter/Copter.h | 4 ++-- ArduCopter/GCS_Mavlink.cpp | 7 ------- ArduCopter/GCS_Mavlink.h | 2 -- 3 files changed, 2 insertions(+), 11 deletions(-) diff --git a/ArduCopter/Copter.h b/ArduCopter/Copter.h index b3be8285f7..e0e891432e 100644 --- a/ArduCopter/Copter.h +++ b/ArduCopter/Copter.h @@ -739,8 +739,8 @@ private: // commands.cpp 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); // compassmot.cpp diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index 9c7eeccf16..3c10b8e0ce 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -711,13 +711,6 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_preflight_reboot(const mavlink_command_int return GCS_MAVLINK::handle_preflight_reboot(packet, msg); } -bool GCS_MAVLINK_Copter::set_home_to_current_location(bool _lock) { - return copter.set_home_to_current_location(_lock); -} -bool GCS_MAVLINK_Copter::set_home(const Location& loc, bool _lock) { - return copter.set_home(loc, _lock); -} - MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_do_reposition(const mavlink_command_int_t &packet) { #if MODE_GUIDED_ENABLED == ENABLED diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 1961916e03..30d325c01d 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -48,8 +48,6 @@ protected: void handle_landing_target(const mavlink_landing_target_t &packet, uint32_t timestamp_ms) 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_nav_controller_output() const override; uint64_t capabilities() const override;