PX4 Firmware
PX4 Autopilot Software http://px4.io
mavlink_ftp_test.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (C) 2014 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /// @file mavlink_ftp_test.cpp
35 /// @author Don Gagne <don@thegagnes.com>
36 
37 #include <sys/stat.h>
38 #include <crc32.h>
39 #include <stdio.h>
40 #include <fcntl.h>
41 
42 #include "mavlink_ftp_test.h"
43 #include "../mavlink_ftp.h"
44 
45 #ifdef __PX4_NUTTX
46 #define PX4_MAVLINK_TEST_DATA_DIR "/etc"
47 #else
48 #define PX4_MAVLINK_TEST_DATA_DIR "etc"
49 #endif
50 
51 /// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
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 }, // Read takes less than single packet
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 }, // Read completely fills single packet
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 }, // Read take two packets
56 };
57 
58 const char MavlinkFtpTest::_unittest_microsd_dir[] = PX4_STORAGEDIR "/ftp_unit_test_dir";
59 const char MavlinkFtpTest::_unittest_microsd_file[] = PX4_STORAGEDIR "/ftp_unit_test_dir/file";
60 
62  _ftp_server(nullptr),
63  _expected_seq_number(0),
64  _reply_msg{}
65 {
66 }
67 
68 /// @brief Called before every test to initialize the FTP Server.
70 {
72  _ftp_server = new MavlinkFTP(nullptr);
74 
76 }
77 
78 /// @brief Called after every test to take down the FTP Server.
80 {
81  delete _ftp_server;
82 
84 }
85 
86 /// @brief Tests for correct behavior of an Ack response.
88 {
89  MavlinkFTP::PayloadHeader payload;
90  const MavlinkFTP::PayloadHeader *reply;
91 
92  payload.opcode = MavlinkFTP::kCmdNone;
93 
94  bool success = _send_receive_msg(&payload, // FTP payload header
95  0, // size in bytes of data
96  nullptr, // Data to start into FTP message payload
97  &reply); // Payload inside FTP message response
98 
99  if (!success) {
100  return false;
101  }
102 
103  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
104  ut_compare("Incorrect payload size", reply->size, 0);
105 
106  return true;
107 }
108 
109 /// @brief Tests for correct response to an invalid opcpde.
111 {
112  MavlinkFTP::PayloadHeader payload;
113  const MavlinkFTP::PayloadHeader *reply;
114 
115  payload.opcode = 0xFF; // bogus opcode
116 
117  bool success = _send_receive_msg(&payload, // FTP payload header
118  0, // size in bytes of data
119  nullptr, // Data to start into FTP message payload
120  &reply); // Payload inside FTP message response
121 
122  if (!success) {
123  return false;
124  }
125 
126  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
127  ut_compare("Incorrect payload size", reply->size, 1);
128  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrUnknownCommand);
129 
130  return true;
131 }
132 
133 /// @brief Tests for correct reponse to a payload which an invalid data size field.
135 {
136  mavlink_message_t msg;
137  MavlinkFTP::PayloadHeader payload;
138  const MavlinkFTP::PayloadHeader *reply;
139 
140  payload.opcode = MavlinkFTP::kCmdListDirectory;
141 
142  _setup_ftp_msg(&payload, 0, nullptr, &msg);
143 
144  // Set the data size to be one larger than is legal
145  ((MavlinkFTP::PayloadHeader *)((mavlink_file_transfer_protocol_t *)msg.payload64)->payload)->size =
146  MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN + 1;
147 
149 
150  if (!_decode_message(&_reply_msg, &reply)) {
151  return false;
152  }
153 
154  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
155  ut_compare("Incorrect payload size", reply->size, 1);
156  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidDataSize);
157 
158  return true;
159 }
160 
162 {
163  MavlinkFTP::PayloadHeader payload;
164  const MavlinkFTP::PayloadHeader *reply;
165 
166  char response1[] = "Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
167 #ifdef __PX4_NUTTX
168  // expected directory layout only valid on nuttx
169  char response2[] = "Ddev|Detc|Dfs|Dobj";
170 #endif /* __PX4_NUTTX */
171 
172  struct _testCase {
173  const char *dir; ///< Directory to run List command on
174  char *response; ///< Expected response entries from List command
175  int response_count; ///< Number of directories that should be returned
176  bool success; ///< true: List command should succeed, false: List command should fail
177  };
178  struct _testCase rgTestCases[] = {
179  { "/bogus", nullptr, 0, false },
180  { PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests", response1, 4, true },
181 #ifdef __PX4_NUTTX
182  // expected directory layout only valid on nuttx
183  { "/", response2, 4, true },
184 #endif /* __PX4_NUTTX */
185  };
186 
187  for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
188  const struct _testCase *test = &rgTestCases[i];
189 
190  payload.opcode = MavlinkFTP::kCmdListDirectory;
191  payload.offset = 0;
192 
193  bool success = _send_receive_msg(&payload, // FTP payload header
194  strlen(test->dir) + 1, // size in bytes of data
195  (uint8_t *)test->dir, // Data to start into FTP message payload
196  &reply); // Payload inside FTP message response
197 
198  if (!success) {
199  return false;
200  }
201 
202  if (test->success) {
203  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
204  ut_compare("Incorrect payload size", reply->size, strlen(test->response) + 1);
205 
206  // The return order of directories from the List command is not repeatable. So we can't do a direct comparison
207  // to a hardcoded return result string.
208 
209  // Convert null terminators to seperator char so we can use strok to parse returned data
210  char list_entry[256];
211 
212  for (uint8_t j = 0; j < reply->size - 1; j++) {
213  if (reply->data[j] == 0) {
214  list_entry[j] = '|';
215 
216  } else {
217  list_entry[j] = reply->data[j];
218  }
219  }
220 
221  list_entry[reply->size - 1] = 0;
222 
223  // Loop over returned directory entries trying to find then in the response list
224  char *dir;
225  int response_count = 0;
226  dir = strtok(list_entry, "|");
227 
228  while (dir != nullptr) {
229  ut_assert("Returned directory not found in expected response", strstr(test->response, dir));
230  response_count++;
231  dir = strtok(nullptr, "|");
232  }
233 
234  ut_compare("Incorrect number of directory entires returned", test->response_count, response_count);
235 
236  } else {
237  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
238  ut_compare("Incorrect payload size", reply->size, 2);
239  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
240  }
241  }
242 
243  return true;
244 }
245 
246 /// @brief Tests for correct response to a List command on a valid directory, but with an offset that
247 /// is beyond the last directory entry.
249 {
250  MavlinkFTP::PayloadHeader payload;
251  const MavlinkFTP::PayloadHeader *reply;
252  const char *dir = "/";
253 
254  payload.opcode = MavlinkFTP::kCmdListDirectory;
255  payload.offset = 4; // offset past top level dirs
256 
257  bool success = _send_receive_msg(&payload, // FTP payload header
258  strlen(dir) + 1, // size in bytes of data
259  (uint8_t *)dir, // Data to start into FTP message payload
260  &reply); // Payload inside FTP message response
261 
262  if (!success) {
263  return false;
264  }
265 
266  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
267  ut_compare("Incorrect payload size", reply->size, 1);
268  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrEOF);
269 
270  return true;
271 }
272 
273 /// @brief Tests for correct response to an Open command on a file which does not exist.
275 {
276  MavlinkFTP::PayloadHeader payload;
277  const MavlinkFTP::PayloadHeader *reply;
278  const char *dir = "/foo"; // non-existent file
279 
280  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
281  payload.offset = 0;
282 
283  bool success = _send_receive_msg(&payload, // FTP payload header
284  strlen(dir) + 1, // size in bytes of data
285  (uint8_t *)dir, // Data to start into FTP message payload
286  &reply); // Payload inside FTP message response
287 
288  if (!success) {
289  return false;
290  }
291 
292  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
293  ut_compare("Incorrect payload size", reply->size, 2);
294  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
295 
296  return true;
297 }
298 
299 /// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
301 {
302  MavlinkFTP::PayloadHeader payload;
303  const MavlinkFTP::PayloadHeader *reply;
304 
305  for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
306  struct stat st;
308 
309  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
310  payload.offset = 0;
311 
312  bool success = _send_receive_msg(&payload, // FTP payload header
313  strlen(test->file) + 1, // size in bytes of data
314  (uint8_t *)test->file, // Data to start into FTP message payload
315  &reply); // Payload inside FTP message response
316 
317  if (!success) {
318  return false;
319  }
320 
321  ut_compare("stat failed", stat(test->file, &st), 0);
322 
323  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
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);
326 
327  payload.opcode = MavlinkFTP::kCmdTerminateSession;
328  payload.session = reply->session;
329  payload.size = 0;
330 
331  success = _send_receive_msg(&payload, // FTP payload header
332  0, // size in bytes of data
333  nullptr, // Data to start into FTP message payload
334  &reply); // Payload inside FTP message response
335 
336  if (!success) {
337  return false;
338  }
339 
340  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
341  ut_compare("Incorrect payload size", reply->size, 0);
342  }
343 
344  return true;
345 }
346 
347 /// @brief Tests for correct reponse to a Terminate command on an invalid session.
349 {
350  MavlinkFTP::PayloadHeader payload;
351  const MavlinkFTP::PayloadHeader *reply;
352  const char *file = _rgDownloadTestCases[0].file;
353 
354  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
355  payload.offset = 0;
356 
357  bool success = _send_receive_msg(&payload, // FTP payload header
358  strlen(file) + 1, // size in bytes of data
359  (uint8_t *)file, // Data to start into FTP message payload
360  &reply); // Payload inside FTP message response
361 
362  if (!success) {
363  return false;
364  }
365 
366  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
367 
368  payload.opcode = MavlinkFTP::kCmdTerminateSession;
369  payload.session = reply->session + 1;
370  payload.size = 0;
371 
372  success = _send_receive_msg(&payload, // FTP payload header
373  0, // size in bytes of data
374  nullptr, // Data to start into FTP message payload
375  &reply); // Payload inside FTP message response
376 
377  if (!success) {
378  return false;
379  }
380 
381  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
382  ut_compare("Incorrect payload size", reply->size, 1);
383  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
384 
385  return true;
386 }
387 
388 /// @brief Tests for correct reponse to a Read command on an open session.
390 {
391  MavlinkFTP::PayloadHeader payload;
392  const MavlinkFTP::PayloadHeader *reply;
393 
394  for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
395  struct stat st;
397 
398  // Read in the file so we can compare it to what we get back
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);
403  ut_assert("open failed", fd != -1);
404  int bytes_read = ::read(fd, bytes, st.st_size);
405  ut_compare("read failed", bytes_read, st.st_size);
406  ::close(fd);
407 
408  // Test case data files are created for specific boundary conditions
409  ut_compare("Test case data files are out of date", test->length, st.st_size);
410 
411  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
412  payload.offset = 0;
413 
414  bool success = _send_receive_msg(&payload, // FTP payload header
415  strlen(test->file) + 1, // size in bytes of data
416  (uint8_t *)test->file, // Data to start into FTP message payload
417  &reply); // Payload inside FTP message response
418 
419  if (!success) {
420  delete[] bytes;
421  return false;
422  }
423 
424  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
425 
426  payload.opcode = MavlinkFTP::kCmdReadFile;
427  payload.session = reply->session;
428  payload.offset = 0;
429 
430  success = _send_receive_msg(&payload, // FTP payload header
431  0, // size in bytes of data
432  nullptr, // Data to start into FTP message payload
433  &reply); // Payload inside FTP message response
434 
435  if (!success) {
436  delete[] bytes;
437  return false;
438  }
439 
440  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
441  ut_compare("Offset incorrect", reply->offset, 0);
442 
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);
447 
448  payload.offset += expected_bytes;
449 
450  if (test->singlePacketRead) {
451  // Try going past EOF
452  success = _send_receive_msg(&payload, // FTP payload header
453  0, // size in bytes of data
454  nullptr, // Data to start into FTP message payload
455  &reply); // Payload inside FTP message response
456 
457  if (!success) {
458  delete[] bytes;
459  return false;
460  }
461 
462  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
463 
464  } else {
465  success = _send_receive_msg(&payload, // FTP payload header
466  0, // size in bytes of data
467  nullptr, // Data to start into FTP message payload
468  &reply); // Payload inside FTP message response
469 
470  if (!success) {
471  delete[] bytes;
472  return false;
473  }
474 
475  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
476  ut_compare("Offset incorrect", reply->offset, payload.offset);
477 
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);
481  }
482 
483  payload.opcode = MavlinkFTP::kCmdTerminateSession;
484  payload.session = reply->session;
485  payload.size = 0;
486 
487  success = _send_receive_msg(&payload, // FTP payload header
488  0, // size in bytes of data
489  nullptr, // Data to start into FTP message payload
490  &reply); // Payload inside FTP message response
491 
492  if (!success) {
493  delete[] bytes;
494  return false;
495  }
496 
497  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
498  ut_compare("Incorrect payload size", reply->size, 0);
499 
500  delete[] bytes;
501  bytes = nullptr;
502  }
503 
504  return true;
505 }
506 
507 /// @brief Tests for correct reponse to a Read command on an open session.
509 {
510  MavlinkFTP::PayloadHeader payload;
511  const MavlinkFTP::PayloadHeader *reply;
512  BurstInfo burst_info;
513 
514 
515 
516  for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
517  struct stat st;
519 
520  // Read in the file so we can compare it to what we get back
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);
525  ut_assert("open failed", fd != -1);
526  int bytes_read = ::read(fd, bytes, st.st_size);
527  ut_compare("read failed", bytes_read, st.st_size);
528  ::close(fd);
529 
530  // Test case data files are created for specific boundary conditions
531  ut_compare("Test case data files are out of date", test->length, st.st_size);
532 
533  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
534  payload.offset = 0;
535 
536  bool success = _send_receive_msg(&payload, // FTP payload header
537  strlen(test->file) + 1, // size in bytes of data
538  (uint8_t *)test->file, // Data to start into FTP message payload
539  &reply); // Payload inside FTP message response
540 
541  if (!success) {
542  delete[] bytes;
543  return false;
544  }
545 
546  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
547 
548  // Setup for burst response handler
549  burst_info.burst_state = burst_state_first_ack;
550  burst_info.single_packet_file = test->singlePacketRead;
551  burst_info.file_size = st.st_size;
552  burst_info.file_bytes = bytes;
553  burst_info.ftp_test_class = this;
555 
556  // Send the burst command, message response will be handled by _receive_message_handler_stream
557  payload.opcode = MavlinkFTP::kCmdBurstReadFile;
558  payload.session = reply->session;
559  payload.offset = 0;
560 
561  mavlink_message_t msg;
562  _setup_ftp_msg(&payload, 0, nullptr, &msg);
564 
565  // First packet is sent using stream mechanism, so we need to force it out ourselves
566  hrt_abstime t = 0;
567  _ftp_server->send(t);
568 
569  ut_compare("Incorrect sequence of messages", burst_info.burst_state, burst_state_complete);
570 
571  // Put back generic message handler
573 
574  // Terminate session
575  payload.opcode = MavlinkFTP::kCmdTerminateSession;
576  payload.session = reply->session;
577  payload.size = 0;
578 
579  success = _send_receive_msg(&payload, // FTP payload header
580  0, // size in bytes of data
581  nullptr, // Data to start into FTP message payload
582  &reply); // Payload inside FTP message response
583 
584  if (!success) {
585  delete[] bytes;
586  return false;
587  }
588 
589  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
590  ut_compare("Incorrect payload size", reply->size, 0);
591 
592  delete[] bytes;
593  bytes = nullptr;
594  }
595 
596  return true;
597 }
598 
599 /// @brief Tests for correct reponse to a Read command on an invalid session.
601 {
602  MavlinkFTP::PayloadHeader payload;
603  const MavlinkFTP::PayloadHeader *reply;
604  const char *file = _rgDownloadTestCases[0].file;
605 
606  payload.opcode = MavlinkFTP::kCmdOpenFileRO;
607  payload.offset = 0;
608 
609  bool success = _send_receive_msg(&payload, // FTP payload header
610  strlen(file) + 1, // size in bytes of data
611  (uint8_t *)file, // Data to start into FTP message payload
612  &reply); // Payload inside FTP message response
613 
614  if (!success) {
615  return false;
616  }
617 
618  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
619 
620  payload.opcode = MavlinkFTP::kCmdReadFile;
621  payload.session = reply->session + 1; // Invalid session
622  payload.offset = 0;
623 
624  success = _send_receive_msg(&payload, // FTP payload header
625  0, // size in bytes of data
626  nullptr, // Data to start into FTP message payload
627  &reply); // Payload inside FTP message response
628 
629  if (!success) {
630  return false;
631  }
632 
633  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
634  ut_compare("Incorrect payload size", reply->size, 1);
635  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrInvalidSession);
636 
637  return true;
638 }
639 
641 {
642  MavlinkFTP::PayloadHeader payload;
643  const MavlinkFTP::PayloadHeader *reply;
644  int fd;
645 
646  struct _testCase {
647  const char *dir;
648  bool success;
649  bool deleteFile;
650  };
651  static const struct _testCase rgTestCases[] = {
652  { "/bogus", false, false },
653  { PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/empty_dir", false, false },
654  { _unittest_microsd_dir, false, false },
655  { _unittest_microsd_file, false, false },
656  { _unittest_microsd_dir, true, true },
657  };
658 
659  ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
660  ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
661  ::close(fd);
662 
663  for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
664  const struct _testCase *test = &rgTestCases[i];
665 
666  if (test->deleteFile) {
667  ut_compare("unlink failed", ::unlink(_unittest_microsd_file), 0);
668  }
669 
670  payload.opcode = MavlinkFTP::kCmdRemoveDirectory;
671  payload.offset = 0;
672 
673  bool success = _send_receive_msg(&payload, // FTP payload header
674  strlen(test->dir) + 1, // size in bytes of data
675  (uint8_t *)test->dir, // Data to start into FTP message payload
676  &reply); // Payload inside FTP message response
677 
678  if (!success) {
679  return false;
680  }
681 
682  if (test->success) {
683  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
684  ut_compare("Incorrect payload size", reply->size, 0);
685 
686  } else {
687  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
688  ut_compare("Incorrect payload size", reply->size, 2);
689  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
690  }
691  }
692 
693  return true;
694 }
695 
697 {
698  MavlinkFTP::PayloadHeader payload;
699  const MavlinkFTP::PayloadHeader *reply;
700 
701  struct _testCase {
702  const char *dir;
703  bool success;
704  bool fail_exists;
705  };
706  static const struct _testCase rgTestCases[] = {
707  { "/etc/bogus", false, false },
708  { _unittest_microsd_dir, true, false },
709  { _unittest_microsd_dir, false, true },
710  { "/fs/microsd/bogus/bogus", false, false },
711  };
712 
713  for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
714  const struct _testCase *test = &rgTestCases[i];
715 
716  payload.opcode = MavlinkFTP::kCmdCreateDirectory;
717  payload.offset = 0;
718 
719  bool success = _send_receive_msg(&payload, // FTP payload header
720  strlen(test->dir) + 1, // size in bytes of data
721  (uint8_t *)test->dir, // Data to start into FTP message payload
722  &reply); // Payload inside FTP message response
723 
724  if (!success) {
725  return false;
726  }
727 
728  if (test->success) {
729  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
730  ut_compare("Incorrect payload size", reply->size, 0);
731 
732  } else if (test->fail_exists) {
733  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
734  ut_compare("Incorrect payload size", reply->size, 1);
735  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailFileExists);
736 
737  } else {
738  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
739  ut_compare("Incorrect payload size", reply->size, 2);
740  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
741  }
742  }
743 
744  return true;
745 }
746 
748 {
749  MavlinkFTP::PayloadHeader payload;
750  const MavlinkFTP::PayloadHeader *reply;
751  int fd;
752 
753  struct _testCase {
754  const char *file;
755  bool success;
756  };
757  static const struct _testCase rgTestCases[] = {
758  { "/bogus", false },
759 #ifdef __PX4_NUTTX
760  // file can actually be deleted on linux
761  { _rgDownloadTestCases[0].file, false },
762 #endif /* __PX4_NUTTX */
763  { _unittest_microsd_dir, false },
764  { _unittest_microsd_file, true },
765  { _unittest_microsd_file, false },
766  };
767 
768  ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
769  ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
770  ::close(fd);
771 
772  for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
773  const struct _testCase *test = &rgTestCases[i];
774 
775  payload.opcode = MavlinkFTP::kCmdRemoveFile;
776  payload.offset = 0;
777 
778  bool success = _send_receive_msg(&payload, // FTP payload header
779  strlen(test->file) + 1, // size in bytes of data
780  (uint8_t *)test->file, // Data to start into FTP message payload
781  &reply); // Payload inside FTP message response
782 
783  if (!success) {
784  return false;
785  }
786 
787  if (test->success) {
788  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
789  ut_compare("Incorrect payload size", reply->size, 0);
790 
791  } else {
792  ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
793  ut_compare("Incorrect payload size", reply->size, 2);
794  ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
795  }
796  }
797 
798  return true;
799 }
800 
801 /// Static method used as callback from MavlinkFTP for generic use. This method will be called by MavlinkFTP when
802 /// it needs to send a message out on Mavlink.
803 void MavlinkFtpTest::receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
804 {
805  ((MavlinkFtpTest *)worker_data)->_receive_message_handler_generic(ftp_req);
806 }
807 
808 void MavlinkFtpTest::_receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req)
809 {
810  // Move the message into our own member variable
811  memcpy(&_reply_msg, ftp_req, sizeof(mavlink_file_transfer_protocol_t));
812 }
813 
814 /// Static method used as callback from MavlinkFTP for stream download testing. This method will be called by MavlinkFTP when
815 /// it needs to send a message out on Mavlink.
816 void MavlinkFtpTest::receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
817 {
818  BurstInfo *burst_info = (BurstInfo *)worker_data;
819  burst_info->ftp_test_class->_receive_message_handler_burst(ftp_req, burst_info);
820 }
821 
822 bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_msg,
823  BurstInfo *burst_info)
824 {
825  hrt_abstime t = 0;
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;
829 
830  _decode_message(ftp_msg, &reply);
831 
832  switch (burst_info->burst_state) {
834  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
835  ut_compare("Offset incorrect", reply->offset, 0);
836 
837  expected_bytes = burst_info->single_packet_file ? burst_info->file_size : full_packet_bytes;
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);
841 
842  // Setup for next expected message
844 
845  ut_assert("Remaining stream packets missing", _ftp_server->get_size());
846  _ftp_server->send(t);
847  break;
848 
850  ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
851  ut_compare("Offset incorrect", reply->offset, full_packet_bytes);
852 
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);
857 
858  // Setup for next expected message
859  burst_info->burst_state = burst_state_nak_eof;
860 
861  ut_assert("Remaining stream packets missing", _ftp_server->get_size());
862  _ftp_server->send(t);
863  break;
864 
865  case burst_state_nak_eof:
866  // Signal complete
867  burst_info->burst_state = burst_state_complete;
868  ut_compare("All packets should have been seent", _ftp_server->get_size(), 0);
869  break;
870 
871  }
872 
873  return true;
874 }
875 
876 /// @brief Decode and validate the incoming message
877 bool MavlinkFtpTest::_decode_message(const mavlink_file_transfer_protocol_t *ftp_msg, ///< Incoming FTP message
878  const MavlinkFTP::PayloadHeader **payload) ///< Payload inside FTP message response
879 {
880  //warnx("_decode_message");
881 
882  // Make sure the targets are correct
883  ut_compare("Target network non-zero", ftp_msg->target_network, 0);
884  ut_compare("Target system id mismatch", ftp_msg->target_system, clientSystemId);
885  ut_compare("Target component id mismatch", ftp_msg->target_component, clientComponentId);
886 
887  *payload = reinterpret_cast<const MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
888 
889  // Make sure we have a good sequence number
890  ut_compare("Sequence number mismatch", (*payload)->seq_number, _expected_seq_number);
892 
893  return true;
894 }
895 
896 /// @brief Initializes an FTP message into a mavlink message
897 void MavlinkFtpTest::_setup_ftp_msg(const MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
898  uint8_t size, ///< size in bytes of data
899  const uint8_t *data, ///< Data to start into FTP message payload
900  mavlink_message_t *msg) ///< Returned mavlink message
901 {
902  uint8_t payload_bytes[MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN];
903  MavlinkFTP::PayloadHeader *payload = reinterpret_cast<MavlinkFTP::PayloadHeader *>(payload_bytes);
904 
905  memcpy(payload, payload_header, sizeof(MavlinkFTP::PayloadHeader));
906 
907  payload->seq_number = _expected_seq_number++;
908  payload->size = size;
909 
910  if (size != 0) {
911  memcpy(payload->data, data, size);
912  }
913 
914  payload->burst_complete = 0;
915  payload->padding = 0;
916 
917  msg->checksum = 0;
918  mavlink_msg_file_transfer_protocol_pack(clientSystemId, // Sender system id
919  clientComponentId, // Sender component id
920  msg, // Message to pack payload into
921  0, // Target network
922  serverSystemId, // Target system id
923  serverComponentId, // Target component id
924  payload_bytes); // Payload to pack into message
925 }
926 
927 /// @brief Sends the specified FTP message to the server and returns response
928 bool MavlinkFtpTest::_send_receive_msg(MavlinkFTP::PayloadHeader *payload_header, ///< FTP payload header
929  uint8_t size, ///< size in bytes of data
930  const uint8_t *data, ///< Data to start into FTP message payload
931  const MavlinkFTP::PayloadHeader **payload_reply) ///< Payload inside FTP message response
932 {
933  mavlink_message_t msg;
934 
935  _setup_ftp_msg(payload_header, size, data, &msg);
937  return _decode_message(&_reply_msg, payload_reply);
938 }
939 
940 /// @brief Cleans up an files created on microsd during testing
942 {
943  ::unlink(_unittest_microsd_file);
944  ::rmdir(_unittest_microsd_dir);
945 }
946 
947 /// @brief Runs all the unit tests
949 {
953 
954  // TODO FIX: Incorrect payload size - (reply->size:1) (2:2) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:243)
955  //ut_run_test(_list_test);
956 
957  // TODO FIX: Didn't get Nak back - (reply->opcode:128) (MavlinkFTP::kRspNak:129) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:271)
958  //ut_run_test(_list_eof_test);
959 
967 
968  // TODO FIX: Didn't get Nak back - (reply->opcode:128) (MavlinkFTP::kRspNak:129) (../../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:730)
969  //ut_run_test(_createdirectory_test);
971 
972  return (_tests_failed == 0);
973 
974 }
975 
#define ut_declare_test(test_function, test_class)
Macro to create a function which will run a unit test class and print results.
Definition: unit_test.h:82
int _tests_failed
The number of unit tests which failed.
Definition: unit_test.h:206
static char msg[NUM_MSG][CONFIG_USART1_TXBUFSIZE]
Definition: px4io.c:89
static void read(bootloader_app_shared_t *pshared)
uint8_t * data
Definition: dataman.cpp:149
#define ut_assert(message, test)
Used to assert a value within a unit test.
Definition: unit_test.h:113
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...
Definition: lps25h.cpp:792
__BEGIN_DECLS typedef uint64_t hrt_abstime
Absolute time, in microsecond units.
Definition: drv_hrt.h:58
int fd
Definition: dataman.cpp:146
struct @83::@85::@87 file
#define ut_compare(message, v1, v2)
Used to compare two integer values within a unit test.
Definition: unit_test.h:150
#define ut_run_test(test)
Runs a single unit test.
Definition: unit_test.h:96