43 #include "../mavlink_ftp.h" 46 #define PX4_MAVLINK_TEST_DATA_DIR "/etc" 48 #define PX4_MAVLINK_TEST_DATA_DIR "etc" 53 {
PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/test_238.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN -
sizeof(MavlinkFTP::PayloadHeader) - 1,
true,
false },
54 {
PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/test_239.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN -
sizeof(MavlinkFTP::PayloadHeader),
true,
true },
55 {
PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN -
sizeof(MavlinkFTP::PayloadHeader) + 1,
false,
false },
63 _expected_seq_number(0),
89 MavlinkFTP::PayloadHeader payload;
90 const MavlinkFTP::PayloadHeader *reply;
104 ut_compare(
"Incorrect payload size", reply->size, 0);
112 MavlinkFTP::PayloadHeader payload;
113 const MavlinkFTP::PayloadHeader *reply;
115 payload.opcode = 0xFF;
127 ut_compare(
"Incorrect payload size", reply->size, 1);
136 mavlink_message_t
msg;
137 MavlinkFTP::PayloadHeader payload;
138 const MavlinkFTP::PayloadHeader *reply;
145 ((MavlinkFTP::PayloadHeader *)((mavlink_file_transfer_protocol_t *)msg.payload64)->payload)->size =
146 MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN + 1;
155 ut_compare(
"Incorrect payload size", reply->size, 1);
163 MavlinkFTP::PayloadHeader payload;
164 const MavlinkFTP::PayloadHeader *reply;
166 char response1[] =
"Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
169 char response2[] =
"Ddev|Detc|Dfs|Dobj";
178 struct _testCase rgTestCases[] = {
179 {
"/bogus",
nullptr, 0,
false },
183 {
"/", response2, 4,
true },
187 for (
size_t i = 0; i <
sizeof(rgTestCases) /
sizeof(rgTestCases[0]); i++) {
188 const struct _testCase *
test = &rgTestCases[i];
194 strlen(test->dir) + 1,
195 (uint8_t *)test->dir,
204 ut_compare(
"Incorrect payload size", reply->size, strlen(test->response) + 1);
210 char list_entry[256];
212 for (uint8_t j = 0; j < reply->size - 1; j++) {
213 if (reply->data[j] == 0) {
217 list_entry[j] = reply->data[j];
221 list_entry[reply->size - 1] = 0;
225 int response_count = 0;
226 dir = strtok(list_entry,
"|");
228 while (dir !=
nullptr) {
229 ut_assert(
"Returned directory not found in expected response", strstr(test->response, dir));
231 dir = strtok(
nullptr,
"|");
234 ut_compare(
"Incorrect number of directory entires returned", test->response_count, response_count);
238 ut_compare(
"Incorrect payload size", reply->size, 2);
250 MavlinkFTP::PayloadHeader payload;
251 const MavlinkFTP::PayloadHeader *reply;
252 const char *dir =
"/";
267 ut_compare(
"Incorrect payload size", reply->size, 1);
276 MavlinkFTP::PayloadHeader payload;
277 const MavlinkFTP::PayloadHeader *reply;
278 const char *dir =
"/foo";
293 ut_compare(
"Incorrect payload size", reply->size, 2);
302 MavlinkFTP::PayloadHeader payload;
303 const MavlinkFTP::PayloadHeader *reply;
313 strlen(test->file) + 1,
314 (uint8_t *)test->file,
321 ut_compare(
"stat failed", stat(test->file, &st), 0);
324 ut_compare(
"Incorrect payload size", reply->size,
sizeof(uint32_t));
325 ut_compare(
"File size incorrect", *((uint32_t *)&reply->data[0]), (uint32_t)st.st_size);
328 payload.session = reply->session;
341 ut_compare(
"Incorrect payload size", reply->size, 0);
350 MavlinkFTP::PayloadHeader payload;
351 const MavlinkFTP::PayloadHeader *reply;
369 payload.session = reply->session + 1;
382 ut_compare(
"Incorrect payload size", reply->size, 1);
391 MavlinkFTP::PayloadHeader payload;
392 const MavlinkFTP::PayloadHeader *reply;
399 ut_compare(
"stat failed", stat(test->file, &st), 0);
400 uint8_t *bytes =
new uint8_t[st.st_size];
401 ut_assert(
"new failed", bytes !=
nullptr);
402 int fd = ::open(test->file, O_RDONLY);
404 int bytes_read =
::read(fd, bytes, st.st_size);
405 ut_compare(
"read failed", bytes_read, st.st_size);
409 ut_compare(
"Test case data files are out of date", test->length, st.st_size);
415 strlen(test->file) + 1,
416 (uint8_t *)test->file,
427 payload.session = reply->session;
441 ut_compare(
"Offset incorrect", reply->offset, 0);
443 uint32_t full_packet_bytes = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN -
sizeof(MavlinkFTP::PayloadHeader);
444 uint32_t expected_bytes = test->singlePacketRead ? (uint32_t)st.st_size : full_packet_bytes;
445 ut_compare(
"Payload size incorrect", reply->size, expected_bytes);
446 ut_compare(
"File contents differ", memcmp(reply->data, bytes, expected_bytes), 0);
448 payload.offset += expected_bytes;
450 if (test->singlePacketRead) {
476 ut_compare(
"Offset incorrect", reply->offset, payload.offset);
478 expected_bytes = (uint32_t)st.st_size - full_packet_bytes;
479 ut_compare(
"Payload size incorrect", reply->size, expected_bytes);
480 ut_compare(
"File contents differ", memcmp(reply->data, &bytes[payload.offset], expected_bytes), 0);
484 payload.session = reply->session;
498 ut_compare(
"Incorrect payload size", reply->size, 0);
510 MavlinkFTP::PayloadHeader payload;
511 const MavlinkFTP::PayloadHeader *reply;
521 ut_compare(
"stat failed", stat(test->file, &st), 0);
522 uint8_t *bytes =
new uint8_t[st.st_size];
523 ut_assert(
"new failed", bytes !=
nullptr);
524 int fd = ::open(test->file, O_RDONLY);
526 int bytes_read =
::read(fd, bytes, st.st_size);
527 ut_compare(
"read failed", bytes_read, st.st_size);
531 ut_compare(
"Test case data files are out of date", test->length, st.st_size);
537 strlen(test->file) + 1,
538 (uint8_t *)test->file,
558 payload.session = reply->session;
561 mavlink_message_t
msg;
576 payload.session = reply->session;
590 ut_compare(
"Incorrect payload size", reply->size, 0);
602 MavlinkFTP::PayloadHeader payload;
603 const MavlinkFTP::PayloadHeader *reply;
621 payload.session = reply->session + 1;
634 ut_compare(
"Incorrect payload size", reply->size, 1);
642 MavlinkFTP::PayloadHeader payload;
643 const MavlinkFTP::PayloadHeader *reply;
651 static const struct _testCase rgTestCases[] = {
652 {
"/bogus",
false,
false },
663 for (
size_t i = 0; i <
sizeof(rgTestCases) /
sizeof(rgTestCases[0]); i++) {
664 const struct _testCase *
test = &rgTestCases[i];
666 if (test->deleteFile) {
674 strlen(test->dir) + 1,
675 (uint8_t *)test->dir,
684 ut_compare(
"Incorrect payload size", reply->size, 0);
688 ut_compare(
"Incorrect payload size", reply->size, 2);
698 MavlinkFTP::PayloadHeader payload;
699 const MavlinkFTP::PayloadHeader *reply;
706 static const struct _testCase rgTestCases[] = {
707 {
"/etc/bogus",
false,
false },
710 {
"/fs/microsd/bogus/bogus",
false,
false },
713 for (
size_t i = 0; i <
sizeof(rgTestCases) /
sizeof(rgTestCases[0]); i++) {
714 const struct _testCase *
test = &rgTestCases[i];
720 strlen(test->dir) + 1,
721 (uint8_t *)test->dir,
730 ut_compare(
"Incorrect payload size", reply->size, 0);
732 }
else if (test->fail_exists) {
734 ut_compare(
"Incorrect payload size", reply->size, 1);
739 ut_compare(
"Incorrect payload size", reply->size, 2);
749 MavlinkFTP::PayloadHeader payload;
750 const MavlinkFTP::PayloadHeader *reply;
757 static const struct _testCase rgTestCases[] = {
772 for (
size_t i = 0; i <
sizeof(rgTestCases) /
sizeof(rgTestCases[0]); i++) {
773 const struct _testCase *
test = &rgTestCases[i];
779 strlen(test->file) + 1,
780 (uint8_t *)test->file,
789 ut_compare(
"Incorrect payload size", reply->size, 0);
793 ut_compare(
"Incorrect payload size", reply->size, 2);
805 ((
MavlinkFtpTest *)worker_data)->_receive_message_handler_generic(ftp_req);
811 memcpy(&
_reply_msg, ftp_req,
sizeof(mavlink_file_transfer_protocol_t));
826 const MavlinkFTP::PayloadHeader *reply;
827 uint32_t full_packet_bytes = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN -
sizeof(MavlinkFTP::PayloadHeader);
828 uint32_t expected_bytes;
835 ut_compare(
"Offset incorrect", reply->offset, 0);
838 ut_compare(
"Payload size incorrect", reply->size, expected_bytes);
839 ut_compare(
"burst_complete incorrect", reply->burst_complete, 0);
840 ut_compare(
"File contents differ", memcmp(reply->data, burst_info->
file_bytes, expected_bytes), 0);
851 ut_compare(
"Offset incorrect", reply->offset, full_packet_bytes);
853 expected_bytes = burst_info->
file_size - full_packet_bytes;
854 ut_compare(
"Payload size incorrect", reply->size, expected_bytes);
855 ut_compare(
"burst_complete incorrect", reply->burst_complete, 0);
856 ut_compare(
"File contents differ", memcmp(reply->data, &burst_info->
file_bytes[full_packet_bytes], expected_bytes), 0);
878 const MavlinkFTP::PayloadHeader **payload)
883 ut_compare(
"Target network non-zero", ftp_msg->target_network, 0);
887 *payload =
reinterpret_cast<const MavlinkFTP::PayloadHeader *
>(ftp_msg->payload);
900 mavlink_message_t *
msg)
902 uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN];
903 MavlinkFTP::PayloadHeader *payload =
reinterpret_cast<MavlinkFTP::PayloadHeader *
>(payload_bytes);
905 memcpy(payload, payload_header,
sizeof(MavlinkFTP::PayloadHeader));
908 payload->size = size;
911 memcpy(payload->data, data, size);
914 payload->burst_complete = 0;
915 payload->padding = 0;
931 const MavlinkFTP::PayloadHeader **payload_reply)
933 mavlink_message_t
msg;
Session is not currently open.
#define ut_declare_test(test_function, test_class)
Macro to create a function which will run a unit test class and print results.
MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL mes...
static void receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
Static method used as callback from MavlinkFTP for generic use.
bool _receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_req, BurstInfo *burst_info)
void _receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req)
Removes Directory at <path>, must be empty.
bool _decode_message(const mavlink_file_transfer_protocol_t *ftp_msg, const MavlinkFTP::PayloadHeader **payload)
Decode and validate the incoming message.
uint16_t _expected_seq_number
void _cleanup_microsd(void)
Cleans up an files created on microsd during testing.
void send(const hrt_abstime t)
Handle sending of messages.
virtual void _cleanup(void)
Called after every test to take down the FTP Server.
static const char _unittest_microsd_file[]
static const uint8_t clientSystemId
System ID for client.
bool _list_eof_test(void)
Tests for correct response to a List command on a valid directory, but with an offset that is beyond ...
bool _open_badfile_test(void)
Tests for correct response to an Open command on a file which does not exist.
Terminates open Read session.
static const char _unittest_microsd_dir[]
#define PX4_MAVLINK_TEST_DATA_DIR
bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, const MavlinkFTP::PayloadHeader **payload_reply)
Sends the specified FTP message to the server and returns response.
void _setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, mavlink_message_t *msg)
Initializes an FTP message into a mavlink message.
Reads <size> bytes from <offset> in <session>
bool _read_test(void)
Tests for correct reponse to a Read command on an open session.
Worker data for stream handler.
static void receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
Static method used as callback from MavlinkFTP for stream download testing.
bool _removedirectory_test(void)
virtual void _init(void)
Called before every test to initialize the FTP Server.
PayloadHeader.size is invalid.
MavlinkFtpTest * ftp_test_class
int _tests_failed
The number of unit tests which failed.
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
static void read(bootloader_app_shared_t *pshared)
static const uint8_t clientComponentId
Component ID for client.
Command failed, errno sent back in PayloadHeader.data[1].
#define ut_assert(message, test)
Used to assert a value within a unit test.
bool _bad_opcode_test(void)
Tests for correct response to an invalid opcpde.
List files in <path> from <offset>
bool mavlink_ftp_test(void)
void test(enum LPS25H_BUS busid)
Perform some basic functional tests on the driver; make sure we can collect data from the sensor in p...
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
mavlink_file_transfer_protocol_t _reply_msg
void handle_message(const mavlink_message_t *msg)
Handle possible FTP message.
bool _removefile_test(void)
static const DownloadTestCase _rgDownloadTestCases[]
The set of test cases for download testing.
Creates directory at <path>
bool _bad_datasize_test(void)
Tests for correct reponse to a payload which an invalid data size field.
void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, void *worker_data)
Sets up the server to run in unit test mode.
bool _open_terminate_test(void)
Tests for correct reponse to an Open command on a file, followed by Terminate.
struct @83::@85::@87 file
#define ut_compare(message, v1, v2)
Used to compare two integer values within a unit test.
#define ut_run_test(test)
Runs a single unit test.
virtual bool run_tests(void)
Runs all the unit tests.
Offset past end of file for List and Read commands.
bool _createdirectory_test(void)
Opens file at <path> for reading, returns <session>
bool _terminate_badsession_test(void)
Tests for correct reponse to a Terminate command on an invalid session.
bool _ack_test(void)
Tests for correct behavior of an Ack response.
Burst download session file.
bool _read_badsession_test(void)
Tests for correct reponse to a Read command on an invalid session.
static const uint8_t serverSystemId
System ID for server.
A single download test case.
bool _burst_test(void)
Tests for correct reponse to a Read command on an open session.
static const uint8_t serverComponentId
Component ID for server.