diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index e6fc14fdbd..cb330bb9d8 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -583,24 +583,7 @@ void MavlinkReceiver::handle_message_command_both(mavlink_message_t *msg, const return; } - // First we handle legacy support requests which were used before we had - // the generic MAV_CMD_REQUEST_MESSAGE. - if (cmd_mavlink.command == MAV_CMD_REQUEST_AUTOPILOT_CAPABILITIES) { - result = handle_request_message_command(MAVLINK_MSG_ID_AUTOPILOT_VERSION); - - } else if (cmd_mavlink.command == MAV_CMD_REQUEST_PROTOCOL_VERSION) { - result = handle_request_message_command(MAVLINK_MSG_ID_PROTOCOL_VERSION); - - } else if (cmd_mavlink.command == MAV_CMD_GET_HOME_POSITION) { - result = handle_request_message_command(MAVLINK_MSG_ID_HOME_POSITION); - - } else if (cmd_mavlink.command == MAV_CMD_REQUEST_FLIGHT_INFORMATION) { - result = handle_request_message_command(MAVLINK_MSG_ID_FLIGHT_INFORMATION); - - } else if (cmd_mavlink.command == MAV_CMD_REQUEST_STORAGE_INFORMATION) { - result = handle_request_message_command(MAVLINK_MSG_ID_STORAGE_INFORMATION); - - } else if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) { + if (cmd_mavlink.command == MAV_CMD_SET_MESSAGE_INTERVAL) { if (set_message_interval( (int)(cmd_mavlink.param1 + 0.5f), cmd_mavlink.param2, cmd_mavlink.param3, cmd_mavlink.param4, vehicle_command.param7)) { result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_FAILED;