mavlink_ftp_test.cpp 33.3 KB
1 2 3 4 5 6 7 8 9 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 48 49 50 51 52 53 54 55 56 57 58 59 60 61 62 63 64 65 66 67 68 69 70 71 72 73 74 75 76 77 78 79 80 81 82 83 84 85 86 87 88 89 90 91 92 93 94 95 96 97 98 99 100 101 102 103 104 105 106 107 108 109 110 111 112 113 114 115 116 117 118 119 120 121 122 123 124 125 126 127 128 129 130 131 132 133 134 135 136 137 138 139 140 141 142 143 144 145 146 147 148 149 150 151 152 153 154 155 156 157 158 159 160 161 162 163 164 165 166 167 168 169 170 171 172 173 174 175 176 177 178 179 180 181 182 183 184 185 186 187 188 189 190 191 192 193 194 195 196 197 198 199 200 201 202 203 204 205 206 207 208 209 210 211 212 213 214 215 216 217 218 219 220 221 222 223 224 225 226 227 228 229 230 231 232 233 234 235 236 237 238 239 240 241 242 243 244 245 246 247 248 249 250 251 252 253 254 255 256 257 258 259 260 261 262 263 264 265 266 267 268 269 270 271 272 273 274 275 276 277 278 279 280 281 282 283 284 285 286 287 288 289 290 291 292 293 294 295 296 297 298 299 300 301 302 303 304 305 306 307 308 309 310 311 312 313 314 315 316 317 318 319 320 321 322 323 324 325 326 327 328 329 330 331 332 333 334 335 336 337 338 339 340 341 342 343 344 345 346 347 348 349 350 351 352 353 354 355 356 357 358 359 360 361 362 363 364 365 366 367 368 369 370 371 372 373 374 375 376 377 378 379 380 381 382 383 384 385 386 387 388 389 390 391 392 393 394 395 396 397 398 399 400 401 402 403 404 405 406 407 408 409 410 411 412 413 414 415 416 417 418 419 420 421 422 423 424 425 426 427 428 429 430 431 432 433 434 435 436 437 438 439 440 441 442 443 444 445 446 447 448 449 450 451 452 453 454 455 456 457 458 459 460 461 462 463 464 465 466 467 468 469 470 471 472 473 474 475 476 477 478 479 480 481 482 483 484 485 486 487 488 489 490 491 492 493 494 495 496 497 498 499 500 501 502 503 504 505 506 507 508 509 510 511 512 513 514 515 516 517 518 519 520 521 522 523 524 525 526 527 528 529 530 531 532 533 534 535 536 537 538 539 540 541 542 543 544 545 546 547 548 549 550 551 552 553 554 555 556 557 558 559 560 561 562 563 564 565 566 567 568 569 570 571 572 573 574 575 576 577 578 579 580 581 582 583 584 585 586 587 588 589 590 591 592 593 594 595 596 597 598 599 600 601 602 603 604 605 606 607 608 609 610 611 612 613 614 615 616 617 618 619 620 621 622 623 624 625 626 627 628 629 630 631 632 633 634 635 636 637 638 639 640 641 642 643 644 645 646 647 648 649 650 651 652 653 654 655 656 657 658 659 660 661 662 663 664 665 666 667 668 669 670 671 672 673 674 675 676 677 678 679 680 681 682 683 684 685 686 687 688 689 690 691 692 693 694 695 696 697 698 699 700 701 702 703 704 705 706 707 708 709 710 711 712 713 714 715 716 717 718 719 720 721 722 723 724 725 726 727 728 729 730 731 732 733 734 735 736 737 738 739 740 741 742 743 744 745 746 747 748 749 750 751 752 753 754 755 756 757 758 759 760 761 762 763 764 765 766 767 768 769 770 771 772 773 774 775 776 777 778 779 780 781 782 783 784 785 786 787 788 789 790 791 792 793 794 795 796 797 798 799 800 801 802 803 804 805 806 807 808 809 810 811 812 813 814 815 816 817 818 819 820 821 822 823 824 825 826 827 828 829 830 831 832 833 834 835 836 837 838 839 840 841 842 843 844 845 846 847 848 849 850 851 852 853 854 855 856 857 858 859 860 861 862 863 864 865 866 867 868 869 870 871 872 873 874 875 876 877 878 879 880 881 882 883 884 885 886 887 888 889 890 891 892 893 894 895 896 897 898 899 900 901 902 903 904 905 906 907 908 909 910 911 912 913 914 915 916 917 918 919 920 921 922 923 924 925 926 927 928 929 930 931 932 933 934 935 936 937 938 939 940 941 942 943 944 945 946 947 948 949 950 951 952 953 954 955 956 957 958 959 960 961 962 963 964 965 966 967 968 969 970 971 972 973 974 975 976 977 978 979 980 981 982 983 984 985 986 987 988 989 990 991 992 993 994 995 996 997 998 999 1000 1001 1002 1003 1004 1005 1006 1007 1008 1009 1010 1011 1012 1013 1014 1015 1016 1017 1018 1019 1020 1021
/****************************************************************************
 *
 *   Copyright (C) 2014-2020 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
 * are met:
 *
 * 1. Redistributions of source code must retain the above copyright
 *    notice, this list of conditions and the following disclaimer.
 * 2. Redistributions in binary form must reproduce the above copyright
 *    notice, this list of conditions and the following disclaimer in
 *    the documentation and/or other materials provided with the
 *    distribution.
 * 3. Neither the name PX4 nor the names of its contributors may be
 *    used to endorse or promote products derived from this software
 *    without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
 * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
 * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 *
 ****************************************************************************/

/// @file mavlink_ftp_test.cpp
///	@author Don Gagne <don@thegagnes.com>

#include <sys/stat.h>
#include <crc32.h>
#include <stdio.h>
#include <fcntl.h>

#include "mavlink_ftp_test.h"
#include "../mavlink_ftp.h"

#ifdef __PX4_NUTTX
#define PX4_MAVLINK_TEST_DATA_DIR "/fs/microsd/ftp_unit_test_data"
#else
#define PX4_MAVLINK_TEST_DATA_DIR "ftp_unit_test_data"
#endif

static const char *_test_files[] = {
	PX4_MAVLINK_TEST_DATA_DIR  "/" "test_238.data",
	PX4_MAVLINK_TEST_DATA_DIR  "/" "test_239.data",
	PX4_MAVLINK_TEST_DATA_DIR  "/" "test_240.data"
};

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
};

const char MavlinkFtpTest::_unittest_microsd_dir[] = PX4_STORAGEDIR "/ftp_unit_test_dir";
const char MavlinkFtpTest::_unittest_microsd_file[] = PX4_STORAGEDIR "/ftp_unit_test_dir/file";

MavlinkFtpTest::MavlinkFtpTest() :
	_ftp_server(nullptr),
	_expected_seq_number(0),
	_reply_msg{}
{
}

/// @brief Called before every test to initialize the FTP Server.
void MavlinkFtpTest::_init()
{
	_expected_seq_number = 0;
	_ftp_server = new MavlinkFTP(nullptr);
	_ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_generic, this);

	_create_test_files();

	_cleanup_microsd();
}

bool MavlinkFtpTest::_create_test_files()
{
	int ret = ::mkdir(PX4_MAVLINK_TEST_DATA_DIR, S_IRWXU | S_IRWXG | S_IRWXO);
	ut_assert("mkdir failed", ret == 0 || errno == EEXIST);

	ret = ::mkdir(PX4_MAVLINK_TEST_DATA_DIR "/empty_dir", S_IRWXU | S_IRWXG | S_IRWXO);
	ut_assert("mkdir failed", ret == 0 || errno == EEXIST);

	bool failed = false;

	for (int i = 0; i < 3; ++i) {
		int fd = ::open(_test_files[i], O_CREAT | O_EXCL | O_WRONLY, S_IRWXU | S_IRWXG | S_IRWXO);

		if (fd < 0) {
			printf("fd: %d, error: %s\n", fd, strerror(errno));
			ut_assert("Open failed", fd != -1);
		}

		// We create 3 files, with bytes counting from 0 to 238, 239, and 240.
		uint8_t len = 238 + i;

		for (uint8_t c = 0; c < len; ++c) {
			ret = ::write(fd, &c, 1);

			if (ret != 1) {
				failed = true;
			}
		}

		close(fd);
	}

	ut_assert("Could not write test file", !failed);

	return !failed;
}

/// @brief Called after every test to take down the FTP Server.
void MavlinkFtpTest::_cleanup()
{
	delete _ftp_server;

	_cleanup_microsd();
	_remove_test_files();
}

bool MavlinkFtpTest::_remove_test_files()
{
	for (int i = 0; i < 3; ++i) {
		::unlink(_test_files[i]);
	}

	::rmdir(PX4_MAVLINK_TEST_DATA_DIR "/empty_dir");
	::rmdir(PX4_MAVLINK_TEST_DATA_DIR);

	return true;
}


/// @brief Tests for correct behavior of an Ack response.
bool MavlinkFtpTest::_ack_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	payload.opcode = MavlinkFTP::kCmdNone;

	bool 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) {
		return false;
	}

	ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
	ut_compare("Incorrect payload size", reply->size, 0);

	return true;
}

/// @brief Tests for correct response to an invalid opcode.
bool MavlinkFtpTest::_bad_opcode_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	payload.opcode = 0xFF;	// bogus opcode

	bool 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) {
		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::kErrUnknownCommand);

	return true;
}

/// @brief Tests for correct reponse to a payload which an invalid data size field.
bool MavlinkFtpTest::_bad_datasize_test()
{
	mavlink_message_t			msg;
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	payload.opcode = MavlinkFTP::kCmdListDirectory;

	_setup_ftp_msg(&payload, 0, nullptr, &msg);

	// Set the data size to be one larger than is legal
	((MavlinkFTP::PayloadHeader *)((mavlink_file_transfer_protocol_t *)msg.payload64)->payload)->size =
		MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN + 1;

	_ftp_server->handle_message(&msg);

	if (!_decode_message(&_reply_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::kErrInvalidDataSize);

	return true;
}

bool MavlinkFtpTest::_list_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	struct _testCase {
		const char	*dir;		///< Directory to run List command on
		const char	*response;	///< Expected response entries from List command
		int		response_count;	///< Number of directories that should be returned
		bool		success;	///< true: List command should succeed, false: List command should fail
	};
	struct _testCase rgTestCases[] = {
		{ "/bogus",			nullptr,		0,	false },
#ifdef __PX4_NUTTX
		{ PX4_MAVLINK_TEST_DATA_DIR,	"Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240", 	4,	true },
#else
		{ PX4_MAVLINK_TEST_DATA_DIR,	"Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240|S|S",	6,	true },   // readdir on Linux adds . and ..
#endif
	};

	for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
		const struct _testCase *test = &rgTestCases[i];

		payload.opcode = MavlinkFTP::kCmdListDirectory;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			return false;
		}

		if (test->success) {
			ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
			ut_compare("Incorrect payload size", reply->size, strlen(test->response) + 1);

			// The return order of directories from the List command is not repeatable. So we can't do a direct comparison
			// to a hardcoded return result string.

			// Convert null terminators to seperator char so we can use strok to parse returned data
			char list_entry[256];

			for (uint8_t j = 0; j < reply->size - 1; j++) {
				if (reply->data[j] == 0) {
					list_entry[j] = '|';

				} else {
					list_entry[j] = reply->data[j];
				}
			}

			list_entry[reply->size - 1] = 0;

			// Loop over returned directory entries trying to find then in the response list
			char *dir;
			int response_count = 0;
			dir = strtok(list_entry, "|");

			while (dir != nullptr) {
				ut_assert("Returned directory not found in expected response", strstr(test->response, dir));
				response_count++;
				dir = strtok(nullptr, "|");
			}

			ut_compare("Incorrect number of directory entires returned", test->response_count, response_count);

		} else {
			ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
			ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFileNotFound);
			ut_compare("Incorrect payload size", reply->size, 1);
		}
	}

	return true;
}

/// @brief Tests for correct response to a List command on a valid directory, but with an offset that
/// is beyond the last directory entry.
bool MavlinkFtpTest::_list_eof_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	const char				*dir = PX4_MAVLINK_TEST_DATA_DIR;

	payload.opcode = MavlinkFTP::kCmdListDirectory;
#ifdef __PX4_NUTTX
	payload.offset = 4;	// (3 test files, 1 test folder)
#else
	payload.offset = 6;	// (3 test files, 1 test folder, two skipped ./..)
#endif

	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
					 &reply);	// Payload inside FTP message response

	if (!success) {
		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::kErrEOF);

	return true;
}

/// @brief Tests for correct response to an Open command on a file which does not exist.
bool MavlinkFtpTest::_open_badfile_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	const char				*dir = "/foo";	// non-existent file

	payload.opcode = MavlinkFTP::kCmdOpenFileRO;
	payload.offset = 0;

	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
					 &reply);	// Payload inside FTP message response

	if (!success) {
		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::kErrFileNotFound);

	return true;
}

/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
bool MavlinkFtpTest::_open_terminate_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
		struct stat st;
		const DownloadTestCase *test = &_rgDownloadTestCases[i];

		payload.opcode = MavlinkFTP::kCmdOpenFileRO;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			return false;
		}

		ut_compare("stat failed", stat(test->file, &st), 0);

		ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
		ut_compare("Incorrect payload size", reply->size, sizeof(uint32_t));
		ut_compare("File size incorrect", *((uint32_t *)&reply->data[0]), (uint32_t)st.st_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
					    &reply);	// Payload inside FTP message response

		if (!success) {
			return false;
		}

		ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
		ut_compare("Incorrect payload size", reply->size, 0);
	}

	return true;
}

/// @brief Tests for correct reponse to a Terminate command on an invalid session.
bool MavlinkFtpTest::_terminate_badsession_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	const char				*file = _rgDownloadTestCases[0].file;

	payload.opcode = MavlinkFTP::kCmdOpenFileRO;
	payload.offset = 0;

	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
					 &reply);	// Payload inside FTP message response

	if (!success) {
		return false;
	}

	ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);

	payload.opcode = MavlinkFTP::kCmdTerminateSession;
	payload.session = reply->session + 1;
	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
				    &reply);	// Payload inside FTP message response

	if (!success) {
		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::kErrInvalidSession);

	return true;
}

/// @brief Tests for correct reponse to a Read command on an open session.
bool MavlinkFtpTest::_read_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
		struct stat st;
		const DownloadTestCase *test = &_rgDownloadTestCases[i];

		// Read in the file so we can compare it to what we get back
		ut_compare("stat failed", stat(test->file, &st), 0);
		uint8_t *bytes = new uint8_t[st.st_size];
		ut_assert("new failed", bytes != nullptr);
		int fd = ::open(test->file, O_RDONLY);
		ut_assert("open failed", fd != -1);
		int bytes_read = ::read(fd, bytes, st.st_size);
		ut_compare("read failed", bytes_read, st.st_size);
		::close(fd);

		// Test case data files are created for specific boundary conditions
		ut_compare("Test case data files are out of date", test->length, st.st_size);

		payload.opcode = MavlinkFTP::kCmdOpenFileRO;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			delete[] bytes;
			return false;
		}

		ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);

		payload.opcode = MavlinkFTP::kCmdReadFile;
		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);

		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);

		payload.offset += expected_bytes;

		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) {
				delete[] bytes;
				return false;
			}

			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);
		}

		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
					    &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("Incorrect payload size", reply->size, 0);

		delete[] bytes;
		bytes = nullptr;
	}

	return true;
}

/// @brief Tests for correct reponse to a Read command on an open session.
bool MavlinkFtpTest::_burst_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	BurstInfo				burst_info;



	for (size_t i = 0; i < sizeof(_rgDownloadTestCases) / sizeof(_rgDownloadTestCases[0]); i++) {
		struct stat st;
		const DownloadTestCase *test = &_rgDownloadTestCases[i];

		// Read in the file so we can compare it to what we get back
		ut_compare("stat failed", stat(test->file, &st), 0);
		uint8_t *bytes = new uint8_t[st.st_size];
		ut_assert("new failed", bytes != nullptr);
		int fd = ::open(test->file, O_RDONLY);
		ut_assert("open failed", fd != -1);
		int bytes_read = ::read(fd, bytes, st.st_size);
		ut_compare("read failed", bytes_read, st.st_size);
		::close(fd);

		// Test case data files are created for specific boundary conditions
		ut_compare("Test case data files are out of date", test->length, st.st_size);

		payload.opcode = MavlinkFTP::kCmdOpenFileRO;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			delete[] bytes;
			return false;
		}

		ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);

		// Setup for burst response handler
		burst_info.burst_state = burst_state_first_ack;
		burst_info.single_packet_file = test->singlePacketRead;
		burst_info.file_size = st.st_size;
		burst_info.file_bytes = bytes;
		burst_info.ftp_test_class = this;
		_ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_burst, &burst_info);

		// Send the burst command, message response will be handled by _receive_message_handler_stream
		payload.opcode = MavlinkFTP::kCmdBurstReadFile;
		payload.session = reply->session;
		payload.offset = 0;

		mavlink_message_t msg;
		_setup_ftp_msg(&payload, 0, nullptr, &msg);
		_ftp_server->handle_message(&msg);

		// First packet is sent using stream mechanism, so we need to force it out ourselves
		_ftp_server->send();

		ut_compare("Incorrect sequence of messages", burst_info.burst_state, burst_state_complete);

		// Put back generic message handler
		_ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message_handler_generic, this);

		// Terminate session
		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
					    &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("Incorrect payload size", reply->size, 0);

		delete[] bytes;
		bytes = nullptr;
	}

	return true;
}

/// @brief Tests for correct reponse to a Read command on an invalid session.
bool MavlinkFtpTest::_read_badsession_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	const char				*file = _rgDownloadTestCases[0].file;

	payload.opcode = MavlinkFTP::kCmdOpenFileRO;
	payload.offset = 0;

	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
					 &reply);		// Payload inside FTP message response

	if (!success) {
		return false;
	}

	ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);

	payload.opcode = MavlinkFTP::kCmdReadFile;
	payload.session = reply->session + 1;	// Invalid 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) {
		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::kErrInvalidSession);

	return true;
}

bool MavlinkFtpTest::_removedirectory_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	int					fd;

	struct _testCase {
		const char	*dir;
		bool		success;
		bool		deleteFile;
		uint8_t		reply_size;
		uint8_t		error_code;
	};
	static const struct _testCase rgTestCases[] = {
		{ "/bogus",						false,	false, 1, MavlinkFTP::kErrFileNotFound },
		{ _unittest_microsd_dir,				false,	false, 2, MavlinkFTP::kErrFailErrno },
		{ _unittest_microsd_file,				false,	false, 2, MavlinkFTP::kErrFailErrno },
		{ _unittest_microsd_dir,				true,	true, 0, MavlinkFTP::kErrNone },
	};

	ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
	ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
	::close(fd);

	for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
		const struct _testCase *test = &rgTestCases[i];

		if (test->deleteFile) {
			ut_compare("unlink failed", ::unlink(_unittest_microsd_file), 0);
		}

		payload.opcode = MavlinkFTP::kCmdRemoveDirectory;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			return false;
		}

		if (test->success) {
			ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);

		} else {
			ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);
			ut_compare("Incorrect error code", reply->data[0], test->error_code);
		}
	}

	return true;
}

bool MavlinkFtpTest::_createdirectory_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;

	struct _testCase {
		const char	*dir;
		bool		success;
		uint8_t		reply_size;
		uint8_t		error_code;
	};
	static const struct _testCase rgTestCases[] = {
		{ _unittest_microsd_dir,	true,	0, MavlinkFTP::kErrNone},
		{ _unittest_microsd_dir,	false,	1, MavlinkFTP::kErrFailFileExists},
#ifdef __PX4_NUTTX
		{ PX4_MAVLINK_TEST_DATA_DIR "/bogus/bogus",	false,	2, MavlinkFTP::kErrFailErrno} // on NuttX missing folders is EIO
#else
		{ PX4_MAVLINK_TEST_DATA_DIR "/bogus/bogus",	false,	1, MavlinkFTP::kErrFileNotFound} // on Linux it is ENOENT
#endif
	};

	for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
		const struct _testCase *test = &rgTestCases[i];

		payload.opcode = MavlinkFTP::kCmdCreateDirectory;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			return false;
		}

		if (test->success) {
			ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);

		} else {
			ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
			ut_compare("Incorrect error code", reply->data[0], test->error_code);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);
		}
	}

	return true;
}

bool MavlinkFtpTest::_removefile_test()
{
	MavlinkFTP::PayloadHeader		payload;
	const MavlinkFTP::PayloadHeader		*reply;
	int					fd;

	struct _testCase {
		const char	*file;
		bool		success;
		uint8_t		reply_size;
		uint8_t		error_code;
	};
	static const struct _testCase rgTestCases[] = {
		{ "/bogus",			false, 1, MavlinkFTP::kErrFileNotFound },
		{ _unittest_microsd_dir,	false, 2, MavlinkFTP::kErrFailErrno },
		{ _unittest_microsd_file,	true,  0, MavlinkFTP::kErrNone },
		{ _unittest_microsd_file,	false, 1, MavlinkFTP::kErrFileNotFound },
	};

	ut_compare("mkdir failed", ::mkdir(_unittest_microsd_dir, S_IRWXU | S_IRWXG | S_IRWXO), 0);
	ut_assert("open failed", (fd = ::open(_unittest_microsd_file, O_CREAT | O_EXCL, S_IRWXU | S_IRWXG | S_IRWXO)) != -1);
	::close(fd);

	for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
		const struct _testCase *test = &rgTestCases[i];

		payload.opcode = MavlinkFTP::kCmdRemoveFile;
		payload.offset = 0;

		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
						 &reply);		// Payload inside FTP message response

		if (!success) {
			return false;
		}

		if (test->success) {
			ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);

		} else {
			ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
			ut_compare("Incorrect payload size", reply->size, test->reply_size);
			ut_compare("Incorrect error code", reply->data[0], test->error_code);
		}
	}

	return true;
}

/// Static method used as callback from MavlinkFTP for generic use. This method will be called by MavlinkFTP when
/// it needs to send a message out on Mavlink.
void MavlinkFtpTest::receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
{
	((MavlinkFtpTest *)worker_data)->_receive_message_handler_generic(ftp_req);
}

void MavlinkFtpTest::_receive_message_handler_generic(const mavlink_file_transfer_protocol_t *ftp_req)
{
	// Move the message into our own member variable
	memcpy(&_reply_msg, ftp_req, sizeof(mavlink_file_transfer_protocol_t));
}

/// Static method used as callback from MavlinkFTP for stream download testing. This method will be called by MavlinkFTP when
/// it needs to send a message out on Mavlink.
void MavlinkFtpTest::receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_req, void *worker_data)
{
	BurstInfo *burst_info = (BurstInfo *)worker_data;
	burst_info->ftp_test_class->_receive_message_handler_burst(ftp_req, burst_info);
}

bool MavlinkFtpTest::_receive_message_handler_burst(const mavlink_file_transfer_protocol_t *ftp_msg,
		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);

	switch (burst_info->burst_state) {
	case burst_state_first_ack:
		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;
		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);

		// Setup for next expected message
		burst_info->burst_state = burst_info->single_packet_file ? burst_state_nak_eof : burst_state_last_ack;

		ut_assert("Remaining stream packets missing", _ftp_server->get_size());
		_ftp_server->send();
		break;

	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);

		expected_bytes = burst_info->file_size - full_packet_bytes;
		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);

		// Setup for next expected message
		burst_info->burst_state = burst_state_nak_eof;

		ut_assert("Remaining stream packets missing", _ftp_server->get_size());
		_ftp_server->send();
		break;

	case burst_state_nak_eof:
		// Signal complete
		burst_info->burst_state = burst_state_complete;
		ut_compare("All packets should have been seent", _ftp_server->get_size(), 0);
		break;

	}

	return true;
}

/// @brief Decode and validate the incoming message
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);
	ut_compare("Target component id mismatch", ftp_msg->target_component, clientComponentId);

	*payload = reinterpret_cast<const MavlinkFTP::PayloadHeader *>(ftp_msg->payload);

	// Make sure we have a good sequence number
	ut_compare("Sequence number mismatch", (*payload)->seq_number, _expected_seq_number);
	_expected_seq_number++;

	return true;
}

/// @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
				    const uint8_t			*data,			///< Data to start into FTP message payload
				    mavlink_message_t			*msg)			///< Returned mavlink message
{
	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);
	}

	payload->burst_complete = 0;
	payload->padding = 0;

	msg->checksum = 0;
	mavlink_msg_file_transfer_protocol_pack(clientSystemId,		// Sender system id
						clientComponentId,	// Sender component id
						msg,			// Message to pack payload into
						0,			// Target network
						serverSystemId,		// Target system id
						serverComponentId,	// Target component id
						payload_bytes);		// Payload to pack into message
}

/// @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 MavlinkFTP::PayloadHeader	**payload_reply)	///< Payload inside FTP message response
{
	mavlink_message_t msg;

	_setup_ftp_msg(payload_header, size, data, &msg);
	_ftp_server->handle_message(&msg);
	return _decode_message(&_reply_msg, payload_reply);
}

/// @brief Cleans up an files created on microsd during testing
void MavlinkFtpTest::_cleanup_microsd()
{
	::unlink(_unittest_microsd_file);
	::rmdir(_unittest_microsd_dir);
}

/// @brief Runs all the unit tests
bool MavlinkFtpTest::run_tests()
{
	ut_run_test(_ack_test);
	ut_run_test(_bad_opcode_test);
	ut_run_test(_bad_datasize_test);
	ut_run_test(_list_test);
	ut_run_test(_list_eof_test);
	ut_run_test(_open_badfile_test);
	ut_run_test(_open_terminate_test);
	ut_run_test(_terminate_badsession_test);
	ut_run_test(_read_test);
	ut_run_test(_read_badsession_test);
	ut_run_test(_burst_test);
	ut_run_test(_removedirectory_test);
	ut_run_test(_createdirectory_test);
	ut_run_test(_removefile_test);

	return (_tests_failed == 0);

}

ut_declare_test(mavlink_ftp_test, MavlinkFtpTest)