Commit 36e7a165 authored by DonLakeFlyer's avatar DonLakeFlyer

parent b730b4b7
/****************************************************************************
*
* (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#include "MAVLinkFTPManager.h"
#include "Vehicle.h"
#include "QGCApplication.h"
#include <QFile>
#include <QDir>
#include <string>
QGC_LOGGING_CATEGORY(MAVLinkFTPManagerLog, "MAVLinkFTPManagerLog")
MAVLinkFTPManager::MAVLinkFTPManager(Vehicle* vehicle)
: QObject (vehicle)
, _vehicle (vehicle)
{
connect(&_ackTimer, &QTimer::timeout, this, &MAVLinkFTPManager::_ackTimeout);
_lastOutgoingRequest.hdr.seqNumber = 0;
_systemIdServer = _vehicle->id();
// Make sure we don't have bad structure packing
Q_ASSERT(sizeof(RequestHeader) == 12);
}
/// Respond to the Ack associated with the Open command with the next read command.
void MAVLinkFTPManager::_openAckResponse(Request* openAck)
{
qCDebug(MAVLinkFTPManagerLog) << QString("_openAckResponse: _currentOperation(%1) _readFileLength(%2)").arg(_currentOperation).arg(openAck->openFileLength);
Q_ASSERT(_currentOperation == kCOOpenRead || _currentOperation == kCOOpenBurst);
_currentOperation = _currentOperation == kCOOpenRead ? kCORead : kCOBurst;
_activeSession = openAck->hdr.session;
// File length comes back in data
Q_ASSERT(openAck->hdr.size == sizeof(uint32_t));
_downloadFileSize = openAck->openFileLength;
// Start the sequence of read commands
_downloadOffset = 0; // Start reading at beginning of file
_readFileAccumulator.clear(); // Start with an empty file
_missingDownloadedBytes = 0;
_downloadingMissingParts = false;
_missingData.clear();
Request request;
request.hdr.session = _activeSession;
Q_ASSERT(_currentOperation == kCORead || _currentOperation == kCOBurst);
request.hdr.opcode = _currentOperation == kCORead ? kCmdReadFile : kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = sizeof(request.data);
_sendRequest(&request);
}
/// request the next missing part of a (partially) downloaded file
void MAVLinkFTPManager::_requestMissingData()
{
if (_missingData.empty()) {
_downloadingMissingParts = false;
_missingDownloadedBytes = 0;
// there might be more data missing at the end
if ((uint32_t)_readFileAccumulator.length() != _downloadFileSize) {
_downloadOffset = _readFileAccumulator.length();
qCDebug(MAVLinkFTPManagerLog) << QString("_requestMissingData: missing parts done, downloadOffset(%1) downloadFileSize(%2)")
.arg(_downloadOffset).arg(_downloadFileSize);
} else {
_closeDownloadSession(true);
return;
}
} else {
qCDebug(MAVLinkFTPManagerLog) << QString("_requestMissingData: offset(%1) size(%2)").arg(_missingData.head().offset).arg(_missingData.head().size);
_downloadOffset = _missingData.head().offset;
}
Request request;
_currentOperation = kCORead;
request.hdr.session = _activeSession;
request.hdr.opcode = kCmdReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = sizeof(request.data);
_sendRequest(&request);
}
/// Closes out a download session by writing the file and doing cleanup.
/// @param success true: successful download completion, false: error during download
void MAVLinkFTPManager::_closeDownloadSession(bool success)
{
qCDebug(MAVLinkFTPManagerLog) << QString("_closeDownloadSession: success(%1) missingBytes(%2)").arg(success).arg(_missingDownloadedBytes);
_currentOperation = kCOIdle;
if (success) {
if (_missingDownloadedBytes > 0 || (uint32_t)_readFileAccumulator.length() < _downloadFileSize) {
// we're not done yet: request the missing parts individually (either we had missing parts or
// the last (few) packets right before the EOF got dropped)
_downloadingMissingParts = true;
_requestMissingData();
return;
}
QString downloadFilePath = _readFileDownloadDir.absoluteFilePath(_readFileDownloadFilename);
QFile file(downloadFilePath);
if (!file.open(QIODevice::WriteOnly | QIODevice::Truncate)) {
_emitErrorMessage(tr("Unable to open local file for writing (%1)").arg(downloadFilePath));
return;
}
qint64 bytesWritten = file.write((const char *)_readFileAccumulator, _readFileAccumulator.length());
if (bytesWritten != _readFileAccumulator.length()) {
file.close();
_emitErrorMessage(tr("Unable to write data to local file (%1)").arg(downloadFilePath));
return;
}
file.close();
emit commandComplete();
}
_readFileAccumulator.clear();
// Close the open session
_sendResetCommand();
}
/// Closes out an upload session doing cleanup.
/// @param success true: successful upload completion, false: error during download
void MAVLinkFTPManager::_closeUploadSession(bool success)
{
qCDebug(MAVLinkFTPManagerLog) << QString("_closeUploadSession: success(%1)").arg(success);
_currentOperation = kCOIdle;
_writeFileAccumulator.clear();
_writeFileSize = 0;
if (success) {
emit commandComplete();
}
// Close the open session
_sendResetCommand();
}
/// Respond to the Ack associated with the Read or Stream commands.
/// @param readFile: true: read file, false: stream file
void MAVLinkFTPManager::_downloadAckResponse(Request* readAck, bool readFile)
{
if (readAck->hdr.session != _activeSession) {
_closeDownloadSession(false /* failure */);
_emitErrorMessage(tr("Download: Incorrect session returned"));
return;
}
if (readAck->hdr.offset != _downloadOffset) {
if (readFile) {
_closeDownloadSession(false /* failure */);
_emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
return;
} else { // burst
if (readAck->hdr.offset < _downloadOffset) { // old data: ignore it
_setupAckTimeout();
return;
}
// keep track of missing data chunks
MissingData missingData;
missingData.offset = _downloadOffset;
missingData.size = readAck->hdr.offset - _downloadOffset;
_missingData.push_back(missingData);
_missingDownloadedBytes += readAck->hdr.offset - _downloadOffset;
qCDebug(MAVLinkFTPManagerLog) << QString("_downloadAckResponse: missing data: offset(%1) size(%2)").arg(missingData.offset).arg(missingData.size);
_downloadOffset = readAck->hdr.offset;
_readFileAccumulator.resize(_downloadOffset); // placeholder for the missing data
}
}
qCDebug(MAVLinkFTPManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
if (_downloadingMissingParts) {
Q_ASSERT(_missingData.head().offset == _downloadOffset);
_missingDownloadedBytes -= readAck->hdr.size;
_readFileAccumulator.replace(_downloadOffset, readAck->hdr.size, (const char*)readAck->data, readAck->hdr.size);
if (_missingData.head().size <= readAck->hdr.size) {
_missingData.pop_front();
} else {
_missingData.head().size -= readAck->hdr.size;
_missingData.head().offset += readAck->hdr.size;
}
} else {
_downloadOffset += readAck->hdr.size;
_readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
}
if (_downloadFileSize != 0) {
emit commandProgress(100 * ((float)(_readFileAccumulator.length() - _missingDownloadedBytes) / (float)_downloadFileSize));
}
if (_downloadingMissingParts) {
_requestMissingData();
} else if (readFile || readAck->hdr.burstComplete) {
// Possibly still more data to read, send next read request
Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = readFile ? kCmdReadFile : kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = 0;
_sendRequest(&request);
} else if (!readFile) {
// Streaming, so next ack should come automatically
_setupAckTimeout();
}
}
/// @brief Respond to the Ack associated with the List command.
void MAVLinkFTPManager::_listAckResponse(Request* listAck)
{
if (listAck->hdr.offset != _listOffset) {
// this is a real error (directory listing is synchronous), no need to retransmit
_currentOperation = kCOIdle;
_emitErrorMessage(tr("List: Offset returned (%1) differs from offset requested (%2)").arg(listAck->hdr.offset).arg(_listOffset));
return;
}
uint8_t offset = 0;
uint8_t cListEntries = 0;
uint8_t cBytes = listAck->hdr.size;
// parse filenames out of the buffer
while (offset < cBytes) {
const char * ptr = ((const char *)listAck->data) + offset;
// get the length of the name
uint8_t cBytesLeft = cBytes - offset;
uint8_t nlen = static_cast<uint8_t>(strnlen(ptr, cBytesLeft));
if ((*ptr == 'S' && nlen > 1) || (*ptr != 'S' && nlen < 2)) {
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Incorrectly formed list entry: '%1'").arg(ptr));
return;
} else if (nlen == cBytesLeft) {
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Missing NULL termination in list entry"));
return;
}
// Returned names are prepended with D for directory, F for file, S for skip
if (*ptr == 'F' || *ptr == 'D') {
// put it in the view
_emitListEntry(ptr);
} else if (*ptr == 'S') {
// do nothing
} else {
qDebug() << "unknown entry" << ptr;
}
// account for the name + NUL
offset += nlen + 1;
cListEntries++;
}
if (listAck->hdr.size == 0 || cListEntries == 0) {
// Directory is empty, we're done
Q_ASSERT(listAck->hdr.opcode == kRspAck);
_currentOperation = kCOIdle;
emit commandComplete();
} else {
// Possibly more entries to come, need to keep trying till we get EOF
_currentOperation = kCOList;
_listOffset += cListEntries;
_sendListCommand();
}
}
/// @brief Respond to the Ack associated with the create command.
void MAVLinkFTPManager::_createAckResponse(Request* createAck)
{
qCDebug(MAVLinkFTPManagerLog) << "_createAckResponse";
_currentOperation = kCOWrite;
_activeSession = createAck->hdr.session;
// Start the sequence of write commands from the beginning of the file
_writeOffset = 0;
_writeSize = 0;
_writeFileDatablock();
}
/// @brief Respond to the Ack associated with the write command.
void MAVLinkFTPManager::_writeAckResponse(Request* writeAck)
{
if(_writeOffset + _writeSize >= _writeFileSize){
_closeUploadSession(true /* success */);
return;
}
if (writeAck->hdr.session != _activeSession) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Incorrect session returned"));
return;
}
if (writeAck->hdr.offset != _writeOffset) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Offset returned (%1) differs from offset requested (%2)").arg(writeAck->hdr.offset).arg(_writeOffset));
return;
}
if (writeAck->hdr.size != sizeof(uint32_t)) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Returned invalid size of write size data"));
return;
}
if( writeAck->writeFileLength !=_writeSize) {
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Write: Size returned (%1) differs from size requested (%2)").arg(writeAck->writeFileLength).arg(_writeSize));
return;
}
_writeFileDatablock();
}
/// @brief Send next write file data block.
void MAVLinkFTPManager::_writeFileDatablock(void)
{
if (_writeOffset + _writeSize >= _writeFileSize){
_closeUploadSession(true /* success */);
return;
}
_writeOffset += _writeSize;
Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = kCmdWriteFile;
request.hdr.offset = _writeOffset;
if(_writeFileSize -_writeOffset > sizeof(request.data) )
_writeSize = sizeof(request.data);
else
_writeSize = _writeFileSize - _writeOffset;
request.hdr.size = _writeSize;
memcpy(request.data, &_writeFileAccumulator.data()[_writeOffset], _writeSize);
_sendRequest(&request);
}
void MAVLinkFTPManager::receiveMessage(mavlink_message_t message)
{
// receiveMessage is signalled will all mavlink messages so we need to filter everything else out but ours.
if (message.msgid != MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL) {
return;
}
mavlink_file_transfer_protocol_t data;
mavlink_msg_file_transfer_protocol_decode(&message, &data);
// Make sure we are the target system
if (data.target_system != _systemIdQGC) {
qDebug() << "Received MAVLINK_MSG_ID_FILE_TRANSFER_PROTOCOL with incorrect target_system:" << data.target_system << "expected:" << _systemIdQGC;
return;
}
Request* request = (Request*)&data.payload[0];
uint16_t incomingSeqNumber = request->hdr.seqNumber;
// Make sure we have a good sequence number
uint16_t expectedSeqNumber = _lastOutgoingRequest.hdr.seqNumber + 1;
// ignore old/reordered packets (handle wrap-around properly)
if ((uint16_t)((expectedSeqNumber - 1) - incomingSeqNumber) < (std::numeric_limits<uint16_t>::max()/2)) {
qDebug() << "Received old packet: expected seq:" << expectedSeqNumber << "got:" << incomingSeqNumber;
return;
}
_clearAckTimeout();
qCDebug(MAVLinkFTPManagerLog) << "receiveMessage" << request->hdr.opcode;
if (incomingSeqNumber != expectedSeqNumber) {
bool doAbort = true;
switch (_currentOperation) {
case kCOBurst: // burst download drops are handled in _downloadAckResponse()
doAbort = false;
break;
case kCORead:
_closeDownloadSession(false /* failure */);
break;
case kCOWrite:
_closeUploadSession(false /* failure */);
break;
case kCOOpenRead:
case kCOOpenBurst:
case kCOCreate:
// We could have an open session hanging around
_currentOperation = kCOIdle;
_sendResetCommand();
break;
default:
// Don't need to do anything special
_currentOperation = kCOIdle;
break;
}
if (doAbort) {
_emitErrorMessage(tr("Bad sequence number on received message: expected(%1) received(%2)").arg(expectedSeqNumber).arg(incomingSeqNumber));
return;
}
}
// Move past the incoming sequence number for next request
_lastOutgoingRequest.hdr.seqNumber = incomingSeqNumber;
if (request->hdr.opcode == kRspAck) {
switch (request->hdr.req_opcode) {
case kCmdListDirectory:
_listAckResponse(request);
break;
case kCmdOpenFileRO:
case kCmdOpenFileWO:
_openAckResponse(request);
break;
case kCmdReadFile:
_downloadAckResponse(request, true /* read file */);
break;
case kCmdBurstReadFile:
_downloadAckResponse(request, false /* stream file */);
break;
case kCmdCreateFile:
_createAckResponse(request);
break;
case kCmdWriteFile:
_writeAckResponse(request);
break;
default:
// Ack back from operation which does not require additional work
_currentOperation = kCOIdle;
break;
}
} else if (request->hdr.opcode == kRspNak) {
uint8_t errorCode = request->data[0];
// Nak's normally have 1 byte of data for error code, except for kErrFailErrno which has additional byte for errno
Q_ASSERT((errorCode == kErrFailErrno && request->hdr.size == 2) || request->hdr.size == 1);
_currentOperation = kCOIdle;
if (request->hdr.req_opcode == kCmdListDirectory && errorCode == kErrEOF) {
// This is not an error, just the end of the list loop
emit commandComplete();
return;
} else if ((request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) && errorCode == kErrEOF) {
// This is not an error, just the end of the download loop
_closeDownloadSession(true /* success */);
return;
} else if (request->hdr.req_opcode == kCmdCreateFile) {
_emitErrorMessage(tr("Nak received creating file, error: %1").arg(errorString(request->data[0])));
return;
} else if (request->hdr.req_opcode == kCmdCreateDirectory) {
_emitErrorMessage(tr("Nak received creating directory, error: %1").arg(errorString(request->data[0])));
return;
} else {
// Generic Nak handling
if (request->hdr.req_opcode == kCmdReadFile || request->hdr.req_opcode == kCmdBurstReadFile) {
// Nak error during download loop, download failed
_closeDownloadSession(false /* failure */);
} else if (request->hdr.req_opcode == kCmdWriteFile) {
// Nak error during upload loop, upload failed
_closeUploadSession(false /* failure */);
}
_emitErrorMessage(tr("Nak received, error: %1").arg(errorString(request->data[0])));
}
} else {
// Note that we don't change our operation state. If something goes wrong beyond this, the operation
// will time out.
_emitErrorMessage(tr("Unknown opcode returned from server: %1").arg(request->hdr.opcode));
}
}
void MAVLinkFTPManager::listDirectory(const QString& dirPath)
{
if (_currentOperation != kCOIdle) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
}
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
// initialise the lister
_listPath = dirPath;
_listOffset = 0;
_currentOperation = kCOList;
// and send the initial request
_sendListCommand();
}
void MAVLinkFTPManager::_fillRequestWithString(Request* request, const QString& str)
{
strncpy((char *)&request->data[0], str.toStdString().c_str(), sizeof(request->data));
request->hdr.size = static_cast<uint8_t>(strnlen((const char *)&request->data[0], sizeof(request->data)));
}
void MAVLinkFTPManager::_sendListCommand(void)
{
Request request;
request.hdr.session = 0;
request.hdr.opcode = kCmdListDirectory;
request.hdr.offset = _listOffset;
request.hdr.size = 0;
_fillRequestWithString(&request, _listPath);
qCDebug(MAVLinkFTPManagerLog) << "listDirectory: path:" << _listPath << "offset:" << _listOffset;
_sendRequest(&request);
}
void MAVLinkFTPManager::downloadPath(const QString& vehicleFilePath, const QDir& downloadDir)
{
if (_currentOperation != kCOIdle) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
}
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
qCDebug(MAVLinkFTPManagerLog) << "downloadPath vehicleFilePath:" << vehicleFilePath << "to:" << downloadDir;
_downloadWorker(vehicleFilePath, downloadDir, true /* read file */);
}
void MAVLinkFTPManager::streamPath(const QString& from, const QDir& downloadDir)
{
if (_currentOperation != kCOIdle) {
_emitErrorMessage(tr("Command not sent. Waiting for previous command to complete."));
return;
}
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
qCDebug(MAVLinkFTPManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, false /* stream file */);
}
void MAVLinkFTPManager::_downloadWorker(const QString& vehicleFilePath, const QDir& downloadDir, bool readFile)
{
if (vehicleFilePath.isEmpty()) {
return;
}
_readFileDownloadDir.setPath(downloadDir.absolutePath());
// We need to strip off the file name from the fully qualified path. We can't use the usual QDir
// routines because this path does not exist locally.
int i;
for (i=vehicleFilePath.size()-1; i>=0; i--) {
if (vehicleFilePath[i] == '/') {
break;
}
}
i++; // move past slash
_readFileDownloadFilename = vehicleFilePath.right(vehicleFilePath.size() - i);
_currentOperation = readFile ? kCOOpenRead : kCOOpenBurst;
Request request;
request.hdr.session = 0;
request.hdr.opcode = kCmdOpenFileRO;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, vehicleFilePath);
_sendRequest(&request);
}
/// @brief Uploads the specified file.
/// @param toPath File in UAS to upload to, fully qualified path
/// @param uploadFile Local file to upload from
void MAVLinkFTPManager::uploadPath(const QString& toPath, const QFileInfo& uploadFile)
{
if(_currentOperation != kCOIdle){
_emitErrorMessage(tr("UAS File manager busy. Try again later"));
return;
}
_dedicatedLink = _vehicle->priorityLink();
if (!_dedicatedLink) {
_emitErrorMessage(tr("Command not sent. No Vehicle links."));
return;
}
if (toPath.isEmpty()) {
return;
}
if (!uploadFile.isReadable()){
_emitErrorMessage(tr("File (%1) is not readable for upload").arg(uploadFile.path()));
return;
}
QFile file(uploadFile.absoluteFilePath());
if (!file.open(QIODevice::ReadOnly)) {
_emitErrorMessage(tr("Unable to open local file for upload (%1)").arg(uploadFile.absoluteFilePath()));
return;
}
_writeFileAccumulator = file.readAll();
_writeFileSize = _writeFileAccumulator.size();
file.close();
if (_writeFileAccumulator.size() == 0) {
_emitErrorMessage(tr("Unable to read data from local file (%1)").arg(uploadFile.absoluteFilePath()));
return;
}
_currentOperation = kCOCreate;
Request request;
request.hdr.session = 0;
request.hdr.opcode = kCmdCreateFile;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, toPath + "/" + uploadFile.fileName());
_sendRequest(&request);
}
void MAVLinkFTPManager::createDirectory(const QString& directory)
{
if(_currentOperation != kCOIdle){
_emitErrorMessage(tr("UAS File manager busy. Try again later"));
return;
}
_currentOperation = kCOCreateDir;
Request request;
request.hdr.session = 0;
request.hdr.opcode = kCmdCreateDirectory;
request.hdr.offset = 0;
request.hdr.size = 0;
_fillRequestWithString(&request, directory);
_sendRequest(&request);
}
QString MAVLinkFTPManager::errorString(uint8_t errorCode)
{
switch(errorCode) {
case kErrNone:
return QString("no error");
case kErrFail:
return QString("unknown error");
case kErrEOF:
return QString("read beyond end of file");
case kErrUnknownCommand:
return QString("unknown command");
case kErrFailErrno:
return QString("command failed");
case kErrInvalidDataSize:
return QString("invalid data size");
case kErrInvalidSession:
return QString("invalid session");
case kErrNoSessionsAvailable:
return QString("no sessions available");
case kErrFailFileExists:
return QString("File already exists on target");
case kErrFailFileProtected:
return QString("File is write protected");
default:
return QString("unknown error code");
}
}
/// @brief Sends a command which only requires an opcode and no additional data
/// @param opcode Opcode to send
/// @param newOpState State to put state machine into
/// @return TRUE: command sent, FALSE: command not sent, waiting for previous command to finish
bool MAVLinkFTPManager::_sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState)
{
if (_currentOperation != kCOIdle) {
// Can't have multiple commands in play at the same time
return false;
}
Request request;
request.hdr.session = 0;
request.hdr.opcode = opcode;
request.hdr.offset = 0;
request.hdr.size = 0;
_currentOperation = newOpState;
_sendRequest(&request);
return true;
}
/// @brief Starts the ack timeout timer
void MAVLinkFTPManager::_setupAckTimeout(void)
{
qCDebug(MAVLinkFTPManagerLog) << "_setupAckTimeout";
Q_ASSERT(!_ackTimer.isActive());
_ackNumTries = 0;
_ackTimer.setSingleShot(false);
_ackTimer.start(ackTimerTimeoutMsecs);
}
/// @brief Clears the ack timeout timer
void MAVLinkFTPManager::_clearAckTimeout(void)
{
qCDebug(MAVLinkFTPManagerLog) << "_clearAckTimeout";
_ackTimer.stop();
}
/// @brief Called when ack timeout timer fires
void MAVLinkFTPManager::_ackTimeout(void)
{
qCDebug(MAVLinkFTPManagerLog) << "_ackTimeout";
if (++_ackNumTries <= ackTimerMaxRetries) {
qCDebug(MAVLinkFTPManagerLog) << "ack timeout - retrying";
if (_currentOperation == kCOBurst) {
// for burst downloads try to initiate a new burst
Request request;
request.hdr.session = _activeSession;
request.hdr.opcode = kCmdBurstReadFile;
request.hdr.offset = _downloadOffset;
request.hdr.size = 0;
request.hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
_sendRequestNoAck(&request);
} else {
_sendRequestNoAck(&_lastOutgoingRequest);
}
return;
}
_clearAckTimeout();
// Make sure to set _currentOperation state before emitting error message. Code may respond
// to error message signal by sending another command, which will fail if state is not back
// to idle. FileView UI works this way with the List command.
switch (_currentOperation) {
case kCORead:
case kCOBurst:
_closeDownloadSession(false /* failure */);
_emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
break;
case kCOOpenRead:
case kCOOpenBurst:
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Timeout waiting for ack: Download failed"));
_sendResetCommand();
break;
case kCOCreate:
_currentOperation = kCOIdle;
_emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
_sendResetCommand();
break;
case kCOWrite:
_closeUploadSession(false /* failure */);
_emitErrorMessage(tr("Timeout waiting for ack: Upload failed"));
break;
default:
{
OperationState currentOperation = _currentOperation;
_currentOperation = kCOIdle;
_emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(currentOperation));
}
break;
}
}
void MAVLinkFTPManager::_sendResetCommand(void)
{
Request request;
request.hdr.opcode = kCmdResetSessions;
request.hdr.size = 0;
_sendRequest(&request);
}
void MAVLinkFTPManager::_emitErrorMessage(const QString& msg)
{
qCDebug(MAVLinkFTPManagerLog) << "Error:" << msg;
emit commandError(msg);
}
void MAVLinkFTPManager::_emitListEntry(const QString& entry)
{
qCDebug(MAVLinkFTPManagerLog) << "_emitListEntry" << entry;
emit listEntry(entry);
}
/// @brief Sends the specified Request out to the UAS.
void MAVLinkFTPManager::_sendRequest(Request* request)
{
_setupAckTimeout();
request->hdr.seqNumber = ++_lastOutgoingRequest.hdr.seqNumber;
// store the current request
if (request->hdr.size <= sizeof(request->data)) {
memcpy(&_lastOutgoingRequest, request, sizeof(RequestHeader) + request->hdr.size);
} else {
qCCritical(MAVLinkFTPManagerLog) << "request length too long:" << request->hdr.size;
}
qCDebug(MAVLinkFTPManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
if (_systemIdQGC == 0) {
_systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
}
_sendRequestNoAck(request);
}
/// @brief Sends the specified Request out to the UAS, without ack timeout handling
void MAVLinkFTPManager::_sendRequestNoAck(Request* request)
{
mavlink_message_t message;
// Unit testing code can end up here without _dedicateLink set since it tests inidividual commands.
LinkInterface* link;
if (_dedicatedLink) {
link = _dedicatedLink;
} else {
link = _vehicle->priorityLink();
}
mavlink_msg_file_transfer_protocol_pack_chan(_systemIdQGC, // QGC System ID
0, // QGC Component ID
link->mavlinkChannel(),
&message, // Mavlink Message to pack into
0, // Target network
_systemIdServer, // Target system
0, // Target component
(uint8_t*)request); // Payload
_vehicle->sendMessageOnLinkThreadSafe(link, message);
}
/****************************************************************************
*
* (c) 2009-2018 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
*
* QGroundControl is licensed according to the terms in the file
* COPYING.md in the root of the source code directory.
*
****************************************************************************/
#pragma once
#include <QObject>
#include <QDir>
#include <QTimer>
#include <QQueue>
#include "UASInterface.h"
#include "QGCLoggingCategory.h"
#ifdef __GNUC__
#define PACKED_STRUCT( __Declaration__ ) __Declaration__ __attribute__((packed))
#else
#define PACKED_STRUCT( __Declaration__ ) __pragma( pack(push, 1) ) __Declaration__ __pragma( pack(pop) )
#endif
Q_DECLARE_LOGGING_CATEGORY(MAVLinkFTPManagerLog)
class Vehicle;
class MAVLinkFTPManager : public QObject
{
Q_OBJECT
public:
MAVLinkFTPManager(Vehicle* vehicle);
/// These methods are only used for testing purposes.
bool _sendCmdTestAck(void) { return _sendOpcodeOnlyCmd(kCmdNone, kCOAck); };
bool _sendCmdTestNoAck(void) { return _sendOpcodeOnlyCmd(kCmdTestNoAck, kCOAck); };
/// Timeout in msecs to wait for an Ack time come back. This is public so we can write unit tests which wait long enough
/// for the MAVLinkFTPManager to timeout.
static const int ackTimerTimeoutMsecs = 50;
static const int ackTimerMaxRetries = 6;
/// Downloads the specified file.
/// @param vehicleFilePath File to download from UAS, fully qualified path
/// @param downloadDir Local directory to download file to
void downloadPath(const QString& vehicleFilePath, const QDir& downloadDir);
/// Stream downloads the specified file.
/// @param from File to download from UAS, fully qualified path
/// @param downloadDir Local directory to download file to
void streamPath(const QString& from, const QDir& downloadDir);
/// Lists the specified directory. Emits listEntry signal for each entry, followed by listComplete signal.
/// @param dirPath Fully qualified path to list
void listDirectory(const QString& dirPath);
/// Upload the specified file to the specified location
void uploadPath(const QString& toPath, const QFileInfo& uploadFile);
/// Create a remote directory
void createDirectory(const QString& directory);
signals:
// Signals associated with the listDirectory method
/// Signalled to indicate a new directory entry was received.
void listEntry(const QString& entry);
// Signals associated with all commands
/// Signalled after a command has completed
void commandComplete(void);
/// Signalled when an error occurs during a command. In this case a commandComplete signal will
/// not be sent.
void commandError(const QString& msg);
/// Signalled during a lengthy command to show progress
/// @param value Amount of progress: 0.0 = none, 1.0 = complete
void commandProgress(int value);
public slots:
void receiveMessage(mavlink_message_t message);
private slots:
void _ackTimeout(void);
private:
/// @brief This is the fixed length portion of the protocol data.
/// This needs to be packed, because it's typecasted from mavlink_file_transfer_protocol_t.payload, which starts
/// at a 3 byte offset, causing an unaligned access to seq_number and offset
PACKED_STRUCT(
typedef struct _RequestHeader
{
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 burstComplete; ///< Only used if req_opcode=kCmdBurstReadFile - 1: set of burst packets complete, 0: More burst packets coming.
uint8_t padding; ///< 32 bit aligment padding
uint32_t offset; ///< Offsets for List and Read commands
}) RequestHeader;
PACKED_STRUCT(
typedef struct _Request
{
RequestHeader hdr;
// We use a union here instead of just casting (uint32_t)&payload[0] to not break strict aliasing rules
union {
// The entire Request must fit into the payload member of the mavlink_file_transfer_protocol_t structure. We use as many leftover bytes
// after we use up space for the RequestHeader for the data portion of the Request.
uint8_t data[sizeof(((mavlink_file_transfer_protocol_t*)0)->payload) - sizeof(RequestHeader)];
// File length returned by Open command
uint32_t openFileLength;
// Length of file chunk written by write command
uint32_t writeFileLength;
};
}) Request;
enum Opcode
{
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>
kCmdBurstReadFile, ///< Burst download session file
kRspAck = 128, ///< Ack response
kRspNak, ///< Nak response
// Used for testing only, not part of protocol
kCmdTestNoAck, ///< ignored, ack not sent back, should timeout waiting for ack
};
/// @brief Error codes returned in Nak response PayloadHeader.data[0].
enum ErrorCode
{
kErrNone,
kErrFail, ///< Unknown failure
kErrFailErrno, ///< 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
kErrFailFileExists, ///< File exists already
kErrFailFileProtected ///< File is write protected
};
enum OperationState
{
kCOIdle, // not doing anything
kCOAck, // waiting for an Ack
kCOList, // waiting for List response
kCOOpenRead, // waiting for Open response followed by Read download
kCOOpenBurst, // waiting for Open response, followed by Burst download
kCORead, // waiting for Read response
kCOBurst, // waiting for Burst response
kCOWrite, // waiting for Write response
kCOCreate, // waiting for Create response
kCOCreateDir, // waiting for Create Directory response
};
bool _sendOpcodeOnlyCmd(uint8_t opcode, OperationState newOpState);
void _setupAckTimeout(void);
void _clearAckTimeout(void);
void _emitErrorMessage(const QString& msg);
void _emitListEntry(const QString& entry);
void _sendRequest(Request* request);
void _sendRequestNoAck(Request* request);
void _fillRequestWithString(Request* request, const QString& str);
void _openAckResponse(Request* openAck);
void _downloadAckResponse(Request* readAck, bool readFile);
void _listAckResponse(Request* listAck);
void _createAckResponse(Request* createAck);
void _writeAckResponse(Request* writeAck);
void _writeFileDatablock(void);
void _sendListCommand(void);
void _sendResetCommand(void);
void _closeDownloadSession(bool success);
void _closeUploadSession(bool success);
void _downloadWorker(const QString& vehicleFilePath, const QDir& downloadDir, bool readFile);
void _requestMissingData();
static QString errorString(uint8_t errorCode);
OperationState _currentOperation = kCOIdle; ///< Current operation of state machine
QTimer _ackTimer; ///< Used to signal a timeout waiting for an ack
int _ackNumTries = 0; ///< current number of tries
Vehicle* _vehicle = nullptr;
LinkInterface* _dedicatedLink = nullptr; ///< Link to use for communication
Request _lastOutgoingRequest; ///< contains the last outgoing packet
unsigned _listOffset; ///< offset for the current List operation
QString _listPath; ///< path for the current List operation
uint8_t _activeSession = 0; ///< currently active session, 0 for none
uint32_t _readOffset; ///< current read offset
uint32_t _writeOffset; ///< current write offset
uint32_t _writeSize; ///< current write data size
uint32_t _writeFileSize; ///< Size of file being uploaded
QByteArray _writeFileAccumulator; ///< Holds file being uploaded
struct MissingData {
uint32_t offset;
uint32_t size;
};
uint32_t _downloadOffset; ///< current download offset
uint32_t _missingDownloadedBytes = 0; ///< number of missing bytes for burst download
QQueue<MissingData> _missingData; ///< missing chunks of downloaded file (for burst downloads)
bool _downloadingMissingParts = false; ///< true if we are currently downloading missing parts
QByteArray _readFileAccumulator; ///< Holds file being downloaded
QDir _readFileDownloadDir; ///< Directory to download file to
QString _readFileDownloadFilename; ///< Filename (no path) for download file
uint32_t _downloadFileSize; ///< Size of file being downloaded
uint8_t _systemIdQGC = 0; ///< System ID for QGC
uint8_t _systemIdServer = 0; ///< System ID for server
// We give MockLinkFileServer friend access so that it can use the data structures and opcodes
// to build a mock mavlink file server for testing.
friend class MockLinkFileServer;
};
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment