Newer
Older
/****************************************************************************
*
* (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 "LogDownloadController.h"
#include "MultiVehicleManager.h"
#include "QGCMAVLink.h"
#include "UAS.h"
#include "QGCApplication.h"
#include "QGCToolbox.h"
#include "QGCMapEngine.h"
#include "ParameterManager.h"
Gus Grubba
committed
#include "SettingsManager.h"
#define kGUIRateMilliseconds 17
Nate Weibley
committed
#define kChunkSize (kTableBins * MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)
QGC_LOGGING_CATEGORY(LogDownloadLog, "LogDownloadLog")
Nate Weibley
committed
//-----------------------------------------------------------------------------
struct LogDownloadData {
LogDownloadData(QGCLogEntry* entry);
QBitArray chunk_table;
uint32_t current_chunk;
QFile file;
QString filename;
uint ID;
QGCLogEntry* entry;
uint written;
size_t rate_bytes;
qreal rate_avg;
Nate Weibley
committed
QElapsedTimer elapsed;
void advanceChunk()
{
current_chunk++;
chunk_table = QBitArray(chunkBins(), false);
}
// The number of MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN bins in the current chunk
uint32_t chunkBins() const
{
return qMin(qCeil((entry->size() - current_chunk*kChunkSize)/static_cast<qreal>(MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN)),
kTableBins);
}
// The number of kChunkSize chunks in the file
uint32_t numChunks() const
{
return qCeil(entry->size() / static_cast<qreal>(kChunkSize));
}
// True if all bins in the chunk have been set to val
bool chunkEquals(const bool val) const
{
return chunk_table == QBitArray(chunk_table.size(), val);
}
};
//----------------------------------------------------------------------------------------
LogDownloadData::LogDownloadData(QGCLogEntry* entry_)
: ID(entry_->id())
, entry(entry_)
, written(0)
, rate_bytes(0)
, rate_avg(0)
{
}
//----------------------------------------------------------------------------------------
QGCLogEntry::QGCLogEntry(uint logId, const QDateTime& dateTime, uint logSize, bool received)
: _logID(logId)
, _logSize(logSize)
, _logTimeUTC(dateTime)
, _received(received)
, _selected(false)
{
//----------------------------------------------------------------------------------------
QString
QGCLogEntry::sizeStr() const
{
return QGCMapEngine::bigSizeToString(_logSize);
//----------------------------------------------------------------------------------------
LogDownloadController::LogDownloadController(void)
: _uas(NULL)
, _downloadData(NULL)
, _vehicle(NULL)
, _requestingLogEntries(false)
, _downloadingLogs(false)
, _retries(0)
{
MultiVehicleManager *manager = qgcApp()->toolbox()->multiVehicleManager();
connect(manager, &MultiVehicleManager::activeVehicleChanged, this, &LogDownloadController::_setActiveVehicle);
connect(&_timer, &QTimer::timeout, this, &LogDownloadController::_processDownload);
_setActiveVehicle(manager->activeVehicle());
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_processDownload()
{
if(_requestingLogEntries) {
_findMissingEntries();
} else if(_downloadingLogs) {
_findMissingData();
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setActiveVehicle(Vehicle* vehicle)
{
if(_uas) {
_logEntriesModel.clear();
disconnect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
disconnect(_uas, &UASInterface::logData, this, &LogDownloadController::_logData);
_uas = NULL;
}
_vehicle = vehicle;
if(_vehicle) {
_uas = vehicle->uas();
connect(_uas, &UASInterface::logEntry, this, &LogDownloadController::_logEntry);
connect(_uas, &UASInterface::logData, this, &LogDownloadController::_logData);
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t size, uint16_t id, uint16_t num_logs, uint16_t /*last_log_num*/)
{
//-- Do we care?
if(!_uas || uas != _uas || !_requestingLogEntries) {
return;
}
//-- If this is the first, pre-fill it
if(!_logEntriesModel.count() && num_logs > 0) {
//-- Is this APM? They send a first entry with bogus ID and only the
// count is valid. From now on, all entries are 1-based.
if(_vehicle->firmwareType() == MAV_AUTOPILOT_ARDUPILOTMEGA) {
_apmOneBased = 1;
}
for(int i = 0; i < num_logs; i++) {
QGCLogEntry *entry = new QGCLogEntry(i);
_logEntriesModel.append(entry);
}
}
//-- Update this log record
if(num_logs > 0) {
if(size || _vehicle->firmwareType() != MAV_AUTOPILOT_ARDUPILOTMEGA) {
id -= _apmOneBased;
if(id < _logEntriesModel.count()) {
QGCLogEntry* entry = _logEntriesModel[id];
entry->setSize(size);
entry->setTime(QDateTime::fromTime_t(time_utc));
entry->setReceived(true);
entry->setStatus(tr("Available"));
} else {
qWarning() << "Received log entry for out-of-bound index:" << id;
}
//-- No logs to list
_receivedAllEntries();
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
}
//-- Reset retry count
_retries = 0;
//-- Do we have it all?
if(_entriesComplete()) {
_receivedAllEntries();
} else {
//-- Reset timer
_timer.start(kTimeOutMilliseconds);
}
}
//----------------------------------------------------------------------------------------
bool
LogDownloadController::_entriesComplete()
{
//-- Iterate entries and look for a gap
int num_logs = _logEntriesModel.count();
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry) {
if(!entry->received()) {
return false;
}
}
}
return true;
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_resetSelection(bool canceled)
{
int num_logs = _logEntriesModel.count();
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry) {
entry->setStatus(tr("Canceled"));
}
}
emit selectionChanged();
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllEntries()
{
_timer.stop();
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
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingEntries()
{
int start = -1;
int end = -1;
int num_logs = _logEntriesModel.count();
//-- Iterate entries and look for a gap
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry) {
if(!entry->received()) {
if(start < 0)
start = i;
else
end = i;
} else {
if(start >= 0) {
break;
}
}
}
}
//-- Is there something missing?
if(start >= 0) {
//-- Have we tried too many times?
if(_retries++ > 2) {
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry && !entry->received()) {
entry->setStatus(tr("Error"));
}
}
//-- Give up
_receivedAllEntries();
qWarning() << "Too many errors retreiving log list. Giving up.";
return;
}
//-- Is it a sequence or just one entry?
if(end < 0) {
end = start;
}
//-- APM "Fix"
start += _apmOneBased;
end += _apmOneBased;
//-- Request these entries again
_requestLogList((uint32_t)start, (uint32_t) end);
} else {
_receivedAllEntries();
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_logData(UASInterface* uas, uint32_t ofs, uint16_t id, uint8_t count, const uint8_t* data)
{
if(!_uas || uas != _uas || !_downloadData) {
return;
}
if(_downloadData->ID != id) {
qWarning() << "Received log data for wrong log";
return;
}
Nate Weibley
committed
if ((ofs % MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN) != 0) {
qWarning() << "Ignored misaligned incoming packet @" << ofs;
return;
}
bool result = false;
uint32_t timeout_time = kTimeOutMilliseconds;
if(ofs <= _downloadData->entry->size()) {
Nate Weibley
committed
const uint32_t chunk = ofs / kChunkSize;
if (chunk != _downloadData->current_chunk) {
qWarning() << "Ignored packet for out of order chunk actual:expected" << chunk << _downloadData->current_chunk;
Nate Weibley
committed
return;
}
const uint16_t bin = (ofs - chunk*kChunkSize) / MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
if (bin >= _downloadData->chunk_table.size()) {
qWarning() << "Out of range bin received";
} else
_downloadData->chunk_table.setBit(bin);
if (_downloadData->file.pos() != ofs) {
// Seek to correct position
if (!_downloadData->file.seek(ofs)) {
qWarning() << "Error while seeking log file offset";
return;
}
}
if(_downloadData->file.write((const char*)data, count)) {
_downloadData->written += count;
_downloadData->rate_bytes += count;
if (_downloadData->elapsed.elapsed() >= kGUIRateMilliseconds) {
//-- Update download rate
qreal rrate = _downloadData->rate_bytes/(_downloadData->elapsed.elapsed()/1000.0);
_downloadData->rate_avg = _downloadData->rate_avg*0.95 + rrate*0.05;
_downloadData->rate_bytes = 0;
const QString status = QString("%1 (%2/s)").arg(QGCMapEngine::bigSizeToString(_downloadData->written),
QGCMapEngine::bigSizeToString(_downloadData->rate_avg));
_downloadData->entry->setStatus(status);
_downloadData->elapsed.start();
}
result = true;
//-- reset retries
_retries = 0;
//-- Reset timer
_timer.start(timeout_time);
//-- Do we have it all?
if(_logComplete()) {
_downloadData->entry->setStatus(tr("Downloaded"));
//-- Check for more
_receivedAllData();
Nate Weibley
committed
} else if (_chunkComplete()) {
_downloadData->advanceChunk();
_requestLogData(_downloadData->ID,
_downloadData->current_chunk*kChunkSize,
_downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
} else if (bin < _downloadData->chunk_table.size() - 1 && _downloadData->chunk_table.at(bin+1)) {
// Likely to be grabbing fragments and got to the end of a gap
_findMissingData();
qWarning() << "Error while writing log file chunk";
}
} else {
qWarning() << "Received log offset greater than expected";
}
if(!result) {
_downloadData->entry->setStatus(tr("Error"));
Nate Weibley
committed
//----------------------------------------------------------------------------------------
bool
LogDownloadController::_chunkComplete() const
{
return _downloadData->chunkEquals(true);
}
//----------------------------------------------------------------------------------------
bool
Nate Weibley
committed
LogDownloadController::_logComplete() const
Nate Weibley
committed
return _chunkComplete() && (_downloadData->current_chunk+1) == _downloadData->numChunks();
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_receivedAllData()
{
_timer.stop();
//-- Anything queued up for download?
if(_prepareLogDownload()) {
//-- Request Log
Nate Weibley
committed
_requestLogData(_downloadData->ID, 0, _downloadData->chunk_table.size()*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN);
_timer.start(kTimeOutMilliseconds);
_setDownloading(false);
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_findMissingData()
{
if (_logComplete()) {
_receivedAllData();
return;
Nate Weibley
committed
} else if (_chunkComplete()) {
_downloadData->advanceChunk();
_downloadData->entry->setStatus(tr("Timed Out"));
//-- Give up
qWarning() << "Too many errors retreiving log data. Giving up.";
_receivedAllData();
return;
}
Nate Weibley
committed
uint16_t start = 0, end = 0;
const int size = _downloadData->chunk_table.size();
for (; start < size; start++) {
if (!_downloadData->chunk_table.testBit(start)) {
break;
}
Nate Weibley
committed
for (end = start; end < size; end++) {
if (_downloadData->chunk_table.testBit(end)) {
break;
}
}
const uint32_t pos = _downloadData->current_chunk*kChunkSize + start*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN,
len = (end - start)*MAVLINK_MSG_LOG_DATA_FIELD_DATA_LEN;
_requestLogData(_downloadData->ID, pos, len);
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogData(uint16_t id, uint32_t offset, uint32_t count)
qCDebug(LogDownloadLog) << "Request log data (id:" << id << "offset:" << offset << "size:" << count << ")";
mavlink_message_t msg;
mavlink_msg_log_request_data_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId(),
id, offset, count);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::refresh(void)
{
_logEntriesModel.clear();
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_requestLogList(uint32_t start, uint32_t end)
{
if(_vehicle && _uas) {
qCDebug(LogDownloadLog) << "Request log entry list (" << start << "through" << end << ")";
mavlink_msg_log_request_list_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
_vehicle->id(),
_vehicle->defaultComponentId(),
start,
end);
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
//-- Wait 5 seconds before bitching about not getting anything
_timer.start(5000);
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::download(QString path)
QString dir = path;
#if defined(__mobile__)
if(dir.isEmpty()) {
Gus Grubba
committed
dir = qgcApp()->toolbox()->settingsManager()->appSettings()->logSavePath();
}
#else
if(dir.isEmpty()) {
dir = QString(); //-- TODO: QGCQFileDialog::getExistingDirectory(
// MainWindow::instance(),
// tr("Log Download Directory"),
// QDir::homePath(),
// QGCQFileDialog::ShowDirsOnly | QGCQFileDialog::DontResolveSymlinks);
}
#endif
downloadToDirectory(dir);
}
void LogDownloadController::downloadToDirectory(const QString& dir)
{
//-- Stop listing just in case
_receivedAllEntries();
//-- Reset downloads, again just in case
if(_downloadData) {
delete _downloadData;
_downloadData = 0;
}
if(!_downloadPath.isEmpty()) {
if(!_downloadPath.endsWith(QDir::separator()))
_downloadPath += QDir::separator();
//-- Iterate selected entries and shown them as waiting
int num_logs = _logEntriesModel.count();
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry) {
if(entry->selected()) {
entry->setStatus(tr("Waiting"));
_setDownloading(true);
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
//----------------------------------------------------------------------------------------
QGCLogEntry*
LogDownloadController::_getNextSelected()
{
//-- Iterate entries and look for a selected file
int num_logs = _logEntriesModel.count();
for(int i = 0; i < num_logs; i++) {
QGCLogEntry* entry = _logEntriesModel[i];
if(entry) {
if(entry->selected()) {
return entry;
}
}
}
return NULL;
}
//----------------------------------------------------------------------------------------
bool
LogDownloadController::_prepareLogDownload()
{
if(_downloadData) {
delete _downloadData;
_downloadData = NULL;
}
QGCLogEntry* entry = _getNextSelected();
if(!entry) {
return false;
}
//-- Deselect file
entry->setSelected(false);
emit selectionChanged();
bool result = false;
QString ftime;
ftime = entry->time().toString(QStringLiteral("yyyy-M-d-hh-mm-ss"));
}
_downloadData = new LogDownloadData(entry);
_downloadData->filename = QString("log_") + QString::number(entry->id()) + "_" + ftime;
if (_vehicle->firmwareType() == MAV_AUTOPILOT_PX4) {
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, loggerParam) &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, loggerParam)->rawValue().toInt() == 0) {
_downloadData->filename += ".px4log";
} else {
_downloadData->filename += ".ulg";
}
} else {
_downloadData->filename += ".bin";
}
_downloadData->file.setFileName(_downloadPath + _downloadData->filename);
//-- Append a number to the end if the filename already exists
if (_downloadData->file.exists()){
uint num_dups = 0;
QStringList filename_spl = _downloadData->filename.split('.');
do {
num_dups +=1;
_downloadData->file.setFileName(filename_spl[0] + '_' + QString::number(num_dups) + '.' + filename_spl[1]);
} while( _downloadData->file.exists());
}
//-- Create file
if (!_downloadData->file.open(QIODevice::WriteOnly)) {
qWarning() << "Failed to create log file:" << _downloadData->filename;
} else {
//-- Preallocate file
if(!_downloadData->file.resize(entry->size())) {
qWarning() << "Failed to allocate space for log file:" << _downloadData->filename;
} else {
Nate Weibley
committed
_downloadData->current_chunk = 0;
_downloadData->chunk_table = QBitArray(_downloadData->chunkBins(), false);
_downloadData->elapsed.start();
result = true;
}
}
if(!result) {
if (_downloadData->file.exists()) {
_downloadData->file.remove();
}
_downloadData->entry->setStatus(tr("Error"));
delete _downloadData;
_downloadData = NULL;
}
return result;
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setDownloading(bool active)
{
if (_downloadingLogs != active) {
_downloadingLogs = active;
_vehicle->setConnectionLostEnabled(!active);
emit downloadingLogsChanged();
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::_setListing(bool active)
{
if (_requestingLogEntries != active) {
_requestingLogEntries = active;
_vehicle->setConnectionLostEnabled(!active);
emit requestingListChanged();
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::eraseAll(void)
{
if(_vehicle && _uas) {
mavlink_message_t msg;
mavlink_msg_log_erase_pack_chan(
qgcApp()->toolbox()->mavlinkProtocol()->getSystemId(),
qgcApp()->toolbox()->mavlinkProtocol()->getComponentId(),
_vehicle->priorityLink()->mavlinkChannel(),
&msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->defaultComponentId());
_vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg);
}
}
//----------------------------------------------------------------------------------------
void
LogDownloadController::cancel(void)
{
if(_uas){
_receivedAllEntries();
}
if(_downloadData) {
_downloadData->entry->setStatus(tr("Canceled"));
if (_downloadData->file.exists()) {
_downloadData->file.remove();
}
delete _downloadData;
_downloadData = 0;
}
_setDownloading(false);
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
}
//-----------------------------------------------------------------------------
QGCLogModel::QGCLogModel(QObject* parent)
: QAbstractListModel(parent)
{
}
//-----------------------------------------------------------------------------
QGCLogEntry*
QGCLogModel::get(int index)
{
if (index < 0 || index >= _logEntries.count()) {
return NULL;
}
return _logEntries[index];
}
//-----------------------------------------------------------------------------
int
QGCLogModel::count() const
{
return _logEntries.count();
}
//-----------------------------------------------------------------------------
void
QGCLogModel::append(QGCLogEntry* object)
{
beginInsertRows(QModelIndex(), rowCount(), rowCount());
QQmlEngine::setObjectOwnership(object, QQmlEngine::CppOwnership);
_logEntries.append(object);
endInsertRows();
emit countChanged();
}
//-----------------------------------------------------------------------------
void
QGCLogModel::clear(void)
{
if(!_logEntries.isEmpty()) {
beginRemoveRows(QModelIndex(), 0, _logEntries.count());
while (_logEntries.count()) {
QGCLogEntry* entry = _logEntries.last();
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
_logEntries.removeLast();
}
endRemoveRows();
emit countChanged();
}
}
//-----------------------------------------------------------------------------
QGCLogEntry*
QGCLogModel::operator[](int index)
{
return get(index);
}
//-----------------------------------------------------------------------------
int
QGCLogModel::rowCount(const QModelIndex& /*parent*/) const
{
return _logEntries.count();
}
//-----------------------------------------------------------------------------
QVariant
QGCLogModel::data(const QModelIndex & index, int role) const {
if (index.row() < 0 || index.row() >= _logEntries.count())
return QVariant();
if (role == ObjectRole)
return QVariant::fromValue(_logEntries[index.row()]);
return QVariant();
}
//-----------------------------------------------------------------------------
QHash<int, QByteArray>
QGCLogModel::roleNames() const {
QHash<int, QByteArray> roles;
roles[ObjectRole] = "logEntry";
return roles;
}