Browse Source

mavlink_ftp: fix tests after implementation fix

In commit 462b572172 the reading operation
on the PX4 side was changed to only read as many bytes as requested
rather than however many fit in the payload data.

This caused the unit tests to fail which this commit here aims to fix.

What is confusing about MAVLink FTP is that there is a size field which
generally signals how many bytes of the payload data are used/set.

However, in the case of a read requst, the size field is used to
indicate how many bytes should be read. The payload data is empty in
that case though.

This case was, from how I understand it, not implemented/tested in the
unit tests and now failed. In order to implement it I had to change a
few things:
- Change _setup_ftp_msg and _send_receive_msg so that the params contain
  a data length rather than the size field. The size field itself needs
  to be set outside of these methods using payload->size.
- Since we test files smaller, equal, and bigger than one payload data
  length, I implemented that we send multiple read requests until we
  have the whole file and not just the first part.
- Additionally, I saw a lot of uninitialized warnings in valgrind, and
  got rid of them by adding a few zero initializations.
master
Julian Oes 3 years ago committed by Daniel Agar
parent
commit
7c90b06628
  1. 2
      src/modules/mavlink/mavlink_ftp.cpp
  2. 175
      src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
  3. 5
      src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h

2
src/modules/mavlink/mavlink_ftp.cpp

@ -165,7 +165,7 @@ MavlinkFTP::_process_request( @@ -165,7 +165,7 @@ MavlinkFTP::_process_request(
// basic sanity checks; must validate length before use
if (payload->size > kMaxDataLength) {
errorCode = kErrInvalidDataSize;
PX4_WARN("invalid data size");
PX4_WARN("invalid data size: %d", payload->size);
goto out;
}

175
src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp

@ -1,6 +1,6 @@ @@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (C) 2014-2020 PX4 Development Team. All rights reserved.
* Copyright (C) 2014-2021 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -54,10 +54,13 @@ static const char *_test_files[] = { @@ -54,10 +54,13 @@ static const char *_test_files[] = {
PX4_MAVLINK_TEST_DATA_DIR "/" "test_240.data"
};
constexpr uint32_t MAX_DATA_LEN = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(
MavlinkFTP::PayloadHeader);
const MavlinkFtpTest::DownloadTestCase MavlinkFtpTest::_rgDownloadTestCases[] = {
{ _test_files[0], MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1, true, false }, // Read takes less than single packet
{ _test_files[1], MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader), true, true }, // Read completely fills single packet
{ _test_files[2], MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1, false, false }, // Read take two packets
{ _test_files[0], MAX_DATA_LEN - 1, true, false }, // Read takes less than single packet
{ _test_files[1], MAX_DATA_LEN, true, true }, // Read completely fills single packet
{ _test_files[2], MAX_DATA_LEN + 1, false, false }, // Read take two packets
};
const char MavlinkFtpTest::_unittest_microsd_dir[] = PX4_STORAGEDIR "/ftp_unit_test_dir";
@ -144,14 +147,15 @@ bool MavlinkFtpTest::_remove_test_files() @@ -144,14 +147,15 @@ bool MavlinkFtpTest::_remove_test_files()
/// @brief Tests for correct behavior of an Ack response.
bool MavlinkFtpTest::_ack_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
payload.opcode = MavlinkFTP::kCmdNone;
payload.size = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -167,14 +171,15 @@ bool MavlinkFtpTest::_ack_test() @@ -167,14 +171,15 @@ bool MavlinkFtpTest::_ack_test()
/// @brief Tests for correct response to an invalid opcode.
bool MavlinkFtpTest::_bad_opcode_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
payload.opcode = 0xFF; // bogus opcode
payload.size = 0;
bool success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -192,12 +197,13 @@ bool MavlinkFtpTest::_bad_opcode_test() @@ -192,12 +197,13 @@ bool MavlinkFtpTest::_bad_opcode_test()
bool MavlinkFtpTest::_bad_datasize_test()
{
mavlink_message_t msg;
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
payload.opcode = MavlinkFTP::kCmdListDirectory;
payload.size = 42; // This has to be greater than 0, otherwise everything including the size field gets truncated.
_setup_ftp_msg(&payload, 0, nullptr, &msg);
_setup_ftp_msg(&payload, nullptr, 0, &msg);
// Set the data size to be one larger than is legal
((MavlinkFTP::PayloadHeader *)((mavlink_file_transfer_protocol_t *)msg.payload64)->payload)->size =
@ -218,7 +224,7 @@ bool MavlinkFtpTest::_bad_datasize_test() @@ -218,7 +224,7 @@ bool MavlinkFtpTest::_bad_datasize_test()
bool MavlinkFtpTest::_list_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
struct _testCase {
@ -241,10 +247,11 @@ bool MavlinkFtpTest::_list_test() @@ -241,10 +247,11 @@ bool MavlinkFtpTest::_list_test()
payload.opcode = MavlinkFTP::kCmdListDirectory;
payload.offset = 0;
payload.size = strlen(test->dir) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->dir) + 1, // size in bytes of data
(uint8_t *)test->dir, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -299,7 +306,7 @@ bool MavlinkFtpTest::_list_test() @@ -299,7 +306,7 @@ bool MavlinkFtpTest::_list_test()
/// is beyond the last directory entry.
bool MavlinkFtpTest::_list_eof_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
const char *dir = PX4_MAVLINK_TEST_DATA_DIR;
@ -309,10 +316,11 @@ bool MavlinkFtpTest::_list_eof_test() @@ -309,10 +316,11 @@ bool MavlinkFtpTest::_list_eof_test()
#else
payload.offset = 6; // (3 test files, 1 test folder, two skipped ./..)
#endif
payload.size = strlen(dir) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(dir) + 1, // size in bytes of data
(uint8_t *)dir, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -329,16 +337,17 @@ bool MavlinkFtpTest::_list_eof_test() @@ -329,16 +337,17 @@ bool MavlinkFtpTest::_list_eof_test()
/// @brief Tests for correct response to an Open command on a file which does not exist.
bool MavlinkFtpTest::_open_badfile_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
const char *dir = "/foo"; // non-existent file
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(dir) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(dir) + 1, // size in bytes of data
(uint8_t *)dir, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -355,7 +364,7 @@ bool MavlinkFtpTest::_open_badfile_test() @@ -355,7 +364,7 @@ bool MavlinkFtpTest::_open_badfile_test()
/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
bool MavlinkFtpTest::_open_terminate_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
@ -364,10 +373,11 @@ bool MavlinkFtpTest::_open_terminate_test() @@ -364,10 +373,11 @@ bool MavlinkFtpTest::_open_terminate_test()
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(test->file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->file) + 1, // size in bytes of data
(uint8_t *)test->file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -385,8 +395,8 @@ bool MavlinkFtpTest::_open_terminate_test() @@ -385,8 +395,8 @@ bool MavlinkFtpTest::_open_terminate_test()
payload.size = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -403,16 +413,17 @@ bool MavlinkFtpTest::_open_terminate_test() @@ -403,16 +413,17 @@ bool MavlinkFtpTest::_open_terminate_test()
/// @brief Tests for correct reponse to a Terminate command on an invalid session.
bool MavlinkFtpTest::_terminate_badsession_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
const char *file = _rgDownloadTestCases[0].file;
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(file) + 1, // size in bytes of data
(uint8_t *)file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -426,8 +437,8 @@ bool MavlinkFtpTest::_terminate_badsession_test() @@ -426,8 +437,8 @@ bool MavlinkFtpTest::_terminate_badsession_test()
payload.size = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -444,7 +455,7 @@ bool MavlinkFtpTest::_terminate_badsession_test() @@ -444,7 +455,7 @@ bool MavlinkFtpTest::_terminate_badsession_test()
/// @brief Tests for correct reponse to a Read command on an open session.
bool MavlinkFtpTest::_read_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
@ -466,10 +477,11 @@ bool MavlinkFtpTest::_read_test() @@ -466,10 +477,11 @@ bool MavlinkFtpTest::_read_test()
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(test->file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->file) + 1, // size in bytes of data
(uint8_t *)test->file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -483,44 +495,20 @@ bool MavlinkFtpTest::_read_test() @@ -483,44 +495,20 @@ bool MavlinkFtpTest::_read_test()
payload.session = reply->session;
payload.offset = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
&reply); // Payload inside FTP message response
if (!success) {
delete[] bytes;
return false;
}
ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
ut_compare("Offset incorrect", reply->offset, 0);
ut_compare("Reply containing file size wrong", reply->size, sizeof(uint32_t));
const uint32_t size = *reinterpret_cast<const uint32_t *>(&reply->data[0]);
uint32_t full_packet_bytes = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader);
uint32_t expected_bytes = test->singlePacketRead ? (uint32_t)st.st_size : full_packet_bytes;
ut_compare("Payload size incorrect", reply->size, expected_bytes);
ut_compare("File contents differ", memcmp(reply->data, bytes, expected_bytes), 0);
// We need to download multiple packets until done.
while (payload.offset < size) {
payload.offset += expected_bytes;
// Setting this size is slightly odd as we are not actually sending a payload but
// use it to communicate how many bytes we want to read.
// Also, we can only request what actually fits in the payload.
payload.size = size - payload.offset > MAX_DATA_LEN ? MAX_DATA_LEN : size - payload.offset;
if (test->singlePacketRead) {
// Try going past EOF
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
&reply); // Payload inside FTP message response
if (!success) {
delete[] bytes;
return false;
}
ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
} else {
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
&reply); // Payload inside FTP message response
if (!success) {
@ -531,18 +519,21 @@ bool MavlinkFtpTest::_read_test() @@ -531,18 +519,21 @@ bool MavlinkFtpTest::_read_test()
ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
ut_compare("Offset incorrect", reply->offset, payload.offset);
expected_bytes = (uint32_t)st.st_size - full_packet_bytes;
ut_compare("Payload size incorrect", reply->size, expected_bytes);
ut_compare("File contents differ", memcmp(reply->data, &bytes[payload.offset], expected_bytes), 0);
ut_compare("Payload size incorrect", reply->size, payload.size);
ut_compare("Payload content differs", memcmp(reply->data, bytes + payload.offset, reply->size), 0);
payload.offset += reply->size;
}
ut_compare("File size overall not correct", payload.offset, size);
payload.opcode = MavlinkFTP::kCmdTerminateSession;
payload.session = reply->session;
payload.size = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -563,7 +554,7 @@ bool MavlinkFtpTest::_read_test() @@ -563,7 +554,7 @@ bool MavlinkFtpTest::_read_test()
/// @brief Tests for correct reponse to a Read command on an open session.
bool MavlinkFtpTest::_burst_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
BurstInfo burst_info;
@ -588,10 +579,11 @@ bool MavlinkFtpTest::_burst_test() @@ -588,10 +579,11 @@ bool MavlinkFtpTest::_burst_test()
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(test->file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->file) + 1, // size in bytes of data
(uint8_t *)test->file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -613,9 +605,10 @@ bool MavlinkFtpTest::_burst_test() @@ -613,9 +605,10 @@ bool MavlinkFtpTest::_burst_test()
payload.opcode = MavlinkFTP::kCmdBurstReadFile;
payload.session = reply->session;
payload.offset = 0;
payload.size = MAX_DATA_LEN;
mavlink_message_t msg;
_setup_ftp_msg(&payload, 0, nullptr, &msg);
_setup_ftp_msg(&payload, nullptr, 0, &msg);
_ftp_server->handle_message(&msg);
// First packet is sent using stream mechanism, so we need to force it out ourselves
@ -632,8 +625,8 @@ bool MavlinkFtpTest::_burst_test() @@ -632,8 +625,8 @@ bool MavlinkFtpTest::_burst_test()
payload.size = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -654,16 +647,17 @@ bool MavlinkFtpTest::_burst_test() @@ -654,16 +647,17 @@ bool MavlinkFtpTest::_burst_test()
/// @brief Tests for correct reponse to a Read command on an invalid session.
bool MavlinkFtpTest::_read_badsession_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
const char *file = _rgDownloadTestCases[0].file;
payload.opcode = MavlinkFTP::kCmdOpenFileRO;
payload.offset = 0;
payload.size = strlen(file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(file) + 1, // size in bytes of data
(uint8_t *)file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -677,8 +671,8 @@ bool MavlinkFtpTest::_read_badsession_test() @@ -677,8 +671,8 @@ bool MavlinkFtpTest::_read_badsession_test()
payload.offset = 0;
success = _send_receive_msg(&payload, // FTP payload header
0, // size in bytes of data
nullptr, // Data to start into FTP message payload
0, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -694,7 +688,7 @@ bool MavlinkFtpTest::_read_badsession_test() @@ -694,7 +688,7 @@ bool MavlinkFtpTest::_read_badsession_test()
bool MavlinkFtpTest::_removedirectory_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
int fd;
@ -725,10 +719,11 @@ bool MavlinkFtpTest::_removedirectory_test() @@ -725,10 +719,11 @@ bool MavlinkFtpTest::_removedirectory_test()
payload.opcode = MavlinkFTP::kCmdRemoveDirectory;
payload.offset = 0;
payload.size = strlen(test->dir) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->dir) + 1, // size in bytes of data
(uint8_t *)test->dir, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -751,7 +746,7 @@ bool MavlinkFtpTest::_removedirectory_test() @@ -751,7 +746,7 @@ bool MavlinkFtpTest::_removedirectory_test()
bool MavlinkFtpTest::_createdirectory_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
struct _testCase {
@ -775,10 +770,11 @@ bool MavlinkFtpTest::_createdirectory_test() @@ -775,10 +770,11 @@ bool MavlinkFtpTest::_createdirectory_test()
payload.opcode = MavlinkFTP::kCmdCreateDirectory;
payload.offset = 0;
payload.size = strlen(test->dir) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->dir) + 1, // size in bytes of data
(uint8_t *)test->dir, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -801,7 +797,7 @@ bool MavlinkFtpTest::_createdirectory_test() @@ -801,7 +797,7 @@ bool MavlinkFtpTest::_createdirectory_test()
bool MavlinkFtpTest::_removefile_test()
{
MavlinkFTP::PayloadHeader payload;
MavlinkFTP::PayloadHeader payload {};
const MavlinkFTP::PayloadHeader *reply;
int fd;
@ -827,10 +823,11 @@ bool MavlinkFtpTest::_removefile_test() @@ -827,10 +823,11 @@ bool MavlinkFtpTest::_removefile_test()
payload.opcode = MavlinkFTP::kCmdRemoveFile;
payload.offset = 0;
payload.size = strlen(test->file) + 1;
bool success = _send_receive_msg(&payload, // FTP payload header
strlen(test->file) + 1, // size in bytes of data
(uint8_t *)test->file, // Data to start into FTP message payload
payload.size, // size in bytes of data
&reply); // Payload inside FTP message response
if (!success) {
@ -876,7 +873,6 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_ @@ -876,7 +873,6 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_
BurstInfo *burst_info)
{
const MavlinkFTP::PayloadHeader *reply{nullptr};
uint32_t full_packet_bytes = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader);
uint32_t expected_bytes;
_decode_message(ftp_msg, &reply);
@ -886,7 +882,7 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_ @@ -886,7 +882,7 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_
ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
ut_compare("Offset incorrect", reply->offset, 0);
expected_bytes = burst_info->single_packet_file ? burst_info->file_size : full_packet_bytes;
expected_bytes = burst_info->single_packet_file ? burst_info->file_size : MAX_DATA_LEN;
ut_compare("Payload size incorrect", reply->size, expected_bytes);
ut_compare("burst_complete incorrect", reply->burst_complete, 0);
ut_compare("File contents differ", memcmp(reply->data, burst_info->file_bytes, expected_bytes), 0);
@ -900,12 +896,12 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_ @@ -900,12 +896,12 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_
case burst_state_last_ack:
ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
ut_compare("Offset incorrect", reply->offset, full_packet_bytes);
ut_compare("Offset incorrect", reply->offset, MAX_DATA_LEN);
expected_bytes = burst_info->file_size - full_packet_bytes;
expected_bytes = burst_info->file_size - MAX_DATA_LEN;
ut_compare("Payload size incorrect", reply->size, expected_bytes);
ut_compare("burst_complete incorrect", reply->burst_complete, 0);
ut_compare("File contents differ", memcmp(reply->data, &burst_info->file_bytes[full_packet_bytes], expected_bytes), 0);
ut_compare("File contents differ", memcmp(reply->data, &burst_info->file_bytes[MAX_DATA_LEN], expected_bytes), 0);
// Setup for next expected message
burst_info->burst_state = burst_state_nak_eof;
@ -929,8 +925,6 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_ @@ -929,8 +925,6 @@ bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_
bool MavlinkFtpTest::_decode_message(const mavlink_file_transfer_protocol_t *ftp_msg, ///< Incoming FTP message
const MavlinkFTP::PayloadHeader **payload) ///< Payload inside FTP message response
{
//warnx("_decode_message");
// Make sure the targets are correct
ut_compare("Target network non-zero", ftp_msg->target_network, 0);
ut_compare("Target system id mismatch", ftp_msg->target_system, clientSystemId);
@ -946,21 +940,21 @@ bool MavlinkFtpTest::_decode_message(const mavlink_file_transfer_protocol_t *ftp @@ -946,21 +940,21 @@ bool MavlinkFtpTest::_decode_message(const mavlink_file_transfer_protocol_t *ftp
}
/// @brief Initializes an FTP message into a mavlink message
void MavlinkFtpTest::_setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
uint8_t size, ///< size in bytes of data
bool MavlinkFtpTest::_setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
const uint8_t *data, ///< Data to start into FTP message payload
const uint8_t data_len, ///< Data len
mavlink_message_t *msg) ///< Returned mavlink message
{
uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN];
uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN] = {};
MavlinkFTP::PayloadHeader *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(payload_bytes);
memcpy(payload, payload_header, sizeof(MavlinkFTP::PayloadHeader));
payload->seq_number = _expected_seq_number++;
payload->size = size;
if (size != 0) {
memcpy(payload->data, data, size);
if (data_len != 0) {
ut_assert("payload size incorrect", data_len == payload->size);
memcpy(payload->data, data, data_len);
}
payload->burst_complete = 0;
@ -974,17 +968,22 @@ void MavlinkFtpTest::_setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_hea @@ -974,17 +968,22 @@ void MavlinkFtpTest::_setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_hea
serverSystemId, // Target system id
serverComponentId, // Target component id
payload_bytes); // Payload to pack into message
return true;
}
/// @brief Sends the specified FTP message to the server and returns response
bool MavlinkFtpTest::_send_receive_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
uint8_t size, ///< size in bytes of data
const uint8_t *data, ///< Data to start into FTP message payload
const size_t data_len, ///< Size of data
const MavlinkFTP::PayloadHeader **payload_reply) ///< Payload inside FTP message response
{
mavlink_message_t msg;
_setup_ftp_msg(payload_header, size, data, &msg);
ut_assert("data_len out of range", data_len < UINT8_MAX);
_setup_ftp_msg(payload_header, data, static_cast<uint8_t>(data_len), &msg);
_ftp_server->handle_message(&msg);
return _decode_message(&_reply_msg, payload_reply);
}

5
src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h

@ -98,12 +98,13 @@ private: @@ -98,12 +98,13 @@ private:
bool _removefile_test(void);
void _receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req);
void _setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data,
bool _setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header,
const uint8_t *data, const uint8_t data_len,
mavlink_message_t *msg);
bool _decode_message(const mavlink_file_transfer_protocol_t *ftp_msg, const MavlinkFTP::PayloadHeader **payload);
bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,
uint8_t size,
const uint8_t *data,
const size_t data_len,
const MavlinkFTP::PayloadHeader **payload_reply);
void _cleanup_microsd(void);

Loading…
Cancel
Save