aboutsummaryrefslogtreecommitdiff
path: root/src/modules/mavlink
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2014-10-05 13:17:32 +0200
committerThomas Gubler <thomasgubler@gmail.com>2014-10-05 13:17:32 +0200
commit7f9a231b4014bce4ad44c4eb61bfa0e7efeb73fa (patch)
tree1fee14fa887b396a76581ed643f16abe4cf0d1aa /src/modules/mavlink
parent9bda573151ae1b5fa87686ee58596ea14e052941 (diff)
parent80ed01a5b4324ab13b88dca0b0c8e5ea4f8841ce (diff)
downloadpx4-firmware-7f9a231b4014bce4ad44c4eb61bfa0e7efeb73fa.tar.gz
px4-firmware-7f9a231b4014bce4ad44c4eb61bfa0e7efeb73fa.tar.bz2
px4-firmware-7f9a231b4014bce4ad44c4eb61bfa0e7efeb73fa.zip
Merge remote-tracking branch 'upstream/master' into offboard2_externalsetpointmessages
Conflicts: src/modules/navigator/navigator.h src/modules/navigator/navigator_main.cpp
Diffstat (limited to 'src/modules/mavlink')
-rw-r--r--src/modules/mavlink/mavlink_ftp.cpp694
-rw-r--r--src/modules/mavlink/mavlink_ftp.h296
-rw-r--r--src/modules/mavlink/mavlink_main.cpp8
-rw-r--r--src/modules/mavlink/mavlink_messages.cpp26
-rw-r--r--src/modules/mavlink/mavlink_mission.cpp4
-rw-r--r--src/modules/mavlink/mavlink_receiver.cpp60
-rw-r--r--src/modules/mavlink/mavlink_receiver.h2
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp761
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h108
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py7
-rw-r--r--src/modules/mavlink/mavlink_tests/mavlink_tests.cpp47
-rw-r--r--src/modules/mavlink/mavlink_tests/module.mk50
12 files changed, 1708 insertions, 355 deletions
diff --git a/src/modules/mavlink/mavlink_ftp.cpp b/src/modules/mavlink/mavlink_ftp.cpp
index 00c8df18c..f17497aa8 100644
--- a/src/modules/mavlink/mavlink_ftp.cpp
+++ b/src/modules/mavlink/mavlink_ftp.cpp
@@ -31,38 +31,39 @@
*
****************************************************************************/
+/// @file mavlink_ftp.cpp
+/// @author px4dev, Don Gagne <don@thegagnes.com>
+
#include <crc32.h>
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
#include <sys/stat.h>
+#include <errno.h>
#include "mavlink_ftp.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
-MavlinkFTP *MavlinkFTP::_server;
-
MavlinkFTP *
-MavlinkFTP::getServer()
+MavlinkFTP::get_server(void)
{
- // XXX this really cries out for some locking...
- if (_server == nullptr) {
- _server = new MavlinkFTP;
- }
- return _server;
+ static MavlinkFTP server;
+ return &server;
}
MavlinkFTP::MavlinkFTP() :
- _session_fds{},
- _workBufs{},
- _workFree{},
- _lock{}
+ _request_bufs{},
+ _request_queue{},
+ _request_queue_sem{},
+ _utRcvMsgFunc{},
+ _ftp_test{}
{
// initialise the request freelist
- dq_init(&_workFree);
- sem_init(&_lock, 0, 1);
+ dq_init(&_request_queue);
+ sem_init(&_request_queue_sem, 0, 1);
// initialize session list
for (size_t i=0; i<kMaxSession; i++) {
@@ -71,161 +72,258 @@ MavlinkFTP::MavlinkFTP() :
// drop work entries onto the free list
for (unsigned i = 0; i < kRequestQueueSize; i++) {
- _qFree(&_workBufs[i]);
+ _return_request(&_request_bufs[i]);
}
}
+#ifdef MAVLINK_FTP_UNIT_TEST
+void
+MavlinkFTP::set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test)
+{
+ _utRcvMsgFunc = rcvMsgFunc;
+ _ftp_test = ftp_test;
+}
+#endif
+
void
MavlinkFTP::handle_message(Mavlink* mavlink, mavlink_message_t *msg)
{
// get a free request
- auto req = _dqFree();
+ struct Request* req = _get_request();
// if we couldn't get a request slot, just drop it
- if (req != nullptr) {
-
- // decode the request
- if (req->decode(mavlink, msg)) {
+ if (req == nullptr) {
+ warnx("Dropping FTP request: queue full\n");
+ return;
+ }
- // and queue it for the worker
- work_queue(LPWORK, &req->work, &MavlinkFTP::_workerTrampoline, req, 0);
- } else {
- _qFree(req);
+ if (msg->msgid == MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
+ mavlink_msg_file_transfer_protocol_decode(msg, &req->message);
+
+#ifdef MAVLINK_FTP_UNIT_TEST
+ if (!_utRcvMsgFunc) {
+ warnx("Incorrectly written unit test\n");
+ return;
+ }
+ // We use fake ids when unit testing
+ req->serverSystemId = MavlinkFtpTest::serverSystemId;
+ req->serverComponentId = MavlinkFtpTest::serverComponentId;
+ req->serverChannel = MavlinkFtpTest::serverChannel;
+#else
+ // Not unit testing, use the real thing
+ req->serverSystemId = mavlink->get_system_id();
+ req->serverComponentId = mavlink->get_component_id();
+ req->serverChannel = mavlink->get_channel();
+#endif
+
+ // This is the system id we want to target when sending
+ req->targetSystemId = msg->sysid;
+
+ if (req->message.target_system == req->serverSystemId) {
+ req->mavlink = mavlink;
+#ifdef MAVLINK_FTP_UNIT_TEST
+ // We are running in Unit Test mode. Don't queue, just call _worket directly.
+ _process_request(req);
+#else
+ // We are running in normal mode. Queue the request to the worker
+ work_queue(LPWORK, &req->work, &MavlinkFTP::_worker_trampoline, req, 0);
+#endif
+ return;
}
}
+
+ _return_request(req);
}
+/// @brief Queued static work queue routine to handle mavlink messages
void
-MavlinkFTP::_workerTrampoline(void *arg)
+MavlinkFTP::_worker_trampoline(void *arg)
{
- auto req = reinterpret_cast<Request *>(arg);
- auto server = MavlinkFTP::getServer();
+ Request* req = reinterpret_cast<Request *>(arg);
+ MavlinkFTP* server = MavlinkFTP::get_server();
// call the server worker with the work item
- server->_worker(req);
+ server->_process_request(req);
}
+/// @brief Processes an FTP message
void
-MavlinkFTP::_worker(Request *req)
+MavlinkFTP::_process_request(Request *req)
{
- auto hdr = req->header();
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
+
ErrorCode errorCode = kErrNone;
- uint32_t messageCRC;
// basic sanity checks; must validate length before use
- if ((hdr->magic != kProtocolMagic) || (hdr->size > kMaxDataLength)) {
- errorCode = kErrNoRequest;
- goto out;
- }
-
- // check request CRC to make sure this is one of ours
- messageCRC = hdr->crc32;
- hdr->crc32 = 0;
- if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
- errorCode = kErrNoRequest;
+ if (payload->size > kMaxDataLength) {
+ errorCode = kErrInvalidDataSize;
goto out;
- warnx("ftp: bad crc");
}
#ifdef MAVLINK_FTP_DEBUG
- printf("ftp: channel %u opc %u size %u offset %u\n", req->channel(), hdr->opcode, hdr->size, hdr->offset);
+ printf("ftp: channel %u opc %u size %u offset %u\n", req->serverChannel, payload->opcode, payload->size, payload->offset);
#endif
- switch (hdr->opcode) {
+ switch (payload->opcode) {
case kCmdNone:
break;
- case kCmdTerminate:
- errorCode = _workTerminate(req);
+ case kCmdTerminateSession:
+ errorCode = _workTerminate(payload);
+ break;
+
+ case kCmdResetSessions:
+ errorCode = _workReset(payload);
+ break;
+
+ case kCmdListDirectory:
+ errorCode = _workList(payload);
+ break;
+
+ case kCmdOpenFileRO:
+ errorCode = _workOpen(payload, O_RDONLY);
+ break;
+
+ case kCmdCreateFile:
+ errorCode = _workOpen(payload, O_CREAT | O_EXCL | O_WRONLY);
+ break;
+
+ case kCmdOpenFileWO:
+ errorCode = _workOpen(payload, O_CREAT | O_WRONLY);
break;
- case kCmdReset:
- errorCode = _workReset();
+ case kCmdReadFile:
+ errorCode = _workRead(payload);
break;
- case kCmdList:
- errorCode = _workList(req);
+ case kCmdWriteFile:
+ errorCode = _workWrite(payload);
break;
- case kCmdOpen:
- errorCode = _workOpen(req, false);
+ case kCmdRemoveFile:
+ errorCode = _workRemoveFile(payload);
break;
- case kCmdCreate:
- errorCode = _workOpen(req, true);
+ case kCmdRename:
+ errorCode = _workRename(payload);
break;
- case kCmdRead:
- errorCode = _workRead(req);
+ case kCmdTruncateFile:
+ errorCode = _workTruncateFile(payload);
break;
- case kCmdWrite:
- errorCode = _workWrite(req);
+ case kCmdCreateDirectory:
+ errorCode = _workCreateDirectory(payload);
break;
+
+ case kCmdRemoveDirectory:
+ errorCode = _workRemoveDirectory(payload);
+ break;
+
- case kCmdRemove:
- errorCode = _workRemove(req);
+ case kCmdCalcFileCRC32:
+ errorCode = _workCalcFileCRC32(payload);
break;
default:
- errorCode = kErrNoRequest;
+ errorCode = kErrUnknownCommand;
break;
}
out:
// handle success vs. error
if (errorCode == kErrNone) {
- hdr->opcode = kRspAck;
+ payload->req_opcode = payload->opcode;
+ payload->opcode = kRspAck;
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: ack\n");
#endif
} else {
+ int r_errno = errno;
warnx("FTP: nak %u", errorCode);
- hdr->opcode = kRspNak;
- hdr->size = 1;
- hdr->data[0] = errorCode;
+ payload->req_opcode = payload->opcode;
+ payload->opcode = kRspNak;
+ payload->size = 1;
+ payload->data[0] = errorCode;
+ if (errorCode == kErrFailErrno) {
+ payload->size = 2;
+ payload->data[1] = r_errno;
+ }
}
+
// respond to the request
_reply(req);
- // free the request buffer back to the freelist
- _qFree(req);
+ _return_request(req);
}
+/// @brief Sends the specified FTP reponse message out through mavlink
void
MavlinkFTP::_reply(Request *req)
{
- auto hdr = req->header();
+ PayloadHeader *payload = reinterpret_cast<PayloadHeader *>(&req->message.payload[0]);
- hdr->magic = kProtocolMagic;
+ payload->seqNumber = payload->seqNumber + 1;
- // message is assumed to be already constructed in the request buffer, so generate the CRC
- hdr->crc32 = 0;
- hdr->crc32 = crc32(req->rawData(), req->dataSize());
+ mavlink_message_t msg;
+ msg.checksum = 0;
+#ifndef MAVLINK_FTP_UNIT_TEST
+ uint16_t len =
+#endif
+ mavlink_msg_file_transfer_protocol_pack_chan(req->serverSystemId, // Sender system id
+ req->serverComponentId, // Sender component id
+ req->serverChannel, // Channel to send on
+ &msg, // Message to pack payload into
+ 0, // Target network
+ req->targetSystemId, // Target system id
+ 0, // Target component id
+ (const uint8_t*)payload); // Payload to pack into message
+
+ bool success = true;
+#ifdef MAVLINK_FTP_UNIT_TEST
+ // Unit test hook is set, call that instead
+ _utRcvMsgFunc(&msg, _ftp_test);
+#else
+ Mavlink *mavlink = req->mavlink;
+
+ mavlink->lockMessageBufferMutex();
+ success = mavlink->message_buffer_write(&msg, len);
+ mavlink->unlockMessageBufferMutex();
+
+#endif
- // then pack and send the reply back to the request source
- req->reply();
+ if (!success) {
+ warnx("FTP TX ERR");
+ }
+#ifdef MAVLINK_FTP_DEBUG
+ else {
+ warnx("wrote: sys: %d, comp: %d, chan: %d, checksum: %d",
+ req->serverSystemId,
+ req->serverComponentId,
+ req->serverChannel,
+ msg.checksum);
+ }
+#endif
}
+/// @brief Responds to a List command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workList(Request *req)
+MavlinkFTP::_workList(PayloadHeader* payload)
{
- auto hdr = req->header();
-
char dirPath[kMaxDataLength];
- strncpy(dirPath, req->dataAsCString(), kMaxDataLength);
+ strncpy(dirPath, _data_as_cstring(payload), kMaxDataLength);
DIR *dp = opendir(dirPath);
if (dp == nullptr) {
warnx("FTP: can't open path '%s'", dirPath);
- return kErrNotDir;
+ return kErrFailErrno;
}
#ifdef MAVLINK_FTP_DEBUG
- warnx("FTP: list %s offset %d", dirPath, hdr->offset);
+ warnx("FTP: list %s offset %d", dirPath, payload->offset);
#endif
ErrorCode errorCode = kErrNone;
@@ -233,19 +331,19 @@ MavlinkFTP::_workList(Request *req)
unsigned offset = 0;
// move to the requested offset
- seekdir(dp, hdr->offset);
+ seekdir(dp, payload->offset);
for (;;) {
// read the directory entry
if (readdir_r(dp, &entry, &result)) {
warnx("FTP: list %s readdir_r failure\n", dirPath);
- errorCode = kErrIO;
+ errorCode = kErrFailErrno;
break;
}
// no more entries?
if (result == nullptr) {
- if (hdr->offset != 0 && offset == 0) {
+ if (payload->offset != 0 && offset == 0) {
// User is requesting subsequent dir entries but there were none. This means the user asked
// to seek past EOF.
errorCode = kErrEOF;
@@ -270,14 +368,22 @@ MavlinkFTP::_workList(Request *req)
}
break;
case DTYPE_DIRECTORY:
- direntType = kDirentDir;
+ if (strcmp(entry.d_name, ".") == 0 || strcmp(entry.d_name, "..") == 0) {
+ // Don't bother sending these back
+ direntType = kDirentSkip;
+ } else {
+ direntType = kDirentDir;
+ }
break;
default:
- direntType = kDirentUnknown;
- break;
+ // We only send back file and diretory entries, skip everything else
+ direntType = kDirentSkip;
}
- if (entry.d_type == DTYPE_FILE) {
+ if (direntType == kDirentSkip) {
+ // Skip send only dirent identifier
+ buf[0] = '\0';
+ } else if (direntType == kDirentFile) {
// Files send filename and file length
snprintf(buf, sizeof(buf), "%s\t%d", entry.d_name, fileSize);
} else {
@@ -293,145 +399,230 @@ MavlinkFTP::_workList(Request *req)
}
// Move the data into the buffer
- hdr->data[offset++] = direntType;
- strcpy((char *)&hdr->data[offset], buf);
+ payload->data[offset++] = direntType;
+ strcpy((char *)&payload->data[offset], buf);
#ifdef MAVLINK_FTP_DEBUG
- printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
+ printf("FTP: list %s %s\n", dirPath, (char *)&payload->data[offset-1]);
#endif
offset += nameLen + 1;
}
closedir(dp);
- hdr->size = offset;
+ payload->size = offset;
return errorCode;
}
+/// @brief Responds to an Open command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workOpen(Request *req, bool create)
+MavlinkFTP::_workOpen(PayloadHeader* payload, int oflag)
{
- auto hdr = req->header();
-
- int session_index = _findUnusedSession();
+ int session_index = _find_unused_session();
if (session_index < 0) {
- return kErrNoSession;
+ warnx("FTP: Open failed - out of sessions\n");
+ return kErrNoSessionsAvailable;
}
-
+ char *filename = _data_as_cstring(payload);
+
uint32_t fileSize = 0;
- if (!create) {
- struct stat st;
- if (stat(req->dataAsCString(), &st) != 0) {
- return kErrNotFile;
- }
- fileSize = st.st_size;
+ struct stat st;
+ if (stat(filename, &st) != 0) {
+ // fail only if requested open for read
+ if (oflag & O_RDONLY)
+ return kErrFailErrno;
+ else
+ st.st_size = 0;
}
+ fileSize = st.st_size;
- int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
-
- int fd = ::open(req->dataAsCString(), oflag);
+ int fd = ::open(filename, oflag);
if (fd < 0) {
- return create ? kErrPerm : kErrNotFile;
+ return kErrFailErrno;
}
_session_fds[session_index] = fd;
- hdr->session = session_index;
- if (create) {
- hdr->size = 0;
- } else {
- hdr->size = sizeof(uint32_t);
- *((uint32_t*)hdr->data) = fileSize;
- }
+ payload->session = session_index;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = fileSize;
return kErrNone;
}
+/// @brief Responds to a Read command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRead(Request *req)
+MavlinkFTP::_workRead(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- int session_index = hdr->session;
+ int session_index = payload->session;
- if (!_validSession(session_index)) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
// Seek to the specified position
#ifdef MAVLINK_FTP_DEBUG
- warnx("seek %d", hdr->offset);
+ warnx("seek %d", payload->offset);
#endif
- if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
+ if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) {
// Unable to see to the specified location
warnx("seek fail");
return kErrEOF;
}
- int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
+ int bytes_read = ::read(_session_fds[session_index], &payload->data[0], kMaxDataLength);
if (bytes_read < 0) {
// Negative return indicates error other than eof
warnx("read fail %d", bytes_read);
- return kErrIO;
+ return kErrFailErrno;
}
- hdr->size = bytes_read;
+ payload->size = bytes_read;
return kErrNone;
}
+/// @brief Responds to a Write command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workWrite(Request *req)
+MavlinkFTP::_workWrite(PayloadHeader* payload)
{
-#if 0
- // NYI: Coming soon
- auto hdr = req->header();
+ int session_index = payload->session;
- // look up session
- auto session = getSession(hdr->session);
- if (session == nullptr) {
- return kErrNoSession;
+ if (!_valid_session(session_index)) {
+ return kErrInvalidSession;
}
- // append to file
- int result = session->append(hdr->offset, &hdr->data[0], hdr->size);
+ // Seek to the specified position
+#ifdef MAVLINK_FTP_DEBUG
+ warnx("seek %d", payload->offset);
+#endif
+ if (lseek(_session_fds[session_index], payload->offset, SEEK_SET) < 0) {
+ // Unable to see to the specified location
+ warnx("seek fail");
+ return kErrFailErrno;
+ }
- if (result < 0) {
- // XXX might also be no space, I/O, etc.
- return kErrNotAppend;
+ int bytes_written = ::write(_session_fds[session_index], &payload->data[0], payload->size);
+ if (bytes_written < 0) {
+ // Negative return indicates error other than eof
+ warnx("write fail %d", bytes_written);
+ return kErrFailErrno;
}
- hdr->size = result;
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = bytes_written;
+
return kErrNone;
-#else
- return kErrPerm;
-#endif
}
+/// @brief Responds to a RemoveFile command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workRemove(Request *req)
+MavlinkFTP::_workRemoveFile(PayloadHeader* payload)
{
- //auto hdr = req->header();
+ char file[kMaxDataLength];
+ strncpy(file, _data_as_cstring(payload), kMaxDataLength);
+
+ if (unlink(file) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a TruncateFile command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workTruncateFile(PayloadHeader* payload)
+{
+ char file[kMaxDataLength];
+ const char temp_file[] = "/fs/microsd/.trunc.tmp";
+ strncpy(file, _data_as_cstring(payload), kMaxDataLength);
+ payload->size = 0;
+
+ // emulate truncate(file, payload->offset) by
+ // copying to temp and overwrite with O_TRUNC flag.
+
+ struct stat st;
+ if (stat(file, &st) != 0) {
+ return kErrFailErrno;
+ }
+
+ if (!S_ISREG(st.st_mode)) {
+ errno = EISDIR;
+ return kErrFailErrno;
+ }
+
+ // check perms allow us to write (not romfs)
+ if (!(st.st_mode & (S_IWUSR | S_IWGRP | S_IWOTH))) {
+ errno = EROFS;
+ return kErrFailErrno;
+ }
+
+ if (payload->offset == (unsigned)st.st_size) {
+ // nothing to do
+ return kErrNone;
+ }
+ else if (payload->offset == 0) {
+ // 1: truncate all data
+ int fd = ::open(file, O_TRUNC | O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ ::close(fd);
+ return kErrNone;
+ }
+ else if (payload->offset > (unsigned)st.st_size) {
+ // 2: extend file
+ int fd = ::open(file, O_WRONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
- // for now, send error reply
- return kErrPerm;
+ if (lseek(fd, payload->offset - 1, SEEK_SET) < 0) {
+ ::close(fd);
+ return kErrFailErrno;
+ }
+
+ bool ok = 1 == ::write(fd, "", 1);
+ ::close(fd);
+
+ return (ok)? kErrNone : kErrFailErrno;
+ }
+ else {
+ // 3: truncate
+ if (_copy_file(file, temp_file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (_copy_file(temp_file, file, payload->offset) != 0) {
+ return kErrFailErrno;
+ }
+ if (::unlink(temp_file) != 0) {
+ return kErrFailErrno;
+ }
+
+ return kErrNone;
+ }
}
+/// @brief Responds to a Terminate command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workTerminate(Request *req)
+MavlinkFTP::_workTerminate(PayloadHeader* payload)
{
- auto hdr = req->header();
-
- if (!_validSession(hdr->session)) {
- return kErrNoSession;
+ if (!_valid_session(payload->session)) {
+ return kErrInvalidSession;
}
- ::close(_session_fds[hdr->session]);
+ ::close(_session_fds[payload->session]);
+ _session_fds[payload->session] = -1;
+
+ payload->size = 0;
return kErrNone;
}
+/// @brief Responds to a Reset command
MavlinkFTP::ErrorCode
-MavlinkFTP::_workReset(void)
+MavlinkFTP::_workReset(PayloadHeader* payload)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] != -1) {
@@ -440,11 +631,104 @@ MavlinkFTP::_workReset(void)
}
}
+ payload->size = 0;
+
+ return kErrNone;
+}
+
+/// @brief Responds to a Rename command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRename(PayloadHeader* payload)
+{
+ char oldpath[kMaxDataLength];
+ char newpath[kMaxDataLength];
+
+ char *ptr = _data_as_cstring(payload);
+ size_t oldpath_sz = strlen(ptr);
+
+ if (oldpath_sz == payload->size) {
+ // no newpath
+ errno = EINVAL;
+ return kErrFailErrno;
+ }
+
+ strncpy(oldpath, ptr, kMaxDataLength);
+ strncpy(newpath, ptr + oldpath_sz + 1, kMaxDataLength);
+
+ if (rename(oldpath, newpath) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a RemoveDirectory command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workRemoveDirectory(PayloadHeader* payload)
+{
+ char dir[kMaxDataLength];
+ strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
+
+ if (rmdir(dir) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a CreateDirectory command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workCreateDirectory(PayloadHeader* payload)
+{
+ char dir[kMaxDataLength];
+ strncpy(dir, _data_as_cstring(payload), kMaxDataLength);
+
+ if (mkdir(dir, S_IRWXU | S_IRWXG | S_IRWXO) == 0) {
+ payload->size = 0;
+ return kErrNone;
+ } else {
+ return kErrFailErrno;
+ }
+}
+
+/// @brief Responds to a CalcFileCRC32 command
+MavlinkFTP::ErrorCode
+MavlinkFTP::_workCalcFileCRC32(PayloadHeader* payload)
+{
+ char file_buf[256];
+ uint32_t checksum = 0;
+ ssize_t bytes_read;
+ strncpy(file_buf, _data_as_cstring(payload), kMaxDataLength);
+
+ int fd = ::open(file_buf, O_RDONLY);
+ if (fd < 0) {
+ return kErrFailErrno;
+ }
+
+ do {
+ bytes_read = ::read(fd, file_buf, sizeof(file_buf));
+ if (bytes_read < 0) {
+ int r_errno = errno;
+ ::close(fd);
+ errno = r_errno;
+ return kErrFailErrno;
+ }
+
+ checksum = crc32part((uint8_t*)file_buf, bytes_read, checksum);
+ } while (bytes_read == sizeof(file_buf));
+
+ ::close(fd);
+
+ payload->size = sizeof(uint32_t);
+ *((uint32_t*)payload->data) = checksum;
return kErrNone;
}
+/// @brief Returns true if the specified session is a valid open session
bool
-MavlinkFTP::_validSession(unsigned index)
+MavlinkFTP::_valid_session(unsigned index)
{
if ((index >= kMaxSession) || (_session_fds[index] < 0)) {
return false;
@@ -452,8 +736,9 @@ MavlinkFTP::_validSession(unsigned index)
return true;
}
+/// @brief Returns an unused session index
int
-MavlinkFTP::_findUnusedSession(void)
+MavlinkFTP::_find_unused_session(void)
{
for (size_t i=0; i<kMaxSession; i++) {
if (_session_fds[i] == -1) {
@@ -464,16 +749,105 @@ MavlinkFTP::_findUnusedSession(void)
return -1;
}
+/// @brief Guarantees that the payload data is null terminated.
+/// @return Returns a pointer to the payload data as a char *
char *
-MavlinkFTP::Request::dataAsCString()
+MavlinkFTP::_data_as_cstring(PayloadHeader* payload)
{
// guarantee nul termination
- if (header()->size < kMaxDataLength) {
- requestData()[header()->size] = '\0';
+ if (payload->size < kMaxDataLength) {
+ payload->data[payload->size] = '\0';
} else {
- requestData()[kMaxDataLength - 1] = '\0';
+ payload->data[kMaxDataLength - 1] = '\0';
}
// and return data
- return (char *)&(header()->data[0]);
+ return (char *)&(payload->data[0]);
+}
+
+/// @brief Returns a unused Request entry. NULL if none available.
+MavlinkFTP::Request *
+MavlinkFTP::_get_request(void)
+{
+ _lock_request_queue();
+ Request* req = reinterpret_cast<Request *>(dq_remfirst(&_request_queue));
+ _unlock_request_queue();
+ return req;
+}
+
+/// @brief Locks a semaphore to provide exclusive access to the request queue
+void
+MavlinkFTP::_lock_request_queue(void)
+{
+ do {}
+ while (sem_wait(&_request_queue_sem) != 0);
+}
+
+/// @brief Unlocks the semaphore providing exclusive access to the request queue
+void
+MavlinkFTP::_unlock_request_queue(void)
+{
+ sem_post(&_request_queue_sem);
+}
+
+/// @brief Returns a no longer needed request to the queue
+void
+MavlinkFTP::_return_request(Request *req)
+{
+ _lock_request_queue();
+ dq_addlast(&req->work.dq, &_request_queue);
+ _unlock_request_queue();
+}
+
+/// @brief Copy file (with limited space)
+int
+MavlinkFTP::_copy_file(const char *src_path, const char *dst_path, ssize_t length)
+{
+ char buff[512];
+ int src_fd = -1, dst_fd = -1;
+ int op_errno = 0;
+
+ src_fd = ::open(src_path, O_RDONLY);
+ if (src_fd < 0) {
+ return -1;
+ }
+
+ dst_fd = ::open(dst_path, O_CREAT | O_TRUNC | O_WRONLY);
+ if (dst_fd < 0) {
+ op_errno = errno;
+ ::close(src_fd);
+ errno = op_errno;
+ return -1;
+ }
+
+ while (length > 0) {
+ ssize_t bytes_read, bytes_written;
+ size_t blen = (length > sizeof(buff))? sizeof(buff) : length;
+
+ bytes_read = ::read(src_fd, buff, blen);
+ if (bytes_read == 0) {
+ // EOF
+ break;
+ }
+ else if (bytes_read < 0) {
+ warnx("cp: read");
+ op_errno = errno;
+ break;
+ }
+
+ bytes_written = ::write(dst_fd, buff, bytes_read);
+ if (bytes_written != bytes_read) {
+ warnx("cp: short write");
+ op_errno = errno;
+ break;
+ }
+
+ length -= bytes_written;
+ }
+
+ ::close(src_fd);
+ ::close(dst_fd);
+
+ errno = op_errno;
+ return (length > 0)? -1 : 0;
}
diff --git a/src/modules/mavlink/mavlink_ftp.h b/src/modules/mavlink/mavlink_ftp.h
index 43de89de9..bef6775a9 100644
--- a/src/modules/mavlink/mavlink_ftp.h
+++ b/src/modules/mavlink/mavlink_ftp.h
@@ -33,20 +33,8 @@
#pragma once
-/**
- * @file mavlink_ftp.h
- *
- * MAVLink remote file server.
- *
- * Messages are wrapped in ENCAPSULATED_DATA messages. Every message includes
- * a session ID and sequence number.
- *
- * A limited number of requests (currently 2) may be outstanding at a time.
- * Additional messages will be discarded.
- *
- * Messages consist of a fixed header, followed by a data area.
- *
- */
+/// @file mavlink_ftp.h
+/// @author px4dev, Don Gagne <don@thegagnes.com>
#include <dirent.h>
#include <queue.h>
@@ -57,174 +45,136 @@
#include "mavlink_messages.h"
#include "mavlink_main.h"
+class MavlinkFtpTest;
+
+/// @brief MAVLink remote file server. Support FTP like commands using MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL message.
+/// A limited number of requests (kRequestQueueSize) may be outstanding at a time. Additional messages will be discarded.
class MavlinkFTP
{
public:
+ /// @brief Returns the one Mavlink FTP server in the system.
+ static MavlinkFTP* get_server(void);
+
+ /// @brief Contructor is only public so unit test code can new objects.
MavlinkFTP();
-
- static MavlinkFTP *getServer();
-
- // static interface
- void handle_message(Mavlink* mavlink,
- mavlink_message_t *msg);
-
-private:
-
- static const unsigned kRequestQueueSize = 2;
-
- static MavlinkFTP *_server;
-
- struct RequestHeader
- {
- uint8_t magic;
- uint8_t session;
- uint8_t opcode;
- uint8_t size;
- uint32_t crc32;
- uint32_t offset;
- uint8_t data[];
- };
-
+
+ /// @brief Adds the specified message to the work queue.
+ void handle_message(Mavlink* mavlink, mavlink_message_t *msg);
+
+ typedef void (*ReceiveMessageFunc_t)(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ /// @brief Sets up the server to run in unit test mode.
+ /// @param rcvmsgFunc Function which will be called to handle outgoing mavlink messages.
+ /// @param ftp_test MavlinkFtpTest object which the function is associated with
+ void set_unittest_worker(ReceiveMessageFunc_t rcvMsgFunc, MavlinkFtpTest *ftp_test);
+
+ /// @brief This is the payload which is in mavlink_file_transfer_protocol_t.payload. We pad the structure ourselves to
+ /// 32 bit alignment to avoid usage of any pack pragmas.
+ struct PayloadHeader
+ {
+ uint16_t seqNumber; ///< sequence number for message
+ uint8_t session; ///< Session id for read and write commands
+ uint8_t opcode; ///< Command opcode
+ uint8_t size; ///< Size of data
+ uint8_t req_opcode; ///< Request opcode returned in kRspAck, kRspNak message
+ uint8_t padding[2]; ///< 32 bit aligment padding
+ uint32_t offset; ///< Offsets for List and Read commands
+ uint8_t data[]; ///< command data, varies by Opcode
+ };
+
+ /// @brief Command opcodes
enum Opcode : uint8_t
{
- kCmdNone, // ignored, always acked
- kCmdTerminate, // releases sessionID, closes file
- kCmdReset, // terminates all sessions
- kCmdList, // list files in <path> from <offset>
- kCmdOpen, // opens <path> for reading, returns <session>
- kCmdRead, // reads <size> bytes from <offset> in <session>
- kCmdCreate, // creates <path> for writing, returns <session>
- kCmdWrite, // appends <size> bytes at <offset> in <session>
- kCmdRemove, // remove file (only if created by server?)
-
- kRspAck,
- kRspNak
+ kCmdNone, ///< ignored, always acked
+ kCmdTerminateSession, ///< Terminates open Read session
+ kCmdResetSessions, ///< Terminates all open Read sessions
+ kCmdListDirectory, ///< List files in <path> from <offset>
+ kCmdOpenFileRO, ///< Opens file at <path> for reading, returns <session>
+ kCmdReadFile, ///< Reads <size> bytes from <offset> in <session>
+ kCmdCreateFile, ///< Creates file at <path> for writing, returns <session>
+ kCmdWriteFile, ///< Writes <size> bytes to <offset> in <session>
+ kCmdRemoveFile, ///< Remove file at <path>
+ kCmdCreateDirectory, ///< Creates directory at <path>
+ kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
+ kCmdOpenFileWO, ///< Opens file at <path> for writing, returns <session>
+ kCmdTruncateFile, ///< Truncate file at <path> to <offset> length
+ kCmdRename, ///< Rename <path1> to <path2>
+ kCmdCalcFileCRC32, ///< Calculate CRC32 for file at <path>
+
+ kRspAck = 128, ///< Ack response
+ kRspNak ///< Nak response
};
-
+
+ /// @brief Error codes returned in Nak response PayloadHeader.data[0].
enum ErrorCode : uint8_t
- {
+ {
kErrNone,
- kErrNoRequest,
- kErrNoSession,
- kErrSequence,
- kErrNotDir,
- kErrNotFile,
- kErrEOF,
- kErrNotAppend,
- kErrTooBig,
- kErrIO,
- kErrPerm
- };
-
- int _findUnusedSession(void);
- bool _validSession(unsigned index);
-
- static const unsigned kMaxSession = 2;
- int _session_fds[kMaxSession];
-
- class Request
+ kErrFail, ///< Unknown failure
+ kErrFailErrno, ///< Command failed, errno sent back in PayloadHeader.data[1]
+ kErrInvalidDataSize, ///< PayloadHeader.size is invalid
+ kErrInvalidSession, ///< Session is not currently open
+ kErrNoSessionsAvailable, ///< All available Sessions in use
+ kErrEOF, ///< Offset past end of file for List and Read commands
+ kErrUnknownCommand ///< Unknown command opcode
+ };
+
+private:
+ /// @brief Unit of work which is queued to work_queue
+ struct Request
{
- public:
- union {
- dq_entry_t entry;
- work_s work;
- };
-
- bool decode(Mavlink *mavlink, mavlink_message_t *fromMessage) {
- if (fromMessage->msgid == MAVLINK_MSG_ID_ENCAPSULATED_DATA) {
- _mavlink = mavlink;
- mavlink_msg_encapsulated_data_decode(fromMessage, &_message);
- return true;
- }
- return false;
- }
-
- void reply() {
-
- // XXX the proper way would be an IOCTL / uORB call, rather than exploiting the
- // flat memory architecture, as we're operating between threads here.
- mavlink_message_t msg;
- msg.checksum = 0;
- unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
- _mavlink->get_channel(), &msg, sequence()+1, rawData());
-
- _mavlink->lockMessageBufferMutex();
- bool success = _mavlink->message_buffer_write(&msg, len);
- _mavlink->unlockMessageBufferMutex();
-
- if (!success) {
- warnx("FTP TX ERR");
- }
-#ifdef MAVLINK_FTP_DEBUG
- else {
- warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
- _mavlink->get_system_id(),
- _mavlink->get_component_id(),
- _mavlink->get_channel(),
- len,
- msg.checksum);
- }
-#endif
- }
-
- uint8_t *rawData() { return &_message.data[0]; }
- RequestHeader *header() { return reinterpret_cast<RequestHeader *>(&_message.data[0]); }
- uint8_t *requestData() { return &(header()->data[0]); }
- unsigned dataSize() { return header()->size + sizeof(RequestHeader); }
- uint16_t sequence() const { return _message.seqnr; }
- mavlink_channel_t channel() { return _mavlink->get_channel(); }
-
- char *dataAsCString();
-
- private:
- Mavlink *_mavlink;
- mavlink_encapsulated_data_t _message;
-
+ work_s work; ///< work queue entry
+ Mavlink *mavlink; ///< Mavlink to reply to
+ uint8_t serverSystemId; ///< System ID to send from
+ uint8_t serverComponentId; ///< Component ID to send from
+ uint8_t serverChannel; ///< Channel to send to
+ uint8_t targetSystemId; ///< System ID to target reply to
+
+ mavlink_file_transfer_protocol_t message; ///< Protocol message
};
-
- static const uint8_t kProtocolMagic = 'f';
- static const char kDirentFile = 'F';
- static const char kDirentDir = 'D';
- static const char kDirentUnknown = 'U';
- static const uint8_t kMaxDataLength = MAVLINK_MSG_ENCAPSULATED_DATA_FIELD_DATA_LEN - sizeof(RequestHeader);
-
- /// Request worker; runs on the low-priority work queue to service
- /// remote requests.
- ///
- static void _workerTrampoline(void *arg);
- void _worker(Request *req);
-
- /// Reply to a request (XXX should be a Request method)
- ///
- void _reply(Request *req);
-
- ErrorCode _workList(Request *req);
- ErrorCode _workOpen(Request *req, bool create);
- ErrorCode _workRead(Request *req);
- ErrorCode _workWrite(Request *req);
- ErrorCode _workRemove(Request *req);
- ErrorCode _workTerminate(Request *req);
- ErrorCode _workReset();
-
- // work freelist
- Request _workBufs[kRequestQueueSize];
- dq_queue_t _workFree;
- sem_t _lock;
-
- void _qLock() { do {} while (sem_wait(&_lock) != 0); }
- void _qUnlock() { sem_post(&_lock); }
-
- void _qFree(Request *req) {
- _qLock();
- dq_addlast(&req->entry, &_workFree);
- _qUnlock();
- }
-
- Request *_dqFree() {
- _qLock();
- auto req = reinterpret_cast<Request *>(dq_remfirst(&_workFree));
- _qUnlock();
- return req;
- }
-
+
+ Request *_get_request(void);
+ void _return_request(Request *req);
+ void _lock_request_queue(void);
+ void _unlock_request_queue(void);
+
+ char *_data_as_cstring(PayloadHeader* payload);
+
+ static void _worker_trampoline(void *arg);
+ void _process_request(Request *req);
+ void _reply(Request *req);
+ int _copy_file(const char *src_path, const char *dst_path, ssize_t length);
+
+ ErrorCode _workList(PayloadHeader *payload);
+ ErrorCode _workOpen(PayloadHeader *payload, int oflag);
+ ErrorCode _workRead(PayloadHeader *payload);
+ ErrorCode _workWrite(PayloadHeader *payload);
+ ErrorCode _workTerminate(PayloadHeader *payload);
+ ErrorCode _workReset(PayloadHeader* payload);
+ ErrorCode _workRemoveDirectory(PayloadHeader *payload);
+ ErrorCode _workCreateDirectory(PayloadHeader *payload);
+ ErrorCode _workRemoveFile(PayloadHeader *payload);
+ ErrorCode _workTruncateFile(PayloadHeader *payload);
+ ErrorCode _workRename(PayloadHeader *payload);
+ ErrorCode _workCalcFileCRC32(PayloadHeader *payload);
+
+ static const unsigned kRequestQueueSize = 2; ///< Max number of queued requests
+ Request _request_bufs[kRequestQueueSize]; ///< Request buffers which hold work
+ dq_queue_t _request_queue; ///< Queue of available Request buffers
+ sem_t _request_queue_sem; ///< Semaphore for locking access to _request_queue
+
+ int _find_unused_session(void);
+ bool _valid_session(unsigned index);
+
+ static const char kDirentFile = 'F'; ///< Identifies File returned from List command
+ static const char kDirentDir = 'D'; ///< Identifies Directory returned from List command
+ static const char kDirentSkip = 'S'; ///< Identifies Skipped entry from List command
+
+ /// @brief Maximum data size in RequestHeader::data
+ static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(PayloadHeader);
+
+ static const unsigned kMaxSession = 2; ///< Max number of active sessions
+ int _session_fds[kMaxSession]; ///< Session file descriptors, 0 for empty slot
+
+ ReceiveMessageFunc_t _utRcvMsgFunc; ///< Unit test override for mavlink message sending
+ MavlinkFtpTest *_ftp_test; ///< Additional parameter to _utRcvMsgFunc;
};
diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp
index 4b97aa4fc..4155d6bf4 100644
--- a/src/modules/mavlink/mavlink_main.cpp
+++ b/src/modules/mavlink/mavlink_main.cpp
@@ -1403,14 +1403,14 @@ Mavlink::task_main(int argc, char *argv[])
configure_stream("POSITION_TARGET_GLOBAL_INT", 3.0f);
configure_stream("ATTITUDE_TARGET", 3.0f);
configure_stream("DISTANCE_SENSOR", 0.5f);
- configure_stream("OPTICAL_FLOW", 0.5f);
+ configure_stream("OPTICAL_FLOW", 20.0f);
break;
case MAVLINK_MODE_ONBOARD:
configure_stream("SYS_STATUS", 1.0f);
- configure_stream("ATTITUDE", 15.0f);
- configure_stream("GLOBAL_POSITION_INT", 15.0f);
- configure_stream("CAMERA_CAPTURE", 1.0f);
+ configure_stream("ATTITUDE", 50.0f);
+ configure_stream("GLOBAL_POSITION_INT", 50.0f);
+ configure_stream("CAMERA_CAPTURE", 2.0f);
break;
default:
diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp
index 5a92004a6..a2f3828ff 100644
--- a/src/modules/mavlink/mavlink_messages.cpp
+++ b/src/modules/mavlink/mavlink_messages.cpp
@@ -886,8 +886,8 @@ protected:
msg.eph = cm_uint16_from_m_float(gps.eph);
msg.epv = cm_uint16_from_m_float(gps.epv);
msg.vel = cm_uint16_from_m_float(gps.vel_m_s),
- msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
- msg.satellites_visible = gps.satellites_used;
+ msg.cog = _wrap_2pi(gps.cog_rad) * M_RAD_TO_DEG_F * 1e2f,
+ msg.satellites_visible = gps.satellites_used;
_mavlink->send_message(MAVLINK_MSG_ID_GPS_RAW_INT, &msg);
}
@@ -957,11 +957,11 @@ protected:
msg.lat = pos.lat * 1e7;
msg.lon = pos.lon * 1e7;
msg.alt = pos.alt * 1000.0f;
- msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
- msg.vx = pos.vel_n * 100.0f;
- msg.vy = pos.vel_e * 100.0f;
- msg.vz = pos.vel_d * 100.0f;
- msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
+ msg.relative_alt = (pos.alt - home.alt) * 1000.0f;
+ msg.vx = pos.vel_n * 100.0f;
+ msg.vy = pos.vel_e * 100.0f;
+ msg.vz = pos.vel_d * 100.0f;
+ msg.hdg = _wrap_2pi(pos.yaw) * M_RAD_TO_DEG_F * 100.0f;
_mavlink->send_message(MAVLINK_MSG_ID_GLOBAL_POSITION_INT, &msg);
}
@@ -1022,9 +1022,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
- msg.vx = pos.vx;
- msg.vy = pos.vy;
- msg.vz = pos.vz;
+ msg.vx = pos.vx;
+ msg.vy = pos.vy;
+ msg.vz = pos.vz;
_mavlink->send_message(MAVLINK_MSG_ID_LOCAL_POSITION_NED, &msg);
}
@@ -1085,9 +1085,9 @@ protected:
msg.x = pos.x;
msg.y = pos.y;
msg.z = pos.z;
- msg.roll = pos.roll;
- msg.pitch = pos.pitch;
- msg.yaw = pos.yaw;
+ msg.roll = pos.roll;
+ msg.pitch = pos.pitch;
+ msg.yaw = pos.yaw;
_mavlink->send_message(MAVLINK_MSG_ID_VICON_POSITION_ESTIMATE, &msg);
}
diff --git a/src/modules/mavlink/mavlink_mission.cpp b/src/modules/mavlink/mavlink_mission.cpp
index d436c95e9..a3c127cdc 100644
--- a/src/modules/mavlink/mavlink_mission.cpp
+++ b/src/modules/mavlink/mavlink_mission.cpp
@@ -798,10 +798,10 @@ int
MavlinkMissionManager::format_mavlink_mission_item(const struct mission_item_s *mission_item, mavlink_mission_item_t *mavlink_mission_item)
{
if (mission_item->altitude_is_relative) {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
} else {
- mavlink_mission_item->frame = MAV_FRAME_GLOBAL_RELATIVE_ALT;
+ mavlink_mission_item->frame = MAV_FRAME_GLOBAL;
}
switch (mission_item->nav_cmd) {
diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp
index 3ac4d3b03..e8d783847 100644
--- a/src/modules/mavlink/mavlink_receiver.cpp
+++ b/src/modules/mavlink/mavlink_receiver.cpp
@@ -55,6 +55,7 @@
#include <drivers/drv_gyro.h>
#include <drivers/drv_mag.h>
#include <drivers/drv_baro.h>
+#include <drivers/drv_range_finder.h>
#include <time.h>
#include <float.h>
#include <unistd.h>
@@ -103,6 +104,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
_battery_pub(-1),
_cmd_pub(-1),
_flow_pub(-1),
+ _range_pub(-1),
_offboard_control_sp_pub(-1),
_global_vel_sp_pub(-1),
_att_sp_pub(-1),
@@ -123,7 +125,7 @@ MavlinkReceiver::MavlinkReceiver(Mavlink *parent) :
{
// make sure the FTP server is started
- (void)MavlinkFTP::getServer();
+ (void)MavlinkFTP::get_server();
}
MavlinkReceiver::~MavlinkReceiver()
@@ -182,8 +184,8 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_request_data_stream(msg);
break;
- case MAVLINK_MSG_ID_ENCAPSULATED_DATA:
- MavlinkFTP::getServer()->handle_message(_mavlink, msg);
+ case MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL:
+ MavlinkFTP::get_server()->handle_message(_mavlink, msg);
break;
default:
@@ -210,6 +212,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg)
handle_message_hil_state_quaternion(msg);
break;
+ case MAVLINK_MSG_ID_HIL_OPTICAL_FLOW:
+ handle_message_hil_optical_flow(msg);
+ break;
+
default:
break;
}
@@ -374,6 +380,52 @@ MavlinkReceiver::handle_message_optical_flow(mavlink_message_t *msg)
}
void
+MavlinkReceiver::handle_message_hil_optical_flow(mavlink_message_t *msg)
+{
+ /* optical flow */
+ mavlink_hil_optical_flow_t flow;
+ mavlink_msg_hil_optical_flow_decode(msg, &flow);
+
+ struct optical_flow_s f;
+ memset(&f, 0, sizeof(f));
+
+ f.timestamp = hrt_absolute_time();
+ f.flow_timestamp = flow.time_usec;
+ f.flow_raw_x = flow.flow_x;
+ f.flow_raw_y = flow.flow_y;
+ f.flow_comp_x_m = flow.flow_comp_m_x;
+ f.flow_comp_y_m = flow.flow_comp_m_y;
+ f.ground_distance_m = flow.ground_distance;
+ f.quality = flow.quality;
+ f.sensor_id = flow.sensor_id;
+
+ if (_flow_pub < 0) {
+ _flow_pub = orb_advertise(ORB_ID(optical_flow), &f);
+
+ } else {
+ orb_publish(ORB_ID(optical_flow), _flow_pub, &f);
+ }
+
+ /* Use distance value for range finder report */
+ struct range_finder_report r;
+ memset(&r, 0, sizeof(f));
+
+ r.timestamp = hrt_absolute_time();
+ r.error_count = 0;
+ r.type = RANGE_FINDER_TYPE_LASER;
+ r.distance = flow.ground_distance;
+ r.minimum_distance = 0.0f;
+ r.maximum_distance = 40.0f; // this is set to match the typical range of real sensors, could be made configurable
+ r.valid = (r.distance > r.minimum_distance) && (r.distance < r.maximum_distance);
+
+ if (_range_pub < 0) {
+ _range_pub = orb_advertise(ORB_ID(sensor_range_finder), &r);
+ } else {
+ orb_publish(ORB_ID(sensor_range_finder), _range_pub, &r);
+ }
+}
+
+void
MavlinkReceiver::handle_message_set_mode(mavlink_message_t *msg)
{
mavlink_set_mode_t new_mode;
@@ -772,6 +824,8 @@ MavlinkReceiver::handle_message_radio_status(mavlink_message_t *msg)
tstatus.remote_noise = rstatus.remnoise;
tstatus.rxerrors = rstatus.rxerrors;
tstatus.fixed = rstatus.fixed;
+ tstatus.system_id = msg->sysid;
+ tstatus.component_id = msg->compid;
if (_telemetry_status_pub < 0) {
_telemetry_status_pub = orb_advertise(telemetry_status_orb_id[_mavlink->get_channel()], &tstatus);
diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h
index 8b616abd0..e5f2c6a73 100644
--- a/src/modules/mavlink/mavlink_receiver.h
+++ b/src/modules/mavlink/mavlink_receiver.h
@@ -113,6 +113,7 @@ private:
void handle_message_command_long(mavlink_message_t *msg);
void handle_message_command_int(mavlink_message_t *msg);
void handle_message_optical_flow(mavlink_message_t *msg);
+ void handle_message_hil_optical_flow(mavlink_message_t *msg);
void handle_message_set_mode(mavlink_message_t *msg);
void handle_message_vicon_position_estimate(mavlink_message_t *msg);
void handle_message_vision_position_estimate(mavlink_message_t *msg);
@@ -145,6 +146,7 @@ private:
orb_advert_t _battery_pub;
orb_advert_t _cmd_pub;
orb_advert_t _flow_pub;
+ orb_advert_t _range_pub;
orb_advert_t _offboard_control_sp_pub;
orb_advert_t _global_vel_sp_pub;
orb_advert_t _att_sp_pub;
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
new file mode 100644
index 000000000..a5fb2117e
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.cpp
@@ -0,0 +1,761 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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"
+
+/// @brief Test case file name for Read command. File are generated using mavlink_ftp_test_data.py
+const MavlinkFtpTest::ReadTestCase MavlinkFtpTest::_rgReadTestCases[] = {
+ { "/etc/unit_test_data/mavlink_tests/test_238.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) - 1}, // Read takes less than single packet
+ { "/etc/unit_test_data/mavlink_tests/test_239.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) }, // Read completely fills single packet
+ { "/etc/unit_test_data/mavlink_tests/test_240.data", MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader) + 1 }, // Read take two packets
+};
+
+const char MavlinkFtpTest::_unittest_microsd_dir[] = "/fs/microsd/ftp_unit_test_dir";
+const char MavlinkFtpTest::_unittest_microsd_file[] = "/fs/microsd/ftp_unit_test_dir/file";
+
+MavlinkFtpTest::MavlinkFtpTest() :
+ _ftp_server{},
+ _reply_msg{},
+ _lastOutgoingSeqNumber{}
+{
+}
+
+MavlinkFtpTest::~MavlinkFtpTest()
+{
+
+}
+
+/// @brief Called before every test to initialize the FTP Server.
+void MavlinkFtpTest::_init(void)
+{
+ _ftp_server = new MavlinkFTP;;
+ _ftp_server->set_unittest_worker(MavlinkFtpTest::receive_message, this);
+
+ _cleanup_microsd();
+}
+
+/// @brief Called after every test to take down the FTP Server.
+void MavlinkFtpTest::_cleanup(void)
+{
+ delete _ftp_server;
+
+ _cleanup_microsd();
+}
+
+/// @brief Tests for correct behavior of an Ack response.
+bool MavlinkFtpTest::_ack_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ 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
+ &ftp_msg, // Response from server
+ &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 opcpde.
+bool MavlinkFtpTest::_bad_opcode_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ 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
+ &ftp_msg, // Response from server
+ &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(void)
+{
+ mavlink_message_t msg;
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ 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(nullptr /* mavlink */, &msg);
+
+ if (!_decode_message(&_reply_msg, &ftp_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(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ char response1[] = "Dempty_dir|Ftest_238.data\t238|Ftest_239.data\t239|Ftest_240.data\t240";
+ char response2[] = "Ddev|Detc|Dfs|Dobj";
+
+ struct _testCase {
+ const char *dir; ///< Directory to run List command on
+ 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 },
+ { "/etc/unit_test_data/mavlink_tests", response1, 4, true },
+ { "/", response2, 4, true },
+ };
+
+ 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
+ &ftp_msg, // Response from server
+ &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
+ for (uint8_t j=0; j<reply->size-1; j++) {
+ if (reply->data[j] == 0) {
+ reply->data[j] = '|';
+ }
+ }
+
+ // Loop over returned directory entries trying to find then in the response list
+ char *dir;
+ int response_count = 0;
+ dir = strtok((char *)&reply->data[0], "|");
+ 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 payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to a List command on a valid directory, but with an offset that
+/// is beyond the last directory entry.
+bool MavlinkFtpTest::_list_eof_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/";
+
+ payload.opcode = MavlinkFTP::kCmdListDirectory;
+ payload.offset = 4; // offset past top level dirs
+
+ 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
+ &ftp_msg, // Response from server
+ &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 reponse to an Open command on a file which does not exist.
+bool MavlinkFtpTest::_open_badfile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *dir = "/foo"; // non-existent file
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ 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
+ &ftp_msg, // Response from server
+ &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, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+
+ return true;
+}
+
+/// @brief Tests for correct reponse to an Open command on a file, followed by Terminate
+bool MavlinkFtpTest::_open_terminate_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[i];
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ 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
+ &ftp_msg, // Response from server
+ &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
+ &ftp_msg, // Response from server
+ &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(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ 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
+ &ftp_msg, // Response from server
+ &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
+ &ftp_msg, // Response from server
+ &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(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ for (size_t i=0; i<sizeof(_rgReadTestCases)/sizeof(_rgReadTestCases[0]); i++) {
+ struct stat st;
+ const ReadTestCase *test = &_rgReadTestCases[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::kCmdOpenFile;
+ 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
+ &ftp_msg, // Response from server
+ &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;
+ 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
+ &ftp_msg, // Response from server
+ &reply); // Payload inside FTP message response
+ if (!success) {
+ return false;
+ }
+
+ ut_compare("Didn't get Ack back", reply->opcode, MavlinkFTP::kRspAck);
+ ut_compare("Offset incorrect", reply->offset, 0);
+
+ if (test->length <= MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(MavlinkFTP::PayloadHeader)) {
+ ut_compare("Payload size incorrect", reply->size, (uint32_t)st.st_size);
+ ut_compare("File contents differ", memcmp(reply->data, bytes, st.st_size), 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
+ &ftp_msg, // Response from server
+ &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 Read command on an invalid session.
+bool MavlinkFtpTest::_read_badsession_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ const char *file = _rgReadTestCases[0].file;
+
+ payload.opcode = MavlinkFTP::kCmdOpenFile;
+ 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
+ &ftp_msg, // Response from server
+ &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
+ &ftp_msg, // Response from server
+ &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(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ bool deleteFile;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false, false },
+ { "/etc/unit_test_data/mavlink_tests/empty_dir", false, false },
+ { _unittest_microsd_dir, false, false },
+ { _unittest_microsd_file, false, false },
+ { _unittest_microsd_dir, true, true },
+ };
+
+ 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)) != -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
+ &ftp_msg, // Response from server
+ &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, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_createdirectory_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+
+ struct _testCase {
+ const char *dir;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/etc/bogus", false },
+ { _unittest_microsd_dir, true },
+ { _unittest_microsd_dir, false },
+ { "/fs/microsd/bogus/bogus", false },
+ };
+
+ 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
+ &ftp_msg, // Response from server
+ &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, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+bool MavlinkFtpTest::_removefile_test(void)
+{
+ MavlinkFTP::PayloadHeader payload;
+ mavlink_file_transfer_protocol_t ftp_msg;
+ MavlinkFTP::PayloadHeader *reply;
+ int fd;
+
+ struct _testCase {
+ const char *file;
+ bool success;
+ };
+ static const struct _testCase rgTestCases[] = {
+ { "/bogus", false },
+ { _rgReadTestCases[0].file, false },
+ { _unittest_microsd_dir, false },
+ { _unittest_microsd_file, true },
+ { _unittest_microsd_file, false },
+ };
+
+ 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)) != -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
+ &ftp_msg, // Response from server
+ &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, 0);
+ } else {
+ ut_compare("Didn't get Nak back", reply->opcode, MavlinkFTP::kRspNak);
+ ut_compare("Incorrect payload size", reply->size, 2);
+ ut_compare("Incorrect error code", reply->data[0], MavlinkFTP::kErrFailErrno);
+ }
+ }
+
+ return true;
+}
+
+/// @brief Static method used as callback from MavlinkFTP. This method will be called by MavlinkFTP when
+/// it needs to send a message out on Mavlink.
+void MavlinkFtpTest::receive_message(const mavlink_message_t *msg, MavlinkFtpTest *ftp_test)
+{
+ ftp_test->_receive_message(msg);
+}
+
+/// @brief Non-Static version of receive_message
+void MavlinkFtpTest::_receive_message(const mavlink_message_t *msg)
+{
+ // Move the message into our own member variable
+ memcpy(&_reply_msg, msg, sizeof(mavlink_message_t));
+}
+
+/// @brief Decode and validate the incoming message
+bool MavlinkFtpTest::_decode_message(const mavlink_message_t *msg, ///< Mavlink message to decode
+ mavlink_file_transfer_protocol_t *ftp_msg, ///< Decoded FTP message
+ MavlinkFTP::PayloadHeader **payload) ///< Payload inside FTP message response
+{
+ mavlink_msg_file_transfer_protocol_decode(msg, ftp_msg);
+
+ // 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<MavlinkFTP::PayloadHeader *>(ftp_msg->payload);
+
+ // Make sure we have a good sequence number
+ ut_compare("Sequence number mismatch", (*payload)->seqNumber, _lastOutgoingSeqNumber + 1);
+
+ // Bump sequence number for next outgoing message
+ _lastOutgoingSeqNumber++;
+
+ return true;
+}
+
+/// @brief Initializes an FTP message into a mavlink message
+void MavlinkFtpTest::_setup_ftp_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
+ 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->seqNumber = _lastOutgoingSeqNumber;
+ payload->size = size;
+ if (size != 0) {
+ memcpy(payload->data, data, size);
+ }
+
+ payload->padding[0] = 0;
+ payload->padding[1] = 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
+ mavlink_file_transfer_protocol_t *ftp_msg_reply, ///< Response from server
+ 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(nullptr /* mavlink */, &msg);
+ return _decode_message(&_reply_msg, ftp_msg_reply, payload_reply);
+}
+
+/// @brief Cleans up an files created on microsd during testing
+void MavlinkFtpTest::_cleanup_microsd(void)
+{
+ ::unlink(_unittest_microsd_file);
+ ::rmdir(_unittest_microsd_dir);
+}
+
+/// @brief Runs all the unit tests
+bool MavlinkFtpTest::run_tests(void)
+{
+ 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(_removedirectory_test);
+ ut_run_test(_createdirectory_test);
+ ut_run_test(_removefile_test);
+
+ return (_tests_failed == 0);
+
+}
+
+ut_declare_test(mavlink_ftp_test, MavlinkFtpTest)
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
new file mode 100644
index 000000000..2696192cc
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test.h
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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.h
+/// @author Don Gagne <don@thegagnes.com>
+
+#pragma once
+
+#include <unit_test/unit_test.h>
+#include "../mavlink_bridge_header.h"
+#include "../mavlink_ftp.h"
+
+class MavlinkFtpTest : public UnitTest
+{
+public:
+ MavlinkFtpTest();
+ virtual ~MavlinkFtpTest();
+
+ virtual bool run_tests(void);
+
+ static void receive_message(const mavlink_message_t *msg, MavlinkFtpTest* ftpTest);
+
+ static const uint8_t serverSystemId = 50; ///< System ID for server
+ static const uint8_t serverComponentId = 1; ///< Component ID for server
+ static const uint8_t serverChannel = 0; ///< Channel to send to
+
+ static const uint8_t clientSystemId = 1; ///< System ID for client
+ static const uint8_t clientComponentId = 0; ///< Component ID for client
+
+ // We don't want any of these
+ MavlinkFtpTest(const MavlinkFtpTest&);
+ MavlinkFtpTest& operator=(const MavlinkFtpTest&);
+
+private:
+ virtual void _init(void);
+ virtual void _cleanup(void);
+
+ bool _ack_test(void);
+ bool _bad_opcode_test(void);
+ bool _bad_datasize_test(void);
+ bool _list_test(void);
+ bool _list_eof_test(void);
+ bool _open_badfile_test(void);
+ bool _open_terminate_test(void);
+ bool _terminate_badsession_test(void);
+ bool _read_test(void);
+ bool _read_badsession_test(void);
+ bool _removedirectory_test(void);
+ bool _createdirectory_test(void);
+ bool _removefile_test(void);
+
+ void _receive_message(const mavlink_message_t *msg);
+ void _setup_ftp_msg(MavlinkFTP::PayloadHeader *payload_header, uint8_t size, const uint8_t *data, mavlink_message_t *msg);
+ bool _decode_message(const mavlink_message_t *msg, mavlink_file_transfer_protocol_t *ftp_msg, MavlinkFTP::PayloadHeader **payload);
+ bool _send_receive_msg(MavlinkFTP::PayloadHeader *payload_header,
+ uint8_t size,
+ const uint8_t *data,
+ mavlink_file_transfer_protocol_t *ftp_msg_reply,
+ MavlinkFTP::PayloadHeader **payload_reply);
+ void _cleanup_microsd(void);
+
+ MavlinkFTP *_ftp_server;
+
+ mavlink_message_t _reply_msg;
+
+ uint16_t _lastOutgoingSeqNumber;
+
+ struct ReadTestCase {
+ const char *file;
+ const uint16_t length;
+ };
+ static const ReadTestCase _rgReadTestCases[];
+
+ static const char _unittest_microsd_dir[];
+ static const char _unittest_microsd_file[];
+};
+
+bool mavlink_ftp_test(void);
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
new file mode 100644
index 000000000..a7e68f2a3
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_ftp_test_data.py
@@ -0,0 +1,7 @@
+import sys
+print 'Arguments: file - ' + sys.argv[1] + ', length - ' + sys.argv[2]
+file = open(sys.argv[1], 'w')
+for i in range(int(sys.argv[2])):
+ b = bytearray([i & 0xFF])
+ file.write(b)
+file.close() \ No newline at end of file
diff --git a/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
new file mode 100644
index 000000000..10cbcb0ec
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/mavlink_tests.cpp
@@ -0,0 +1,47 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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_tests.cpp
+ */
+
+#include <systemlib/err.h>
+
+#include "mavlink_ftp_test.h"
+
+extern "C" __EXPORT int mavlink_tests_main(int argc, char *argv[]);
+
+int mavlink_tests_main(int argc, char *argv[])
+{
+ return mavlink_ftp_test() ? 0 : -1;
+}
diff --git a/src/modules/mavlink/mavlink_tests/module.mk b/src/modules/mavlink/mavlink_tests/module.mk
new file mode 100644
index 000000000..1cc28cce1
--- /dev/null
+++ b/src/modules/mavlink/mavlink_tests/module.mk
@@ -0,0 +1,50 @@
+############################################################################
+#
+# Copyright (c) 2014 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.
+#
+############################################################################
+
+#
+# System state machine tests.
+#
+
+MODULE_COMMAND = mavlink_tests
+SRCS = mavlink_tests.cpp \
+ mavlink_ftp_test.cpp \
+ ../mavlink_ftp.cpp \
+ ../mavlink.c
+
+INCLUDE_DIRS += $(MAVLINK_SRC)/include/mavlink
+
+MODULE_STACKSIZE = 5000
+
+MAXOPTIMIZATION = -Os
+
+EXTRACXXFLAGS = -Weffc++ -DMAVLINK_FTP_UNIT_TEST