fix and enable mavlink ftp tests

This commit is contained in:
Daniel Agar 2017-09-27 20:48:12 -04:00 committed by Lorenz Meier
parent 3c18be387c
commit 5eb3e695bb
4 changed files with 38 additions and 43 deletions

View File

@ -45,10 +45,6 @@
#include "mavlink_main.h"
#include "mavlink_tests/mavlink_ftp_test.h"
// Uncomment the line below to get better debug output. Never commit with this left on.
//#define MAVLINK_FTP_DEBUG
constexpr const char MavlinkFTP::_root_dir[];
MavlinkFTP::MavlinkFTP(Mavlink *mavlink) :
@ -142,7 +138,7 @@ MavlinkFTP::handle_message(const mavlink_message_t *msg)
mavlink_msg_file_transfer_protocol_decode(msg, &ftp_request);
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: received ftp protocol message target_system: %d", ftp_request.target_system);
PX4_INFO("FTP: received ftp protocol message target_system: %d", ftp_request.target_system);
#endif
if (ftp_request.target_system == _getServerSystemId()) {
@ -189,8 +185,8 @@ MavlinkFTP::_process_request(mavlink_file_transfer_protocol_t *ftp_req, uint8_t
#ifdef MAVLINK_FTP_DEBUG
printf("ftp: channel %u opc %u size %u offset %u\n", _getServerChannel(), payload->opcode, payload->size,
payload->offset);
PX4_INFO("ftp: channel %u opc %u size %u offset %u", _getServerChannel(), payload->opcode, payload->size,
payload->offset);
#endif
switch (payload->opcode) {
@ -332,7 +328,7 @@ MavlinkFTP::_reply(mavlink_file_transfer_protocol_t *ftp_req)
}
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: %s seq_number: %d", payload->opcode == kRspAck ? "Ack" : "Nak", payload->seq_number);
PX4_INFO("FTP: %s seq_number: %d", payload->opcode == kRspAck ? "Ack" : "Nak", payload->seq_number);
#endif
ftp_req->target_network = 0;
@ -362,7 +358,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
if (dp == nullptr) {
#ifdef MAVLINK_FTP_UNIT_TEST
warnx("File open failed");
PX4_WARN("File open failed %s", _work_buffer1);
#else
_mavlink->send_statustext_critical("FTP: can't open path (file system corrupted?)");
_mavlink->send_statustext_critical(_work_buffer1);
@ -372,7 +368,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
}
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: list %s offset %d", _work_buffer1, payload->offset);
PX4_INFO("FTP: list %s offset %d", _work_buffer1, payload->offset);
#endif
struct dirent *result = nullptr;
@ -390,7 +386,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
if (result == nullptr) {
if (errno) {
#ifdef MAVLINK_FTP_UNIT_TEST
warnx("readdir failed");
PX4_WARN("readdir failed");
#else
_mavlink->send_statustext_critical("FTP: list readdir failure");
_mavlink->send_statustext_critical(_work_buffer1);
@ -496,7 +492,7 @@ MavlinkFTP::_workList(PayloadHeader *payload, bool list_hidden)
payload->data[offset++] = direntType;
strcpy((char *)&payload->data[offset], _work_buffer2);
#ifdef MAVLINK_FTP_DEBUG
printf("FTP: list %s %s\n", _work_buffer1, (char *)&payload->data[offset - 1]);
PX4_INFO("FTP: list %s %s", _work_buffer1, (char *)&payload->data[offset - 1]);
#endif
offset += nameLen + 1;
}
@ -520,7 +516,7 @@ MavlinkFTP::_workOpen(PayloadHeader *payload, int oflag)
strncpy(_work_buffer1 + _root_dir_len, _data_as_cstring(payload), _work_buffer1_len - _root_dir_len);
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: open '%s'", _work_buffer1);
PX4_INFO("FTP: open '%s'", _work_buffer1);
#endif
uint32_t fileSize = 0;
@ -565,7 +561,7 @@ MavlinkFTP::_workRead(PayloadHeader *payload)
}
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: read offset:%d", payload->offset);
PX4_INFO("FTP: read offset:%d", payload->offset);
#endif
// We have to test seek past EOF ourselves, lseek will allow seek past EOF
@ -601,7 +597,7 @@ MavlinkFTP::_workBurst(PayloadHeader *payload, uint8_t target_system_id)
}
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: burst offset:%d", payload->offset);
PX4_INFO("FTP: burst offset:%d", payload->offset);
#endif
// Setup for streaming sends
_session_info.stream_download = true;
@ -993,7 +989,7 @@ void MavlinkFTP::send(const hrt_abstime t)
// Skip send if not enough room
unsigned max_bytes_to_send = _mavlink->get_free_tx_buf();
#ifdef MAVLINK_FTP_DEBUG
warnx("MavlinkFTP::send max_bytes_to_send(%d) get_free_tx_buf(%d)", max_bytes_to_send, _mavlink->get_free_tx_buf());
PX4_INFO("MavlinkFTP::send max_bytes_to_send(%d) get_free_tx_buf(%d)", max_bytes_to_send, _mavlink->get_free_tx_buf());
#endif
if (max_bytes_to_send < get_size()) {
@ -1022,14 +1018,14 @@ void MavlinkFTP::send(const hrt_abstime t)
_session_info.stream_seq_number++;
#ifdef MAVLINK_FTP_DEBUG
warnx("stream send: offset %d", _session_info.stream_offset);
PX4_INFO("stream send: offset %d", _session_info.stream_offset);
#endif
// We have to test seek past EOF ourselves, lseek will allow seek past EOF
if (_session_info.stream_offset >= _session_info.file_size) {
error_code = kErrEOF;
#ifdef MAVLINK_FTP_DEBUG
warnx("stream download: sending Nak EOF");
PX4_INFO("stream download: sending Nak EOF");
#endif
}
@ -1037,7 +1033,7 @@ void MavlinkFTP::send(const hrt_abstime t)
if (lseek(_session_info.fd, payload->offset, SEEK_SET) < 0) {
error_code = kErrFailErrno;
#ifdef MAVLINK_FTP_DEBUG
warnx("stream download: seek fail");
PX4_WARN("stream download: seek fail");
#endif
}
}
@ -1049,7 +1045,7 @@ void MavlinkFTP::send(const hrt_abstime t)
// Negative return indicates error other than eof
error_code = kErrFailErrno;
#ifdef MAVLINK_FTP_DEBUG
warnx("stream download: read fail");
PX4_WARN("stream download: read fail");
#endif
} else {

View File

@ -40,6 +40,7 @@ px4_add_module(
COMPILE_FLAGS
-Wno-sign-compare # TODO: fix all sign-compare
-DMAVLINK_FTP_UNIT_TEST
#-DMAVLINK_FTP_DEBUG
-DMavlinkStream=MavlinkStreamTest
-DMavlinkFTP=MavlinkFTPTest
-Wno-extra-semi

View File

@ -42,10 +42,10 @@
#include "mavlink_ftp_test.h"
#include "../mavlink_ftp.h"
#if !defined(CONFIG_ARCH_BOARD_SITL)
#define PX4_MAVLINK_TEST_DATA_DIR "ROMFS/px4fmu_test/"
#ifdef __PX4_NUTTX
#define PX4_MAVLINK_TEST_DATA_DIR "/etc"
#else
#define PX4_MAVLINK_TEST_DATA_DIR "/etc/"
#define PX4_MAVLINK_TEST_DATA_DIR "ROMFS/px4fmu_test"
#endif
/// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
@ -169,7 +169,10 @@ bool MavlinkFtpTest::_list_test()
const MavlinkFTP::PayloadHeader *reply;
char response1[] = "Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
#ifdef __PX4_NUTTX
// expected directory layout only valid on nuttx
char response2[] = "Ddev|Detc|Dfs|Dobj";
#endif /* __PX4_NUTTX */
struct _testCase {
const char *dir; ///< Directory to run List command on
@ -179,8 +182,11 @@ bool MavlinkFtpTest::_list_test()
};
struct _testCase rgTestCases[] = {
{ "/bogus", nullptr, 0, false },
{ "/etc/unit_test_data/mavlink_tests", response1, 4, true },
{ PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests", response1, 4, true },
#ifdef __PX4_NUTTX
// expected directory layout only valid on nuttx
{ "/", response2, 4, true },
#endif /* __PX4_NUTTX */
};
for (size_t i = 0; i < sizeof(rgTestCases) / sizeof(rgTestCases[0]); i++) {
@ -319,7 +325,6 @@ bool MavlinkFtpTest::_open_terminate_test()
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);
@ -637,7 +642,7 @@ bool MavlinkFtpTest::_removedirectory_test()
};
static const struct _testCase rgTestCases[] = {
{ "/bogus", false, false },
{ "/etc/unit_test_data/mavlink_tests/empty_dir", false, false },
{ PX4_MAVLINK_TEST_DATA_DIR "/unit_test_data/mavlink_tests/empty_dir", false, false },
{ _unittest_microsd_dir, false, false },
{ _unittest_microsd_file, false, false },
{ _unittest_microsd_dir, true, true },
@ -743,7 +748,10 @@ bool MavlinkFtpTest::_removefile_test()
};
static const struct _testCase rgTestCases[] = {
{ "/bogus", false },
#ifdef __PX4_NUTTX
// file can actually be deleted on linux
{ _rgDownloadTestCases[0].file, false },
#endif /* __PX4_NUTTX */
{ _unittest_microsd_dir, false },
{ _unittest_microsd_file, true },
{ _unittest_microsd_file, false },
@ -935,28 +943,18 @@ bool MavlinkFtpTest::run_tests()
ut_run_test(_bad_opcode_test);
ut_run_test(_bad_datasize_test);
// TODO FIX: cmake build system needs to run mavlink_ftp_test_data.py
// TODO FIX: Incorrect payload size - (reply->size:1) (2:2) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:243)
//ut_run_test(_list_test);
// TODO FIX: Compare failed: Didn't get Nak back - (reply->opcode:128) (MavlinkFTP::kRspNak:129) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:265)
// TODO FIX: Didn't get Nak back - (reply->opcode:128) (MavlinkFTP::kRspNak:129) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:271)
//ut_run_test(_list_eof_test);
ut_run_test(_open_badfile_test);
// TODO FIX: Compare failed: stat failed - (stat(test->file, &st):-1) (0:0) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:320)
//ut_run_test(_open_terminate_test);
// TODO FIX: Compare failed: Didn't get Ack back - (reply->opcode:129) (MavlinkFTP::kRspAck:128) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:366)
//ut_run_test(_terminate_badsession_test);
// TODO FIX: Compare failed: Didn't get Ack back - (reply->opcode:129) (MavlinkFTP::kRspAck:128) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:366)
//ut_run_test(_read_test);
// TODO FIX: Compare failed: Didn't get Ack back - (reply->opcode:129) (MavlinkFTP::kRspAck:128) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:605)
//ut_run_test(_read_badsession_test);
// TODO FIX: Compare failed: stat failed - (stat(test->file, &st):-1) (0:0) (../src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp:513)
//ut_run_test(_burst_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);

View File