diff --git a/Blimp/Blimp.h b/Blimp/Blimp.h index 826d92b98c..ccaa200a1c 100644 --- a/Blimp/Blimp.h +++ b/Blimp/Blimp.h @@ -310,8 +310,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); // ekf_check.cpp diff --git a/Blimp/GCS_Mavlink.cpp b/Blimp/GCS_Mavlink.cpp index e6107aab6f..ff52827562 100644 --- a/Blimp/GCS_Mavlink.cpp +++ b/Blimp/GCS_Mavlink.cpp @@ -448,15 +448,6 @@ MAV_RESULT GCS_MAVLINK_Blimp::handle_command_do_set_roi(const Location &roi_loc) return MAV_RESULT_ACCEPTED; } -bool GCS_MAVLINK_Blimp::set_home_to_current_location(bool _lock) -{ - return blimp.set_home_to_current_location(_lock); -} -bool GCS_MAVLINK_Blimp::set_home(const Location& loc, bool _lock) -{ - return blimp.set_home(loc, _lock); -} - MAV_RESULT GCS_MAVLINK_Blimp::handle_command_int_do_reposition(const mavlink_command_int_t &packet) { const bool change_modes = ((int32_t)packet.param2 & MAV_DO_REPOSITION_FLAGS_CHANGE_MODE) == MAV_DO_REPOSITION_FLAGS_CHANGE_MODE; diff --git a/Blimp/GCS_Mavlink.h b/Blimp/GCS_Mavlink.h index 71f10a414e..35276b03a4 100644 --- a/Blimp/GCS_Mavlink.h +++ b/Blimp/GCS_Mavlink.h @@ -35,8 +35,6 @@ protected: bool mav_frame_for_command_long(MAV_FRAME &frame, MAV_CMD packet_command) const override; #endif - 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; //TODO Apparently can't remove this or the build fails. uint64_t capabilities() const override;