More FTP support

Added:
- sequence numbers
- directory list returns file sizes
- open command returns file size in data
This commit is contained in:
Don Gagne 2014-08-10 12:02:10 -07:00
parent 95fc701376
commit 1d3edfa629
2 changed files with 42 additions and 8 deletions

View File

@ -35,6 +35,7 @@
#include <unistd.h>
#include <stdio.h>
#include <fcntl.h>
#include <sys/stat.h>
#include "mavlink_ftp.h"
@ -190,6 +191,8 @@ void
MavlinkFTP::_reply(Request *req)
{
auto hdr = req->header();
hdr->magic = kProtocolMagic;
// message is assumed to be already constructed in the request buffer, so generate the CRC
hdr->crc32 = 0;
@ -242,15 +245,18 @@ MavlinkFTP::_workList(Request *req)
break;
}
// name too big to fit?
if ((strlen(entry.d_name) + offset + 2) > kMaxDataLength) {
break;
}
uint32_t fileSize = 0;
char buf[256];
// store the type marker
switch (entry.d_type) {
case DTYPE_FILE:
hdr->data[offset++] = kDirentFile;
snprintf(buf, sizeof(buf), "%s/%s", dirPath, entry.d_name);
struct stat st;
if (stat(buf, &st) == 0) {
fileSize = st.st_size;
}
break;
case DTYPE_DIRECTORY:
hdr->data[offset++] = kDirentDir;
@ -259,11 +265,24 @@ MavlinkFTP::_workList(Request *req)
hdr->data[offset++] = kDirentUnknown;
break;
}
if (entry.d_type == DTYPE_FILE) {
snprintf(buf, sizeof(buf), "%s\t%d", entry.d_name, fileSize);
} else {
strncpy(buf, entry.d_name, sizeof(buf));
buf[sizeof(buf)-1] = 0;
}
size_t nameLen = strlen(buf);
// name too big to fit?
if ((nameLen + offset + 2) > kMaxDataLength) {
break;
}
// copy the name, which we know will fit
strcpy((char *)&hdr->data[offset], entry.d_name);
strcpy((char *)&hdr->data[offset], buf);
//printf("FTP: list %s %s\n", dirPath, (char *)&hdr->data[offset-1]);
offset += strlen(entry.d_name) + 1;
offset += nameLen + 1;
}
closedir(dp);
@ -282,6 +301,16 @@ MavlinkFTP::_workOpen(Request *req, bool create)
return kErrNoSession;
}
uint32_t fileSize = 0;
if (!create) {
struct stat st;
if (stat(req->dataAsCString(), &st) != 0) {
return kErrNotFile;
}
fileSize = st.st_size;
}
int oflag = create ? (O_CREAT | O_EXCL | O_APPEND) : O_RDONLY;
int fd = ::open(req->dataAsCString(), oflag);
@ -291,7 +320,12 @@ MavlinkFTP::_workOpen(Request *req, bool create)
_session_fds[session_index] = fd;
hdr->session = session_index;
hdr->size = 0;
if (create) {
hdr->size = 0;
} else {
hdr->size = sizeof(uint32_t);
*((uint32_t*)hdr->data) = fileSize;
}
return kErrNone;
}

View File

@ -146,7 +146,7 @@ private:
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(), rawData());
_mavlink->get_channel(), &msg, sequence()+1, rawData());
_mavlink->lockMessageBufferMutex();
bool success = _mavlink->message_buffer_write(&msg, len);