diff --git a/ArduCopter/GCS_Mavlink.cpp b/ArduCopter/GCS_Mavlink.cpp index aebade15dc..57918dd3ab 100644 --- a/ArduCopter/GCS_Mavlink.cpp +++ b/ArduCopter/GCS_Mavlink.cpp @@ -559,16 +559,6 @@ bool GCS_MAVLINK_Copter::handle_guided_request(AP_Mission::Mission_Command &cmd) #endif } -void GCS_MAVLINK_Copter::handle_change_alt_request(AP_Mission::Mission_Command &cmd) -{ - // add home alt if needed - if (cmd.content.location.relative_alt) { - cmd.content.location.alt += copter.ahrs.get_home().alt; - } - - // To-Do: update target altitude for loiter or waypoint controller depending upon nav mode -} - void GCS_MAVLINK_Copter::packetReceived(const mavlink_status_t &status, const mavlink_message_t &msg) { diff --git a/ArduCopter/GCS_Mavlink.h b/ArduCopter/GCS_Mavlink.h index 4ee57af953..74230150b2 100644 --- a/ArduCopter/GCS_Mavlink.h +++ b/ArduCopter/GCS_Mavlink.h @@ -52,7 +52,6 @@ private: void handleMessage(const mavlink_message_t &msg) override; void handle_command_ack(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 packetReceived(const mavlink_status_t &status,