aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink/mavlink_ftp.cpp
diff options
context:
space:
mode:
authorDon Gagne <don@thegagnes.com>2014-09-10 12:28:42 -0700
committerDon Gagne <don@thegagnes.com>2014-09-10 12:28:42 -0700
commite4f3fd88f0623659e6759b9b076be15e4e2f5703 (patch)
tree2c20646fd0fe66db95e06b1abcf7ff16106df14c /src/modules/mavlink/mavlink_ftp.cpp
parent35a6074419b3dcf567f23db74b8ea53eff20c9d6 (diff)
parent0e3c6060b6375fa08b6c0087f7aaf2905ea516d0 (diff)
downloadpx4-firmware-e4f3fd88f0623659e6759b9b076be15e4e2f5703.tar.gz
px4-firmware-e4f3fd88f0623659e6759b9b076be15e4e2f5703.tar.bz2
px4-firmware-e4f3fd88f0623659e6759b9b076be15e4e2f5703.zip
Merge pull request #1357 from vooon/ftp_opcode
FTP request opcode
Diffstat (limited to 'src/modules/mavlink/mavlink_ftp.cpp')
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp27
1 files changed, 2 insertions, 25 deletions
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 72ede8797..64206ac54 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -34,7 +34,6 @@
/// @file mavlink_ftp.cpp
/// @author px4dev, Don Gagne <don@thegagnes.com>
-#include <crc32.h>
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
@@ -161,13 +160,6 @@ MavlinkFTP::_process_request(Request *req)
goto out;
}
- // check request CRC to make sure this is one of ours
- if (_payload_crc32(payload) != payload->crc32) {
- errorCode = kErrCrc;
- goto out;
- warnx("ftp: bad crc");
- }
-
#ifdef MAVLINK_FTP_DEBUG
printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset);
#endif
@@ -224,12 +216,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;
@@ -254,8 +248,6 @@ MavlinkFTP::_reply(Request *req)
payload->seqNumber = payload->seqNumber + 1;
- payload->crc32 = _payload_crc32(payload);
-
mavlink_message_t msg;
msg.checksum = 0;
#ifndef MAVLINK_FTP_UNIT_TEST
@@ -645,18 +637,3 @@ MavlinkFTP::_return_request(Request *req)
_unlock_request_queue();
}
-/// @brief Returns the 32 bit CRC for the payload, crc32 and padding members are set to 0 for calculation.
-uint32_t
-MavlinkFTP::_payload_crc32(PayloadHeader *payload)
-{
- // We calculate CRC with crc and padding set to 0.
- uint32_t saveCRC = payload->crc32;
- 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;
-
- return retCRC;
-}