Merge pull request #1357 from vooon/ftp_opcode

FTP request opcode
This commit is contained in:
Don Gagne
2014-09-10 12:28:42 -07:00
7 changed files with 12 additions and 85 deletions
+2 -25
View File
@@ -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;
}
+4 -7
View File
@@ -76,8 +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
uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0
uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
uint8_t padding[2]; ///< 32 bit aligment padding
uint32_t offset; ///< Offsets for List and Read commands
uint8_t data[]; ///< command data, varies by Opcode
};
@@ -97,7 +97,7 @@ public:
kCmdCreateDirectory, ///< Creates directory at <path>
kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
kRspAck, ///< Ack response
kRspAck = 128, ///< Ack response
kRspNak ///< Nak response
};
@@ -111,8 +111,7 @@ public:
kErrInvalidSession, ///< Session is not currently open
kErrNoSessionsAvailable, ///< All available Sessions in use
kErrEOF, ///< Offset past end of file for List and Read commands
kErrUnknownCommand, ///< Unknown command opcode
kErrCrc ///< CRC on Payload is incorrect
kErrUnknownCommand ///< Unknown command opcode
};
private:
@@ -134,8 +133,6 @@ private:
void _lock_request_queue(void);
void _unlock_request_queue(void);
uint32_t _payload_crc32(PayloadHeader *hdr);
char *_data_as_cstring(PayloadHeader* payload);
static void _worker_trampoline(void *arg);
@@ -44,9 +44,9 @@
/// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
const MavlinkFtpTest::ReadTestCase MavlinkFtpTest::_rgReadTestCases[] = {
{ "/etc/unit_test_data/mavlink_tests/test_234.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1}, // Read takes less than single packet
{ "/etc/unit_test_data/mavlink_tests/test_235.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
{ "/etc/unit_test_data/mavlink_tests/test_236.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
{ "/etc/unit_test_data/mavlink_tests/test_238.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1}, // Read takes less than single packet
{ "/etc/unit_test_data/mavlink_tests/test_239.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
{ "/etc/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
};
const char MavlinkFtpTest::_unittest_microsd_dir[] = "/fs/microsd/ftp_unit_test_dir";
@@ -105,33 +105,6 @@ bool MavlinkFtpTest::_ack_test(void)
return true;
}
/// @brief Tests for correct response to a message sent with an invalid CRC.
bool MavlinkFtpTest::_bad_crc_test(void)
{
mavlink_message_t msg;
MavlinkFTP::PayloadHeader payload;
mavlink_file_transfer_protocol_t ftp_msg;
MavlinkFTP::PayloadHeader *reply;
payload.opcode = MavlinkFTP::kCmdNone;
_setup_ftp_msg(&payload, 0, nullptr, &msg);
((MavlinkFTP::PayloadHeader*)((mavlink_file_transfer_protocol_t*)msg.payload64)->payload)->crc32++;
_ftp_server->handle_message(nullptr /* mavlink */, &msg);
if (!_decode_message(&_reply_msg, &ftp_msg, &reply)) {
return false;
}
ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
ut_compare("Incorrect payload size", reply->size, 1);
ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrCrc);
return true;
}
/// @brief Tests for correct response to an invalid opcpde.
bool MavlinkFtpTest::_bad_opcode_test(void)
{
@@ -191,7 +164,7 @@ bool MavlinkFtpTest::_list_test(void)
mavlink_file_transfer_protocol_t ftp_msg;
MavlinkFTP::PayloadHeader *reply;
char response1[] = "D.|Dempty_dir|Ftest_234.data\t234|Ftest_235.data\t235|Ftest_236.data\t236";
char response1[] = "D.|Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
char response2[] = "Ddev|Detc|Dfs|Dobj";
struct _testCase {
@@ -690,9 +663,6 @@ bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlin
*payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
// Make sure we have a good CRC
ut_compare("Incoming CRC mismatch", (*payload)->crc32, _payload_crc32((*payload)));
// Make sure we have a good sequence number
ut_compare("Sequence number mismatch", (*payload)->seqNumber, _lastOutgoingSeqNumber + 1);
@@ -702,21 +672,6 @@ bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlin
return true;
}
/// @brief Returns the 32 bit CRC for the payload, crc32 and padding are set to 0 for calculation.
uint32_t MavlinkFtpTest::_payload_crc32(struct MavlinkFTP::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(MavlinkFTP::PayloadHeader));
payload->crc32 = saveCRC;
return retCRC;
}
/// @brief Initializes an FTP message into a mavlink message
void MavlinkFtpTest::_setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
uint8_t size, ///< size in bytes of data
@@ -734,7 +689,8 @@ void MavlinkFtpTest::_setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, /
memcpy(payload->data, data, size);
}
payload->crc32 = _payload_crc32(payload);
payload->padding[0] = 0;
payload->padding[1] = 0;
msg->checksum = 0;
mavlink_msg_file_transfer_protocol_pack(clientSystemId, // Sender system id
@@ -771,7 +727,6 @@ void MavlinkFtpTest::_cleanup_microsd(void)
void MavlinkFtpTest::runTests(void)
{
ut_run_test(_ack_test);
ut_run_test(_bad_crc_test);
ut_run_test(_bad_opcode_test);
ut_run_test(_bad_datasize_test);
ut_run_test(_list_test);
@@ -66,7 +66,6 @@ public:
private:
bool _ack_test(void);
bool _bad_crc_test(void);
bool _bad_opcode_test(void);
bool _bad_datasize_test(void);
bool _list_test(void);
@@ -81,7 +80,6 @@ private:
bool _removefile_test(void);
void _receive_message(const mavlink_message_t *msg);
uint32_t _payload_crc32(struct MavlinkFTP::PayloadHeader *payload);
void _setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, mavlink_message_t *msg);
bool _decode_message(const mavlink_message_t *msg, mavlink_file_transfer_protocol_t *ftp_msg, MavlinkFTP::PayloadHeader **payload);
bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,