diff --git a/libraries/GCS_MAVLink/GCS_Common.cpp b/libraries/GCS_MAVLink/GCS_Common.cpp index c1f07fea17c82..90c6eb88e99d6 100644 --- a/libraries/GCS_MAVLink/GCS_Common.cpp +++ b/libraries/GCS_MAVLink/GCS_Common.cpp @@ -2600,19 +2600,7 @@ void GCS_MAVLINK::handle_set_mode(const mavlink_message_t &msg) const MAV_MODE _base_mode = (MAV_MODE)packet.base_mode; const uint32_t _custom_mode = packet.custom_mode; - const MAV_RESULT result = _set_mode_common(_base_mode, _custom_mode); - - // send ACK or NAK. Note that this is extraodinarily improper - - // we are sending a command-ack for a message which is not a - // command. The command we are acking (ID=11) doesn't actually - // exist, but if it did we'd probably be acking something - // completely unrelated to setting modes. - if (HAVE_PAYLOAD_SPACE(chan, COMMAND_ACK)) { - mavlink_msg_command_ack_send(chan, MAVLINK_MSG_ID_SET_MODE, result, - 0, 0, - msg.sysid, - msg.compid); - } + _set_mode_common(_base_mode, _custom_mode); } /*