diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp index 72ede87976..ae9246ece0 100644 --- a/src/modules/mavlink/mavlink_ftp.cpp +++ b/src/modules/mavlink/mavlink_ftp.cpp @@ -224,12 +224,14 @@ MavlinkFTP::_process_request(Request *req) out: // handle success vs. error if (errorCode == kErrNone) { + payload->req_opcode = payload->opcode; payload->opcode = kRspAck; #ifdef MAVLINK_FTP_DEBUG warnx("FTP: ack\n"); #endif } else { warnx("FTP: nak %u", errorCode); + payload->req_opcode = payload->opcode; payload->opcode = kRspNak; payload->size = 1; payload->data[0] = errorCode; @@ -654,7 +656,6 @@ MavlinkFTP::_payload_crc32(PayloadHeader *payload) payload->crc32 = 0; payload->padding[0] = 0; payload->padding[1] = 0; - payload->padding[2] = 0; uint32_t retCRC = crc32((const uint8_t*)payload, payload->size + sizeof(PayloadHeader)); payload->crc32 = saveCRC; diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h index b4cc154d11..1fb50a17e6 100644 --- a/src/modules/mavlink/mavlink_ftp.h +++ b/src/modules/mavlink/mavlink_ftp.h @@ -76,7 +76,8 @@ public: uint8_t session; ///< Session id for read and write commands uint8_t opcode; ///< Command opcode uint8_t size; ///< Size of data - uint8_t padding[3]; ///< 32 bit aligment padding + uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message + uint8_t padding[2]; ///< 32 bit aligment padding uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0 uint32_t offset; ///< Offsets for List and Read commands uint8_t data[]; ///< command data, varies by Opcode