1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
/****************************************************************************
*
* (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 "FileManager.h"
#include "QGC.h"
#include "MAVLinkProtocol.h"
#include "MainWindow.h"
#include "Vehicle.h"
#include "QGCApplication.h"
#include <QFile>
#include <QDir>
#include <string>
QGC_LOGGING_CATEGORY(FileManagerLog, "FileManagerLog")
FileManager::FileManager(QObject* parent, Vehicle* vehicle)
: QObject(parent)
, _currentOperation(kCOIdle)
, _vehicle(vehicle)
, _dedicatedLink(NULL)
, _lastOutgoingSeqNumber(0)
, _activeSession(0)
, _systemIdQGC(0)
{
connect(&_ackTimer, &QTimer::timeout, this, &FileManager::_ackTimeout);
_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 FileManager::_openAckResponse(Request* openAck)
{
qCDebug(FileManagerLog) << 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
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);
}
/// Closes out a download session by writing the file and doing cleanup.
/// @param success true: successful download completion, false: error during download
void FileManager::_closeDownloadSession(bool success)
{
qCDebug(FileManagerLog) << QString("_closeDownloadSession: success(%1)").arg(success);
_currentOperation = kCOIdle;
if (success) {
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 FileManager::_closeUploadSession(bool success)
{
qCDebug(FileManagerLog) << 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 FileManager::_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) {
_closeDownloadSession(false /* failure */);
_emitErrorMessage(tr("Download: Offset returned (%1) differs from offset requested/expected (%2)").arg(readAck->hdr.offset).arg(_downloadOffset));
return;
}
qCDebug(FileManagerLog) << QString("_downloadAckResponse: offset(%1) size(%2) burstComplete(%3)").arg(readAck->hdr.offset).arg(readAck->hdr.size).arg(readAck->hdr.burstComplete);
_downloadOffset += readAck->hdr.size;
_readFileAccumulator.append((const char*)readAck->data, readAck->hdr.size);
if (_downloadFileSize != 0) {
emit commandProgress(100 * ((float)_readFileAccumulator.length() / (float)_downloadFileSize));
}
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 FileManager::_listAckResponse(Request* listAck)
{
if (listAck->hdr.offset != _listOffset) {
_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 FileManager::_createAckResponse(Request* createAck)
{
qCDebug(FileManagerLog) << "_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 FileManager::_writeAckResponse(Request* writeAck)
{
if(_writeOffset + _writeSize >= _writeFileSize){
_closeUploadSession(true /* success */);
}
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 FileManager::_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 FileManager::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];
_clearAckTimeout();
qCDebug(FileManagerLog) << "receiveMessage" << request->hdr.opcode;
uint16_t incomingSeqNumber = request->hdr.seqNumber;
// Make sure we have a good sequence number
uint16_t expectedSeqNumber = _lastOutgoingSeqNumber + 1;
if (incomingSeqNumber != expectedSeqNumber) {
switch (_currentOperation) {
case kCOBurst:
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;
}
_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
_lastOutgoingSeqNumber = 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 {
// 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 FileManager::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 FileManager::_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 FileManager::_sendListCommand(void)
{
Request request;
request.hdr.session = 0;
request.hdr.opcode = kCmdListDirectory;
request.hdr.offset = _listOffset;
request.hdr.size = 0;
_fillRequestWithString(&request, _listPath);
qCDebug(FileManagerLog) << "listDirectory: path:" << _listPath << "offset:" << _listOffset;
_sendRequest(&request);
}
void FileManager::downloadPath(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(FileManagerLog) << "downloadPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, true /* read file */);
}
void FileManager::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(FileManagerLog) << "streamPath from:" << from << "to:" << downloadDir;
_downloadWorker(from, downloadDir, false /* stream file */);
}
void FileManager::_downloadWorker(const QString& from, const QDir& downloadDir, bool readFile)
{
if (from.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=from.size()-1; i>=0; i--) {
if (from[i] == '/') {
break;
}
}
i++; // move past slash
_readFileDownloadFilename = from.right(from.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, from);
_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 FileManager::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);
}
QString FileManager::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 FileManager::_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 FileManager::_setupAckTimeout(void)
{
qCDebug(FileManagerLog) << "_setupAckTimeout";
Q_ASSERT(!_ackTimer.isActive());
_ackTimer.setSingleShot(true);
_ackTimer.start(ackTimerTimeoutMsecs);
}
/// @brief Clears the ack timeout timer
void FileManager::_clearAckTimeout(void)
{
qCDebug(FileManagerLog) << "_clearAckTimeout";
_ackTimer.stop();
}
/// @brief Called when ack timeout timer fires
void FileManager::_ackTimeout(void)
{
qCDebug(FileManagerLog) << "_ackTimeout";
// 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:
_currentOperation = kCOIdle;
_emitErrorMessage(QString("Timeout waiting for ack: Command failed (%1)").arg(_currentOperation));
break;
}
}
void FileManager::_sendResetCommand(void)
{
Request request;
request.hdr.opcode = kCmdResetSessions;
request.hdr.size = 0;
_sendRequest(&request);
}
void FileManager::_emitErrorMessage(const QString& msg)
{
qCDebug(FileManagerLog) << "Error:" << msg;
emit commandError(msg);
}
void FileManager::_emitListEntry(const QString& entry)
{
qCDebug(FileManagerLog) << "_emitListEntry" << entry;
emit listEntry(entry);
}
/// @brief Sends the specified Request out to the UAS.
void FileManager::_sendRequest(Request* request)
{
mavlink_message_t message;
_setupAckTimeout();
_lastOutgoingSeqNumber++;
request->hdr.seqNumber = _lastOutgoingSeqNumber;
qCDebug(FileManagerLog) << "_sendRequest opcode:" << request->hdr.opcode << "seqNumber:" << request->hdr.seqNumber;
if (_systemIdQGC == 0) {
_systemIdQGC = qgcApp()->toolbox()->mavlinkProtocol()->getSystemId();
}
// 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->sendMessageOnLink(link, message);
}