Additional FTP command support plus unit test

- Restructured to a flatter class implementation
- Added support for create/remove directory, remove file
- Refactored error codes and command opcodes
- Added unit test support
- Fixed bugs found by unit test
This commit is contained in:
Don Gagne 2014-09-02 15:36:32 -07:00
parent 37ea85968d
commit 828fb5efd1
2 changed files with 423 additions and 307 deletions

View File

@ -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,167 +72,247 @@ 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) {
if (req == nullptr) {
warnx("Dropping FTP request: queue full\n");
return;
}
// decode the request
if (req->decode(mavlink, msg)) {
// 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->size > kMaxDataLength) {
errorCode = kErrNoRequest;
if (payload->size > kMaxDataLength) {
errorCode = kErrInvalidDataSize;
goto out;
}
// check request CRC to make sure this is one of ours
messageCRC = hdr->crc32;
hdr->crc32 = 0;
hdr->padding[0] = 0;
hdr->padding[1] = 0;
hdr->padding[2] = 0;
if (crc32(req->rawData(), req->dataSize()) != messageCRC) {
errorCode = kErrNoRequest;
if (_payload_crc32(payload) != payload->crc32) {
errorCode = kErrCrc;
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 kCmdReset:
errorCode = _workReset();
case kCmdResetSessions:
errorCode = _workReset(payload);
break;
case kCmdList:
errorCode = _workList(req);
case kCmdListDirectory:
errorCode = _workList(payload);
break;
case kCmdOpen:
errorCode = _workOpen(req, false);
case kCmdOpenFile:
errorCode = _workOpen(payload, false);
break;
case kCmdCreate:
errorCode = _workOpen(req, true);
case kCmdCreateFile:
errorCode = _workOpen(payload, true);
break;
case kCmdRead:
errorCode = _workRead(req);
case kCmdReadFile:
errorCode = _workRead(payload);
break;
case kCmdWrite:
errorCode = _workWrite(req);
case kCmdWriteFile:
errorCode = _workWrite(payload);
break;
case kCmdRemove:
errorCode = _workRemove(req);
case kCmdRemoveFile:
errorCode = _workRemoveFile(payload);
break;
case kCmdCreateDirectory:
errorCode = _workCreateDirectory(payload);
break;
case kCmdRemoveDirectory:
errorCode = _workRemoveDirectory(payload);
break;
default:
errorCode = kErrNoRequest;
errorCode = kErrUnknownCommand;
break;
}
out:
// handle success vs. error
if (errorCode == kErrNone) {
hdr->opcode = kRspAck;
payload->opcode = kRspAck;
#ifdef MAVLINK_FTP_DEBUG
warnx("FTP: ack\n");
#endif
} else {
warnx("FTP: nak %u", errorCode);
hdr->opcode = kRspNak;
hdr->size = 1;
hdr->data[0] = errorCode;
payload->opcode = kRspNak;
payload->size = 1;
payload->data[0] = errorCode;
if (errorCode == kErrFailErrno) {
payload->size = 2;
payload->data[1] = 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->seqNumber = req->header()->seqNumber + 1;
payload->seqNumber = payload->seqNumber + 1;
// message is assumed to be already constructed in the request buffer, so generate the CRC
hdr->crc32 = 0;
hdr->padding[0] = 0;
hdr->padding[1] = 0;
hdr->padding[2] = 0;
hdr->crc32 = crc32(req->rawData(), req->dataSize());
payload->crc32 = _payload_crc32(payload);
// then pack and send the reply back to the request source
req->reply();
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
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;
@ -239,19 +320,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;
@ -299,94 +380,95 @@ 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, bool create)
{
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;
if (stat(filename, &st) != 0) {
return kErrFailErrno;
}
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;
payload->session = session_index;
if (create) {
hdr->size = 0;
payload->size = 0;
} else {
hdr->size = sizeof(uint32_t);
*((uint32_t*)hdr->data) = fileSize;
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 = payload->session;
int session_index = hdr->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
@ -409,35 +491,44 @@ MavlinkFTP::_workWrite(Request *req)
hdr->size = result;
return kErrNone;
#else
return kErrPerm;
return kErrUnknownCommand;
#endif
}
/// @brief Responds to a RemoveFile command
MavlinkFTP::ErrorCode
MavlinkFTP::_workRemove(Request *req)
MavlinkFTP::_workRemoveFile(PayloadHeader* payload)
{
//auto hdr = req->header();
// for now, send error reply
return kErrPerm;
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 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) {
@ -446,11 +537,44 @@ MavlinkFTP::_workReset(void)
}
}
payload->size = 0;
return kErrNone;
}
/// @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 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;
@ -458,8 +582,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) {
@ -470,16 +595,68 @@ 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 Returns the 32 bit CRC for the payload, crc32 and padding members are set to 0 for calculation.
uint32_t
MavlinkFTP::_payload_crc32(PayloadHeader *payload)
{
// We calculate CRC with crc and padding set to 0.
uint32_t saveCRC = payload->crc32;
payload->crc32 = 0;
payload->padding[0] = 0;
payload->padding[1] = 0;
payload->padding[2] = 0;
uint32_t retCRC = crc32((const uint8_t*)payload, payload->size + sizeof(PayloadHeader));
payload->crc32 = saveCRC;
return retCRC;
}

View File

@ -33,17 +33,8 @@
#pragma once
/**
* @file mavlink_ftp.h
*
* MAVLink remote file server.
*
* 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>
@ -54,183 +45,131 @@
#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();
/// @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);
static MavlinkFTP *getServer();
// static interface
void handle_message(Mavlink* mavlink,
mavlink_message_t *msg);
private:
static const unsigned kRequestQueueSize = 2;
static MavlinkFTP *_server;
/// @brief Trying to pack structures across differing compilers is questionable for Clients, so we pad the
/// structure ourselves to 32 bit alignment which should get us what we want.
struct RequestHeader
/// @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 padding[3];
uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0
uint32_t offset; ///< Offsets for List and Read commands
uint8_t data[];
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 padding[3]; ///< 32 bit aligment padding
uint32_t crc32; ///< CRC for entire Request structure, with crc32 and padding set to 0
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>
kCmdOpenFile, ///< 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, ///< Appends <size> bytes to file in <session>
kCmdRemoveFile, ///< Remove file at <path>
kCmdCreateDirectory, ///< Creates directory at <path>
kCmdRemoveDirectory, ///< Removes Directory at <path>, must be empty
kRspAck, ///< 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
kErrCrc ///< CRC on Payload is incorrect
};
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_FILE_TRANSFER_PROTOCOL) {
_systemId = fromMessage->sysid;
_mavlink = mavlink;
mavlink_msg_file_transfer_protocol_decode(fromMessage, &_message);
return _message.target_system == _mavlink->get_system_id();
}
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_file_transfer_protocol_pack_chan(_mavlink->get_system_id(), // Sender system id
_mavlink->get_component_id(), // Sender component id
_mavlink->get_channel(), // Channel to send on
&msg, // Message to pack payload into
0, // Target network
_systemId, // Target system id
0, // Target component id
rawData()); // Payload to pack into message
_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.payload[0]; }
RequestHeader *header() { return reinterpret_cast<RequestHeader *>(&_message.payload[0]); }
uint8_t *requestData() { return &(header()->data[0]); }
unsigned dataSize() { return header()->size + sizeof(RequestHeader); }
mavlink_channel_t channel() { return _mavlink->get_channel(); }
char *dataAsCString();
private:
Mavlink *_mavlink;
mavlink_file_transfer_protocol_t _message;
uint8_t _systemId;
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
};
Request *_get_request(void);
void _return_request(Request *req);
void _lock_request_queue(void);
void _unlock_request_queue(void);
uint32_t _payload_crc32(PayloadHeader *hdr);
char *_data_as_cstring(PayloadHeader* payload);
static void _worker_trampoline(void *arg);
void _process_request(Request *req);
void _reply(Request *req);
static const char kDirentFile = 'F';
static const char kDirentDir = 'D';
static const char kDirentUnknown = 'U';
static const uint8_t kMaxDataLength = MAVLINK_MSG_FILE_TRANSFER_PROTOCOL_FIELD_PAYLOAD_LEN - sizeof(RequestHeader);
ErrorCode _workList(PayloadHeader *payload);
ErrorCode _workOpen(PayloadHeader *payload, bool create);
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);
/// 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;
}
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 kDirentUnknown = 'U'; ///< Identifies Unknown entry returned 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;
};