diff --git a/Rover/GCS_Mavlink.cpp b/Rover/GCS_Mavlink.cpp index db6904cc51..8bcf27275d 100644 --- a/Rover/GCS_Mavlink.cpp +++ b/Rover/GCS_Mavlink.cpp @@ -565,11 +565,6 @@ bool GCS_MAVLINK_Rover::handle_guided_request(AP_Mission::Mission_Command &cmd) return rover.mode_guided.set_desired_location(cmd.content.location); } -void GCS_MAVLINK_Rover::handle_change_alt_request(AP_Mission::Mission_Command &cmd) -{ - // nothing to do -} - MAV_RESULT GCS_MAVLINK_Rover::_handle_command_preflight_calibration(const mavlink_command_long_t &packet) { if (is_equal(packet.param6, 1.0f)) { diff --git a/Rover/GCS_Mavlink.h b/Rover/GCS_Mavlink.h index ec0cbb9a90..2b900f2f6d 100644 --- a/Rover/GCS_Mavlink.h +++ b/Rover/GCS_Mavlink.h @@ -35,7 +35,6 @@ private: void handleMessage(const mavlink_message_t &msg) override; bool handle_guided_request(AP_Mission::Mission_Command &cmd) override; - void handle_change_alt_request(AP_Mission::Mission_Command &cmd) override; bool try_send_message(enum ap_message id) override; void handle_manual_control(const mavlink_message_t &msg);