forked from Archive/PX4-Autopilot
Merge pull request #1083 from DonLakeFlyer/mavlink-ftp
FTP List, Open, Read, Terminate commands working end to end with QGC
This commit is contained in:
commit
5192a5eea9
|
@ -55,6 +55,11 @@ MavlinkFTP::MavlinkFTP()
|
||||||
// initialise the request freelist
|
// initialise the request freelist
|
||||||
dq_init(&_workFree);
|
dq_init(&_workFree);
|
||||||
sem_init(&_lock, 0, 1);
|
sem_init(&_lock, 0, 1);
|
||||||
|
|
||||||
|
// initialize session list
|
||||||
|
for (size_t i=0; i<kMaxSession; i++) {
|
||||||
|
_session_fds[i] = -1;
|
||||||
|
}
|
||||||
|
|
||||||
// drop work entries onto the free list
|
// drop work entries onto the free list
|
||||||
for (unsigned i = 0; i < kRequestQueueSize; i++) {
|
for (unsigned i = 0; i < kRequestQueueSize; i++) {
|
||||||
|
@ -122,13 +127,11 @@ MavlinkFTP::_worker(Request *req)
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case kCmdTerminate:
|
case kCmdTerminate:
|
||||||
if (!Session::terminate(hdr->session)) {
|
errorCode = _workTerminate(req);
|
||||||
errorCode = kErrNoRequest;
|
|
||||||
}
|
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case kCmdReset:
|
case kCmdReset:
|
||||||
Session::reset();
|
errorCode = _workReset();
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case kCmdList:
|
case kCmdList:
|
||||||
|
@ -219,6 +222,12 @@ MavlinkFTP::_workList(Request *req)
|
||||||
|
|
||||||
// no more entries?
|
// no more entries?
|
||||||
if (result == nullptr) {
|
if (result == nullptr) {
|
||||||
|
if (hdr->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;
|
||||||
|
}
|
||||||
|
// Otherwise we are just at the last directory entry, so we leave the errorCode at kErrorNone to signal that
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -256,20 +265,21 @@ MavlinkFTP::ErrorCode
|
||||||
MavlinkFTP::_workOpen(Request *req, bool create)
|
MavlinkFTP::_workOpen(Request *req, bool create)
|
||||||
{
|
{
|
||||||
auto hdr = req->header();
|
auto hdr = req->header();
|
||||||
|
|
||||||
// allocate session ID
|
int session_index = _findUnusedSession();
|
||||||
int session = Session::allocate();
|
if (session_index < 0) {
|
||||||
if (session < 0) {
|
|
||||||
return kErrNoSession;
|
return kErrNoSession;
|
||||||
}
|
}
|
||||||
|
|
||||||
// get the session to open the file
|
int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
|
||||||
if (!Session::get(session)->open(req->dataAsCString(), create)) {
|
|
||||||
|
int fd = ::open(req->dataAsCString(), oflag);
|
||||||
|
if (fd < 0) {
|
||||||
return create ? kErrPerm : kErrNotFile;
|
return create ? kErrPerm : kErrNotFile;
|
||||||
}
|
}
|
||||||
|
_session_fds[session_index] = fd;
|
||||||
|
|
||||||
// save the session ID in the reply
|
hdr->session = session_index;
|
||||||
hdr->session = session;
|
|
||||||
hdr->size = 0;
|
hdr->size = 0;
|
||||||
|
|
||||||
return kErrNone;
|
return kErrNone;
|
||||||
|
@ -280,29 +290,40 @@ MavlinkFTP::_workRead(Request *req)
|
||||||
{
|
{
|
||||||
auto hdr = req->header();
|
auto hdr = req->header();
|
||||||
|
|
||||||
// look up session
|
int session_index = hdr->session;
|
||||||
auto session = Session::get(hdr->session);
|
|
||||||
if (session == nullptr) {
|
if (!_validSession(session_index)) {
|
||||||
return kErrNoSession;
|
return kErrNoSession;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Seek to the specified position
|
||||||
|
printf("Seek %d\n", hdr->offset);
|
||||||
|
if (lseek(_session_fds[session_index], hdr->offset, SEEK_SET) < 0) {
|
||||||
|
// Unable to see to the specified location
|
||||||
|
return kErrEOF;
|
||||||
}
|
}
|
||||||
|
|
||||||
// read from file
|
int bytes_read = ::read(_session_fds[session_index], &hdr->data[0], kMaxDataLength);
|
||||||
int result = session->read(hdr->offset, &hdr->data[0], hdr->size);
|
if (bytes_read < 0) {
|
||||||
|
// Negative return indicates error other than eof
|
||||||
if (result < 0) {
|
|
||||||
return kErrIO;
|
return kErrIO;
|
||||||
}
|
}
|
||||||
hdr->size = result;
|
|
||||||
|
printf("Read success %d\n", bytes_read);
|
||||||
|
hdr->size = bytes_read;
|
||||||
|
|
||||||
return kErrNone;
|
return kErrNone;
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkFTP::ErrorCode
|
MavlinkFTP::ErrorCode
|
||||||
MavlinkFTP::_workWrite(Request *req)
|
MavlinkFTP::_workWrite(Request *req)
|
||||||
{
|
{
|
||||||
|
#if 0
|
||||||
|
// NYI: Coming soon
|
||||||
auto hdr = req->header();
|
auto hdr = req->header();
|
||||||
|
|
||||||
// look up session
|
// look up session
|
||||||
auto session = Session::get(hdr->session);
|
auto session = getSession(hdr->session);
|
||||||
if (session == nullptr) {
|
if (session == nullptr) {
|
||||||
return kErrNoSession;
|
return kErrNoSession;
|
||||||
}
|
}
|
||||||
|
@ -317,6 +338,9 @@ MavlinkFTP::_workWrite(Request *req)
|
||||||
|
|
||||||
hdr->size = result;
|
hdr->size = result;
|
||||||
return kErrNone;
|
return kErrNone;
|
||||||
|
#else
|
||||||
|
return kErrPerm;
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkFTP::ErrorCode
|
MavlinkFTP::ErrorCode
|
||||||
|
@ -328,91 +352,52 @@ MavlinkFTP::_workRemove(Request *req)
|
||||||
return kErrPerm;
|
return kErrPerm;
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkFTP::Session MavlinkFTP::Session::_sessions[MavlinkFTP::Session::kMaxSession];
|
MavlinkFTP::ErrorCode
|
||||||
|
MavlinkFTP::_workTerminate(Request *req)
|
||||||
int
|
|
||||||
MavlinkFTP::Session::allocate()
|
|
||||||
{
|
{
|
||||||
for (unsigned i = 0; i < kMaxSession; i++) {
|
auto hdr = req->header();
|
||||||
if (_sessions[i]._fd < 0) {
|
|
||||||
return i;
|
if (!_validSession(hdr->session)) {
|
||||||
}
|
return kErrNoSession;
|
||||||
}
|
}
|
||||||
return -1;
|
|
||||||
|
::close(_session_fds[hdr->session]);
|
||||||
|
|
||||||
|
return kErrNone;
|
||||||
}
|
}
|
||||||
|
|
||||||
MavlinkFTP::Session *
|
MavlinkFTP::ErrorCode
|
||||||
MavlinkFTP::Session::get(unsigned index)
|
MavlinkFTP::_workReset(void)
|
||||||
{
|
{
|
||||||
if ((index >= kMaxSession) || (_sessions[index]._fd < 0)) {
|
for (size_t i=0; i<kMaxSession; i++) {
|
||||||
return nullptr;
|
if (_session_fds[i] != -1) {
|
||||||
}
|
::close(_session_fds[i]);
|
||||||
return &_sessions[index];
|
_session_fds[i] = -1;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
void
|
|
||||||
MavlinkFTP::Session::terminate()
|
return kErrNone;
|
||||||
{
|
|
||||||
// clean up aborted transfers?
|
|
||||||
if (_fd >= 0) {
|
|
||||||
close(_fd);
|
|
||||||
_fd = -1;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool
|
bool
|
||||||
MavlinkFTP::Session::terminate(unsigned index)
|
MavlinkFTP::_validSession(unsigned index)
|
||||||
{
|
|
||||||
Session *session = get(index);
|
|
||||||
|
|
||||||
if (session == nullptr) {
|
|
||||||
return false;
|
|
||||||
}
|
|
||||||
|
|
||||||
session->terminate();
|
|
||||||
return true;
|
|
||||||
}
|
|
||||||
|
|
||||||
void
|
|
||||||
MavlinkFTP::Session::reset()
|
|
||||||
{
|
{
|
||||||
for (unsigned i = 0; i < kMaxSession; i++) {
|
if ((index >= kMaxSession) || (_session_fds[index] < 0)) {
|
||||||
terminate(i);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
bool
|
|
||||||
MavlinkFTP::Session::open(const char *path, bool create)
|
|
||||||
{
|
|
||||||
int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
|
|
||||||
|
|
||||||
_fd = open(path, oflag);
|
|
||||||
if (_fd < 0) {
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
int
|
int
|
||||||
MavlinkFTP::Session::read(off_t offset, uint8_t *buf, uint8_t count)
|
MavlinkFTP::_findUnusedSession(void)
|
||||||
{
|
{
|
||||||
// can we seek to the location?
|
for (size_t i=0; i<kMaxSession; i++) {
|
||||||
if (lseek(_fd, offset, SEEK_SET) < 0) {
|
if (_session_fds[i] == -1) {
|
||||||
return -1;
|
return i;
|
||||||
}
|
}
|
||||||
|
}
|
||||||
return read(_fd, buf, count);
|
|
||||||
}
|
return -1;
|
||||||
|
|
||||||
int
|
|
||||||
MavlinkFTP::Session::append(off_t offset, uint8_t *buf, uint8_t count)
|
|
||||||
{
|
|
||||||
// make sure that the requested offset matches our current position
|
|
||||||
off_t pos = lseek(_fd, 0, SEEK_CUR);
|
|
||||||
if (pos != offset) {
|
|
||||||
return -1;
|
|
||||||
}
|
|
||||||
return write(_fd, buf, count);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
char *
|
char *
|
||||||
|
|
|
@ -115,27 +115,11 @@ private:
|
||||||
kErrPerm
|
kErrPerm
|
||||||
};
|
};
|
||||||
|
|
||||||
class Session
|
int _findUnusedSession(void);
|
||||||
{
|
bool _validSession(unsigned index);
|
||||||
public:
|
|
||||||
Session() : _fd(-1) {}
|
|
||||||
|
|
||||||
static int allocate();
|
static const unsigned kMaxSession = 2;
|
||||||
static Session *get(unsigned index);
|
int _session_fds[kMaxSession];
|
||||||
static bool terminate(unsigned index);
|
|
||||||
static void reset();
|
|
||||||
|
|
||||||
void terminate();
|
|
||||||
bool open(const char *path, bool create);
|
|
||||||
int read(off_t offset, uint8_t *buf, uint8_t count);
|
|
||||||
int append(off_t offset, uint8_t *buf, uint8_t count);
|
|
||||||
|
|
||||||
private:
|
|
||||||
static const unsigned kMaxSession = 2;
|
|
||||||
static Session _sessions[kMaxSession];
|
|
||||||
|
|
||||||
int _fd;
|
|
||||||
};
|
|
||||||
|
|
||||||
class Request
|
class Request
|
||||||
{
|
{
|
||||||
|
@ -163,7 +147,11 @@ private:
|
||||||
unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
|
unsigned len = mavlink_msg_encapsulated_data_pack_chan(_mavlink->get_system_id(), _mavlink->get_component_id(),
|
||||||
_mavlink->get_channel(), &msg, sequence(), rawData());
|
_mavlink->get_channel(), &msg, sequence(), rawData());
|
||||||
|
|
||||||
if (!_mavlink->message_buffer_write(&msg, len)) {
|
_mavlink->lockMessageBufferMutex();
|
||||||
|
bool fError = _mavlink->message_buffer_write(&msg, len);
|
||||||
|
_mavlink->unlockMessageBufferMutex();
|
||||||
|
|
||||||
|
if (!fError) {
|
||||||
warnx("FTP TX ERR");
|
warnx("FTP TX ERR");
|
||||||
} else {
|
} else {
|
||||||
warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
|
warnx("wrote: sys: %d, comp: %d, chan: %d, len: %d, checksum: %d",
|
||||||
|
@ -211,6 +199,8 @@ private:
|
||||||
ErrorCode _workRead(Request *req);
|
ErrorCode _workRead(Request *req);
|
||||||
ErrorCode _workWrite(Request *req);
|
ErrorCode _workWrite(Request *req);
|
||||||
ErrorCode _workRemove(Request *req);
|
ErrorCode _workRemove(Request *req);
|
||||||
|
ErrorCode _workTerminate(Request *req);
|
||||||
|
ErrorCode _workReset();
|
||||||
|
|
||||||
// work freelist
|
// work freelist
|
||||||
Request _workBufs[kRequestQueueSize];
|
Request _workBufs[kRequestQueueSize];
|
||||||
|
@ -232,4 +222,5 @@ private:
|
||||||
_qUnlock();
|
_qUnlock();
|
||||||
return req;
|
return req;
|
||||||
}
|
}
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -2074,38 +2074,46 @@ Mavlink::task_main(int argc, char *argv[])
|
||||||
if (_passing_on || _ftp_on) {
|
if (_passing_on || _ftp_on) {
|
||||||
|
|
||||||
bool is_part;
|
bool is_part;
|
||||||
void *read_ptr;
|
uint8_t *read_ptr;
|
||||||
|
uint8_t *write_ptr;
|
||||||
|
|
||||||
/* guard get ptr by mutex */
|
|
||||||
pthread_mutex_lock(&_message_buffer_mutex);
|
pthread_mutex_lock(&_message_buffer_mutex);
|
||||||
int available = message_buffer_get_ptr(&read_ptr, &is_part);
|
int available = message_buffer_get_ptr((void**)&read_ptr, &is_part);
|
||||||
pthread_mutex_unlock(&_message_buffer_mutex);
|
pthread_mutex_unlock(&_message_buffer_mutex);
|
||||||
|
|
||||||
if (available > 0) {
|
if (available > 0) {
|
||||||
|
// Reconstruct message from buffer
|
||||||
|
|
||||||
// int oldseq = mavlink_get_channel_status(get_channel())->current_tx_seq;
|
mavlink_message_t msg;
|
||||||
|
write_ptr = (uint8_t*)&msg;
|
||||||
const mavlink_message_t* msg = (const mavlink_message_t*)read_ptr;
|
|
||||||
/* write first part of buffer */
|
|
||||||
_mavlink_resend_uart(_channel, msg);
|
|
||||||
|
|
||||||
// mavlink_get_channel_status(get_channel())->current_tx_seq = oldseq;
|
|
||||||
// mavlink_msg_system_time_send(get_channel(), 255, 255);
|
|
||||||
|
|
||||||
message_buffer_mark_read(available);
|
|
||||||
|
|
||||||
|
// Pull a single message from the buffer
|
||||||
|
int read_count = available;
|
||||||
|
if (read_count > sizeof(mavlink_message_t)) {
|
||||||
|
read_count = sizeof(mavlink_message_t);
|
||||||
|
}
|
||||||
|
|
||||||
|
memcpy(write_ptr, read_ptr, read_count);
|
||||||
|
|
||||||
|
// We hold the mutex until after we complete the second part of the buffer. If we don't
|
||||||
|
// we may end up breaking the empty slot overflow detection semantics when we mark the
|
||||||
|
// possibly partial read below.
|
||||||
|
pthread_mutex_lock(&_message_buffer_mutex);
|
||||||
|
|
||||||
|
message_buffer_mark_read(read_count);
|
||||||
|
|
||||||
/* write second part of buffer if there is some */
|
/* write second part of buffer if there is some */
|
||||||
// XXX this doesn't quite work, as the resend UART call assumes a continous block
|
if (is_part && read_count < sizeof(mavlink_message_t)) {
|
||||||
if (is_part) {
|
write_ptr += read_count;
|
||||||
/* guard get ptr by mutex */
|
available = message_buffer_get_ptr((void**)&read_ptr, &is_part);
|
||||||
pthread_mutex_lock(&_message_buffer_mutex);
|
read_count = sizeof(mavlink_message_t) - read_count;
|
||||||
available = message_buffer_get_ptr(&read_ptr, &is_part);
|
memcpy(write_ptr, read_ptr, read_count);
|
||||||
pthread_mutex_unlock(&_message_buffer_mutex);
|
|
||||||
|
|
||||||
_mavlink_resend_uart(_channel, (const mavlink_message_t*)read_ptr);
|
|
||||||
message_buffer_mark_read(available);
|
message_buffer_mark_read(available);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
pthread_mutex_unlock(&_message_buffer_mutex);
|
||||||
|
|
||||||
|
_mavlink_resend_uart(_channel, &msg);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -228,6 +228,9 @@ public:
|
||||||
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
bool should_transmit() { return (!_wait_to_transmit || (_wait_to_transmit && _received_messages)); }
|
||||||
|
|
||||||
bool message_buffer_write(void *ptr, int size);
|
bool message_buffer_write(void *ptr, int size);
|
||||||
|
|
||||||
|
void lockMessageBufferMutex(void) { pthread_mutex_lock(&_message_buffer_mutex); }
|
||||||
|
void unlockMessageBufferMutex(void) { pthread_mutex_unlock(&_message_buffer_mutex); }
|
||||||
|
|
||||||
protected:
|
protected:
|
||||||
Mavlink *next;
|
Mavlink *next;
|
||||||
|
|
Loading…
Reference in New Issue