15#include <QtCore/QApplicationStatic>
16#include <QtCore/QTimer>
22 , _timer(new QTimer(this))
25 qCDebug(OnboardLogControllerLog) <<
this;
28 (void) connect(_timer, &QTimer::timeout,
this, &OnboardLogController::_processDownload);
30 _timer->setSingleShot(
false);
32 _setActiveVehicle(MultiVehicleManager::instance()->activeVehicle());
37 qCDebug(OnboardLogControllerLog) <<
this;
42 const QString dir = path.isEmpty() ? SettingsManager::instance()->appSettings()->
logSavePath() : path;
43 _downloadToDirectory(dir);
46void OnboardLogController::_downloadToDirectory(
const QString &dir)
48 _receivedAllEntries();
50 _downloadData.reset();
53 if (_downloadPath.isEmpty()) {
57 if (!_downloadPath.endsWith(QDir::separator())) {
58 _downloadPath += QDir::separator();
63 log->setStatus(tr(
"Waiting"));
66 _setDownloading(
true);
70void OnboardLogController::_processDownload()
72 if (_requestingLogEntries) {
73 _findMissingEntries();
74 }
else if (_downloadingLogs) {
79void OnboardLogController::_findMissingEntries()
81 const int num_logs = _logEntriesModel->
count();
84 for (
int i = 0; i < num_logs; i++) {
90 if (!entry->received()) {
96 }
else if (start >= 0) {
102 _receivedAllEntries();
106 if (_retries++ > 2) {
107 for (
int i = 0; i < num_logs; i++) {
109 if (entry && !entry->received()) {
110 entry->setStatus(tr(
"Error"));
114 _receivedAllEntries();
115 qCWarning(OnboardLogControllerLog) <<
"Too many errors retreiving log list. Giving up.";
126 _requestLogList(
static_cast<uint32_t
>(start),
static_cast<uint32_t
>(end));
129void OnboardLogController::_setActiveVehicle(
Vehicle *vehicle)
131 if (vehicle == _vehicle) {
137 (void) disconnect(_vehicle, &
Vehicle::logEntry,
this, &OnboardLogController::_logEntry);
138 (void) disconnect(_vehicle, &
Vehicle::logData,
this, &OnboardLogController::_logData);
144 (void) connect(_vehicle, &
Vehicle::logEntry,
this, &OnboardLogController::_logEntry);
145 (void) connect(_vehicle, &
Vehicle::logData,
this, &OnboardLogController::_logData);
149void OnboardLogController::_logEntry(uint32_t time_utc, uint32_t size, uint16_t
id, uint16_t num_logs, uint16_t last_log_num)
151 Q_UNUSED(last_log_num);
153 if (!_requestingLogEntries) {
157 if ((_logEntriesModel->
count() == 0) && (num_logs > 0)) {
158 if (_vehicle->
firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
163 for (
int i = 0; i < num_logs; i++) {
165 _logEntriesModel->
append(entry);
170 if ((size > 0) || (_vehicle->
firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA)) {
172 if (id < _logEntriesModel->count()) {
174 entry->setSize(size);
175 entry->setTime(QDateTime::fromSecsSinceEpoch(time_utc));
176 entry->setReceived(
true);
177 entry->setStatus(tr(
"Available"));
179 qCWarning(OnboardLogControllerLog) <<
"Received onboard log entry for out-of-bound index:" << id;
183 _receivedAllEntries();
188 if (_entriesComplete()) {
189 _receivedAllEntries();
191 _timer->start(kTimeOutMs);
195void OnboardLogController::_receivedAllEntries()
201bool OnboardLogController::_entriesComplete()
const
203 const int num_logs = _logEntriesModel->
count();
204 for (
int i = 0; i < num_logs; i++) {
210 if (!entry->received()) {
218void OnboardLogController::_logData(uint32_t ofs, uint16_t
id, uint8_t count,
const uint8_t *data)
220 if (!_downloadingLogs || !_downloadData) {
225 if (_downloadData->ID !=
id) {
226 qCWarning(OnboardLogControllerLog) <<
"Received log data for wrong log";
230 if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
231 qCWarning(OnboardLogControllerLog) <<
"Ignored misaligned incoming packet @" << ofs;
236 if (ofs <= _downloadData->entry->size()) {
239 if (chunk != _downloadData->current_chunk) {
240 qCWarning(OnboardLogControllerLog) <<
"Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
245 if (bin >= _downloadData->chunk_table.size()) {
246 qCWarning(OnboardLogControllerLog) <<
"Out of range bin received";
248 _downloadData->chunk_table.setBit(bin);
251 if (_downloadData->file.pos() != ofs) {
252 if (!_downloadData->file.seek(ofs)) {
253 qCWarning(OnboardLogControllerLog) <<
"Error while seeking log file offset";
258 if (_downloadData->file.write(
reinterpret_cast<const char*
>(data), count)) {
259 _downloadData->written += count;
260 _downloadData->rate_bytes += count;
266 _timer->start(kTimeOutMs);
267 if (_logComplete()) {
268 _downloadData->entry->setStatus(tr(
"Downloaded"));
270 }
else if (_chunkComplete()) {
271 _downloadData->advanceChunk();
272 _requestLogData(_downloadData->ID,
274 _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
275 }
else if ((bin < (_downloadData->chunk_table.size() - 1)) && _downloadData->chunk_table.at(bin + 1)) {
280 qCWarning(OnboardLogControllerLog) <<
"Error while writing log file chunk";
283 qCWarning(OnboardLogControllerLog) <<
"Received log offset greater than expected";
287 _downloadData->entry->setStatus(tr(
"Error"));
291void OnboardLogController::_findMissingData()
293 if (_logComplete()) {
298 if (_chunkComplete()) {
299 _downloadData->advanceChunk();
306 uint16_t start = 0, end = 0;
307 const int size = _downloadData->chunk_table.size();
308 for (; start < size; start++) {
309 if (!_downloadData->chunk_table.testBit(start)) {
314 for (end = start; end < size; end++) {
315 if (_downloadData->chunk_table.testBit(end)) {
321 const uint32_t len = (end - start) * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
322 _requestLogData(_downloadData->ID, pos, len, _retries);
325void OnboardLogController::_updateDataRate()
327 constexpr uint kSizeUpdateThreshold = 102400;
328 const bool timeThresholdMet = _downloadData->elapsed.elapsed() >= kGUIRateMs;
329 const bool sizeThresholdMet = (_downloadData->written - _downloadData->last_status_written) >= kSizeUpdateThreshold;
331 if (!timeThresholdMet && !sizeThresholdMet) {
336 if (timeThresholdMet) {
338 const qreal rate = _downloadData->rate_bytes / (_downloadData->elapsed.elapsed() / 1000.0);
339 _downloadData->rate_avg = (_downloadData->rate_avg * 0.95) + (rate * 0.05);
340 _downloadData->rate_bytes = 0;
344 _downloadData->elapsed.start();
351 _downloadData->entry->setStatus(status);
352 _downloadData->last_status_written = _downloadData->written;
355bool OnboardLogController::_chunkComplete()
const
357 return _downloadData->chunkEquals(
true);
360bool OnboardLogController::_logComplete()
const
362 return (_chunkComplete() && ((_downloadData->current_chunk + 1) == _downloadData->numChunks()));
365void OnboardLogController::_receivedAllData()
368 if (_prepareLogDownload()) {
369 _requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size() * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
370 _timer->start(kTimeOutMs);
373 _setDownloading(
false);
377bool OnboardLogController::_prepareLogDownload()
379 _downloadData.reset();
386 entry->setSelected(
false);
389 const QString ftime = (entry->time().date().year() >= 2010) ? entry->time().toString(QStringLiteral(
"yyyy-M-d-hh-mm-ss")) : QStringLiteral(
"UnknownDate");
391 _downloadData = std::make_unique<OnboardLogDownloadData>(entry);
392 _downloadData->filename = QStringLiteral(
"log_") + QString::number(entry->id()) +
"_" + ftime;
395 const QString loggerParam = QStringLiteral(
"SYS_LOGGER");
398 _downloadData->filename +=
".px4log";
400 _downloadData->filename +=
".ulg";
403 _downloadData->filename +=
".bin";
406 _downloadData->file.setFileName(_downloadPath + _downloadData->filename);
408 if (_downloadData->file.exists()) {
409 uint32_t numDups = 0;
410 const QStringList filename_spl = _downloadData->filename.split(
'.');
413 const QString filename = filename_spl[0] +
'_' + QString::number(numDups) +
'.' + filename_spl[1];
414 _downloadData->file.setFileName(_downloadPath + filename);
415 }
while ( _downloadData->file.exists());
419 if (!_downloadData->file.open(QIODevice::WriteOnly)) {
420 qCWarning(OnboardLogControllerLog) <<
"Failed to create log file:" << _downloadData->filename;
421 }
else if (!_downloadData->file.resize(entry->size())) {
422 qCWarning(OnboardLogControllerLog) <<
"Failed to allocate space for log file:" << _downloadData->filename;
424 _downloadData->current_chunk = 0;
425 _downloadData->chunk_table = QBitArray(_downloadData->chunkBins(),
false);
426 _downloadData->elapsed.start();
431 if (_downloadData->file.exists()) {
432 (void) _downloadData->file.remove();
435 _downloadData->entry->setStatus(QStringLiteral(
"Error"));
436 _downloadData.reset();
445 _requestLogList(0, 0xffff);
450 const int numLogs = _logEntriesModel->
count();
451 for (
int i = 0; i < numLogs; i++) {
457 if (entry->selected()) {
468 _receivedAllEntries();
471 _downloadData->entry->setStatus(QStringLiteral(
"Canceled"));
472 if (_downloadData->file.exists()) {
473 (void) _downloadData->file.remove();
476 _downloadData.reset();
479 _resetSelection(
true);
480 _setDownloading(
false);
483void OnboardLogController::_resetSelection(
bool canceled)
485 const int num_logs = _logEntriesModel->
count();
486 for (
int i = 0; i < num_logs; i++) {
492 if (entry->selected()) {
494 entry->setStatus(tr(
"Canceled"));
496 entry->setSelected(
false);
506 qCWarning(OnboardLogControllerLog) <<
"Vehicle Unavailable";
512 qCWarning(OnboardLogControllerLog) <<
"Link Unavailable";
517 (void) mavlink_msg_log_erase_pack_chan(
520 sharedLink->mavlinkChannel(),
527 qCWarning(OnboardLogControllerLog) <<
"Failed to send";
534void OnboardLogController::_requestLogList(uint32_t start, uint32_t end)
537 qCWarning(OnboardLogControllerLog) <<
"Vehicle Unavailable";
543 qCWarning(OnboardLogControllerLog) <<
"Link Unavailable";
548 (void) mavlink_msg_log_request_list_pack_chan(
551 sharedLink->mavlinkChannel(),
560 qCWarning(OnboardLogControllerLog) <<
"Failed to send";
564 qCDebug(OnboardLogControllerLog) <<
"Request onboard log entry list (" << start <<
"through" << end <<
")";
566 _timer->start(kRequestLogListTimeoutMs);
569void OnboardLogController::_requestLogData(uint16_t
id, uint32_t offset, uint32_t count,
int retryCount)
572 qCWarning(OnboardLogControllerLog) <<
"Vehicle Unavailable";
578 qCWarning(OnboardLogControllerLog) <<
"Link Unavailable";
583 qCDebug(OnboardLogControllerLog) <<
"Request log data (id:" <<
id <<
"offset:" << offset <<
"size:" << count <<
"retryCount" << retryCount <<
")";
586 (void) mavlink_msg_log_request_data_pack_chan(
589 sharedLink->mavlinkChannel(),
599 qCWarning(OnboardLogControllerLog) <<
"Failed to send";
603void OnboardLogController::_requestLogEnd()
606 qCWarning(OnboardLogControllerLog) <<
"Vehicle Unavailable";
612 qCWarning(OnboardLogControllerLog) <<
"Link Unavailable";
617 (void) mavlink_msg_log_request_end_pack_chan(
620 sharedLink->mavlinkChannel(),
627 qCWarning(OnboardLogControllerLog) <<
"Failed to send";
631void OnboardLogController::_setDownloading(
bool active)
633 if (_downloadingLogs != active) {
634 _downloadingLogs = active;
640void OnboardLogController::_setListing(
bool active)
642 if (_requestingLogEntries != active) {
643 _requestingLogEntries = active;
651 if (_compressLogs != compress) {
652 _compressLogs = compress;
660 qCWarning(OnboardLogControllerLog) <<
"Log compression not yet implemented (decompression-only API)";
669void OnboardLogController::_handleCompressionProgress(qreal progress)
675void OnboardLogController::_handleCompressionFinished(
bool success)
std::shared_ptr< LinkInterface > SharedLinkInterfacePtr
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
static int getComponentId()
Get the component id of this application.
static MAVLinkProtocol * instance()
int getSystemId() const
Get the system id of this application.
void activeVehicleChanged(Vehicle *activeVehicle)
void downloadingLogsChanged()
void requestingListChanged()
void download(const QString &path=QString())
void setCompressLogs(bool compress)
void compressLogsChanged()
bool compressLogFile(const QString &logPath)
Compress a single log file.
void cancelCompression()
Cancel compression.
bool parameterExists(int componentId, const QString ¶mName) const
Fact * getParameter(int componentId, const QString ¶mName)
static constexpr int defaultComponentId
void append(QObject *object)
Caller maintains responsibility for object ownership and deletion.
int count() const override final
void clearAndDeleteContents() override final
Clears the list and calls deleteLater on each entry.
WeakLinkInterfacePtr primaryLink() const
void setCommunicationLostEnabled(bool communicationLostEnabled)
VehicleLinkManager * vehicleLinkManager()
void logEntry(uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t last_log_num)
MAV_AUTOPILOT firmwareType() const
bool sendMessageOnLinkThreadSafe(LinkInterface *link, mavlink_message_t message)
int defaultComponentId() const
ParameterManager * parameterManager()
void logData(uint32_t ofs, uint16_t id, uint8_t count, const uint8_t *data)
QString bigSizeToString(quint64 size)
Locale-aware byte-size with unit: B, KB, MB, GB, TB. 1 fractional digit above 1 KB.
static const uint32_t kChunkSize