QGroundControl
Ground Control Station for MAVLink Drones
Loading...
Searching...
No Matches
LogReplayLink.cc
Go to the documentation of this file.
1#include "LogReplayLink.h"
2#include "LinkManager.h"
3#include "MAVLinkProtocol.h"
6
7#include <QtCore/QFileInfo>
8#include <QtCore/QtEndian>
9#include <QtCore/QThread>
10#include <QtCore/QTimer>
11
12QGC_LOGGING_CATEGORY(LogReplayLinkLog, "Comms.LogReplayLink")
13
14/*===========================================================================*/
15
16LogReplayConfiguration::LogReplayConfiguration(const QString &name, QObject *parent)
17 : LinkConfiguration(name, parent)
18{
19 qCDebug(LogReplayLinkLog) << this;
20}
21
22LogReplayConfiguration::LogReplayConfiguration(const LogReplayConfiguration *copy, QObject *parent)
23 : LinkConfiguration(copy, parent)
24 , _logFilename(copy->logFilename())
25{
26 qCDebug(LogReplayLinkLog) << this;
27}
28
29LogReplayConfiguration::~LogReplayConfiguration()
30{
31 qCDebug(LogReplayLinkLog) << this;
32}
33
34void LogReplayConfiguration::copyFrom(const LinkConfiguration *source)
35{
36 LinkConfiguration::copyFrom(source);
37
38 const LogReplayConfiguration *logReplaySource = qobject_cast<const LogReplayConfiguration*>(source);
39
40 setLogFilename(logReplaySource->logFilename());
41}
42
43void LogReplayConfiguration::loadSettings(QSettings &settings, const QString &root)
44{
45 settings.beginGroup(root);
46
47 setLogFilename(settings.value("logFilename", "").toString());
48
49 settings.endGroup();
50}
51
52void LogReplayConfiguration::saveSettings(QSettings &settings, const QString &root) const
53{
54 settings.beginGroup(root);
55
56 settings.setValue("logFilename", _logFilename);
57
58 settings.endGroup();
59}
60
61QString LogReplayConfiguration::logFilenameShort() const
62{
63 return QFileInfo(_logFilename).fileName();
64}
65
66void LogReplayConfiguration::setLogFilename(const QString &logFilename)
67{
68 if (logFilename != _logFilename) {
69 _logFilename = logFilename;
70 emit filenameChanged();
71 }
72}
73
74/*===========================================================================*/
75
77 : QObject(parent)
78 , _logReplayConfig(config)
79{
80 qCDebug(LogReplayLinkLog) << this;
81}
82
84{
86
87 qCDebug(LogReplayLinkLog) << this;
88}
89
91{
92 if (!_readTickTimer) {
93 _readTickTimer = new QTimer(this);
94 }
95
96 (void) connect(_readTickTimer, &QTimer::timeout, this, &LogReplayWorker::_readNextLogEntry);
97}
98
100{
101 if (isConnected()) {
102 qCWarning(LogReplayLinkLog) << "Already connected";
103 return;
104 }
105
106 if (MultiVehicleManager::instance()->activeVehicle()) {
107 emit errorOccurred(tr("You must close all connections prior to replaying a log."));
108 return;
109 }
110
111 if (!_loadLogFile()) {
113 return;
114 }
115
116 _isConnected = true;
117 emit connected();
118
119 play();
120}
121
123{
124 if (!isConnected()) {
125 qCDebug(LogReplayLinkLog) << "Already disconnected";
126 return;
127 }
128
129 qCDebug(LogReplayLinkLog) << "Disconnecting from log";
130
131 if (_readTickTimer) {
132 _readTickTimer->stop();
133 }
134
135 if (_logFile.isOpen()) {
136 _logFile.close();
137 }
138
139 _isConnected = false;
140 emit disconnected();
141}
142
144{
145 return (_readTickTimer && _readTickTimer->isActive());
146}
147
149{
150 LinkManager::instance()->setConnectionsSuspended(tr("Connect not allowed during Flight Data replay."));
152
153 if (_logFile.atEnd()) {
154 _resetPlaybackToBeginning();
155 }
156
157 _playbackStartTimeMSecs = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch());
158 _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
159 _readTickTimer->start(1);
160
161 emit playbackStarted();
162}
163
165{
166 LinkManager::instance()->setConnectionsAllowed();
168
169 _readTickTimer->stop();
170
171 emit playbackPaused();
172}
173
174void LogReplayWorker::setPlaybackSpeed(qreal playbackSpeed)
175{
176 _playbackSpeed = playbackSpeed;
177 _playbackStartTimeMSecs = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch());
178 _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
179 _readTickTimer->start(1);
180}
181
182void LogReplayWorker::movePlayhead(qreal percentComplete)
183{
184 if (isPlaying()) {
185 pause();
186 if (_readTickTimer->isActive()) {
187 return;
188 }
189 }
190
191 percentComplete = qBound(0., percentComplete, 100.);
192 const qreal percentCompleteMult = percentComplete / 100.0;
193 const qint64 newFilePos = static_cast<qint64>(percentCompleteMult * static_cast<qreal>(_logFile.size()));
194 if (!_logFile.seek(newFilePos)) {
195 emit errorOccurred(tr("Unable to seek to new position"));
196 return;
197 }
198
199 mavlink_message_t dummy{};
200 _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy);
201
202 qreal newRelativeTimeUSecs = static_cast<qreal>(_logCurrentTimeUSecs - _logStartTimeUSecs);
203 const qreal baudRate = _logFile.size() / static_cast<qreal>(_logDurationUSecs) / 1e6;
204 const qreal desiredTimeUSecs = percentCompleteMult * _logDurationUSecs;
205 const qint64 offset = (newRelativeTimeUSecs - desiredTimeUSecs) * baudRate;
206 if (!_logFile.seek(_logFile.pos() + offset)) {
207 emit errorOccurred(tr("Unable to seek to new position"));
208 return;
209 }
210
211 _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy);
212 _signalCurrentLogTimeSecs();
213
214 newRelativeTimeUSecs = static_cast<qreal>(_logCurrentTimeUSecs - _logStartTimeUSecs);
215 percentComplete = ((newRelativeTimeUSecs / _logDurationUSecs) * 100);
216 emit playbackPercentCompleteChanged(percentComplete);
217}
218
219void LogReplayWorker::_resetPlaybackToBeginning()
220{
221 if (_logFile.isOpen()) {
222 if (!_logFile.reset()) {
223 qCWarning(LogReplayLinkLog) << "failed to reset log file:" << _logFile.error() << _logFile.errorString();
224 }
225 }
226
227 _playbackStartTimeMSecs = 0;
228 _playbackStartLogTimeUSecs = 0;
229 _logCurrentTimeUSecs = _logStartTimeUSecs;
230}
231
232void LogReplayWorker::_readNextLogEntry()
233{
234 int timeToNextExecutionMSecs = 0;
235 while (timeToNextExecutionMSecs < 3) {
236 QByteArray bytes;
237 bytes.reserve(_logFile.bytesAvailable());
238 const qint64 nextTimeUSecs = _readNextMavlinkMessage(bytes);
239 emit dataReceived(bytes);
240 emit playbackPercentCompleteChanged((static_cast<float>(_logCurrentTimeUSecs - _logStartTimeUSecs) / static_cast<float>(_logDurationUSecs)) * 100);
241
242 if (_logFile.atEnd()) {
243 pause();
244 emit playbackAtEnd();
245 return;
246 }
247
248 _logCurrentTimeUSecs = nextTimeUSecs;
249
250 const quint64 currentTimeMSecs = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch());
251 const quint64 desiredPlayheadMovementTimeMSecs = ((_logCurrentTimeUSecs - _playbackStartLogTimeUSecs) / 1000) / _playbackSpeed;
252 const quint64 desiredCurrentTimeMSecs = _playbackStartTimeMSecs + desiredPlayheadMovementTimeMSecs;
253 timeToNextExecutionMSecs = desiredCurrentTimeMSecs - currentTimeMSecs;
254 }
255
256 _signalCurrentLogTimeSecs();
257
258 _readTickTimer->start(timeToNextExecutionMSecs);
259}
260
261void LogReplayWorker::_signalCurrentLogTimeSecs()
262{
263 emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
264}
265
266bool LogReplayWorker::_loadLogFile()
267{
268 if (_logFile.isOpen()) {
269 _logFile.close();
270 emit errorOccurred(tr("Attempt to load new log while log being played"));
271 return false;
272 }
273
274 const QString logFilename = _logReplayConfig->logFilename();
275 _logFile.setFileName(logFilename);
276 if (!_logFile.open(QFile::ReadOnly)) {
277 emit errorOccurred(tr("Unable to open log file: '%1', error: %2").arg(logFilename, _logFile.errorString()));
278 return false;
279 }
280
281 QFileInfo logFileInfo;
282 logFileInfo.setFile(logFilename);
283 _logFileSize = logFileInfo.size();
284
285 const quint64 startTimeUSecs = _parseTimestamp(_logFile.read(kTimestamp));
286 const quint64 endTimeUSecs = _findLastTimestamp();
287 if (endTimeUSecs <= startTimeUSecs) {
288 _logFile.close();
289 emit errorOccurred(tr("The log file '%1' is corrupt or empty.").arg(logFilename));
290 return false;
291 }
292
293 _logEndTimeUSecs = endTimeUSecs;
294 _logStartTimeUSecs = startTimeUSecs;
295 _logDurationUSecs = endTimeUSecs - startTimeUSecs;
296 _logCurrentTimeUSecs = startTimeUSecs;
297
298 if (!_logFile.reset()) {
299 qCWarning(LogReplayLinkLog) << "failed to reset log file:" << _logFile.error() << _logFile.errorString();
300 }
301
302 const quint64 logDurationSecondsTotal = _logDurationUSecs / 1000000;
303 emit logFileStats(logDurationSecondsTotal);
304
305 return true;
306}
307
308quint64 LogReplayWorker::_parseTimestamp(const QByteArray &bytes)
309{
310 const quint64 currentTimestamp = static_cast<quint64>(QDateTime::currentMSecsSinceEpoch()) * 1000;
311 quint64 timestamp = qFromBigEndian(*reinterpret_cast<const quint64*>(bytes.constData()));
312 if (timestamp > currentTimestamp) {
313 timestamp = qbswap(timestamp);
314 }
315
316 return timestamp;
317}
318
319quint64 LogReplayWorker::_readNextMavlinkMessage(QByteArray &bytes)
320{
321 bytes.clear();
322
323 char nextByte;
324 while (_logFile.getChar(&nextByte)) {
325 mavlink_message_t message{};
326 mavlink_status_t status{};
327 const bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &message, &status);
328
329 if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
330 bytes.clear();
331 }
332 (void) bytes.append(nextByte);
333
334 if (messageFound) {
335 const QByteArray rawTime = _logFile.read(kTimestamp);
336 return _parseTimestamp(rawTime);
337 }
338 }
339
340 return 0;
341}
342
343quint64 LogReplayWorker::_seekToNextMavlinkMessage(mavlink_message_t &nextMsg)
344{
345 mavlink_reset_channel_status(_mavlinkChannel);
346
347 qint64 messageStartPos = -1;
348 char nextByte;
349 while (_logFile.getChar(&nextByte)) {
350 mavlink_status_t status{};
351 const bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &nextMsg, &status);
352
353 if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
354 messageStartPos = _logFile.pos() - 1;
355 }
356
357 if (messageFound && (messageStartPos != -1)) {
358 if (!_logFile.seek(messageStartPos - kTimestamp)) {
359 qCWarning(LogReplayLinkLog) << "Failed to seek next message:" << _logFile.error() << _logFile.errorString();
360 break;
361 }
362
363 const QByteArray rawTime = _logFile.read(kTimestamp);
364 return _parseTimestamp(rawTime);
365 }
366 }
367
368 return 0;
369}
370
371quint64 LogReplayWorker::_findLastTimestamp()
372{
373 if (!_logFile.reset()) {
374 qCWarning(LogReplayLinkLog) << "failed to reset log file:" << _logFile.error() << _logFile.errorString();
375 }
376
377 mavlink_reset_channel_status(_mavlinkChannel);
378
379 quint64 lastTimestamp = 0;
380
381 while (_logFile.bytesAvailable() > static_cast<qint64>(kTimestamp)) {
382 lastTimestamp = _parseTimestamp(_logFile.read(kTimestamp));
383
384 bool endOfMessage = false;
385 char nextByte;
386 while (!endOfMessage && _logFile.getChar(&nextByte)) {
387 mavlink_message_t msg{};
388 mavlink_status_t status{};
389 endOfMessage = mavlink_parse_char(_mavlinkChannel, nextByte, &msg, &status);
390 }
391 }
392
393 return lastTimestamp;
394}
395
396/*===========================================================================*/
397
399 : LinkInterface(config, parent)
400 , _logReplayConfig(qobject_cast<LogReplayConfiguration*>(config.get()))
401 , _worker(new LogReplayWorker(_logReplayConfig))
402 , _workerThread(new QThread(this))
403{
404 qCDebug(LogReplayLinkLog) << this;
405
406 _workerThread->setObjectName(QStringLiteral("LogReplay_%1").arg(_logReplayConfig->name()));
407
408 _worker->moveToThread(_workerThread);
409
410 (void) connect(_workerThread, &QThread::started, _worker, &LogReplayWorker::setup);
411 (void) connect(_workerThread, &QThread::finished, _worker, &QObject::deleteLater);
412
413 (void) connect(_worker, &LogReplayWorker::connected, this, &LogReplayLink::_onConnected, Qt::QueuedConnection);
414 (void) connect(_worker, &LogReplayWorker::disconnected, this, &LogReplayLink::_onDisconnected, Qt::QueuedConnection);
415 (void) connect(_worker, &LogReplayWorker::errorOccurred, this, &LogReplayLink::_onErrorOccurred, Qt::QueuedConnection);
416 (void) connect(_worker, &LogReplayWorker::dataReceived, this, &LogReplayLink::_onDataReceived, Qt::QueuedConnection);
417
418 (void) connect(_worker, &LogReplayWorker::logFileStats, this, &LogReplayLink::logFileStats, Qt::QueuedConnection);
419 (void) connect(_worker, &LogReplayWorker::playbackStarted, this, &LogReplayLink::playbackStarted, Qt::QueuedConnection);
420 (void) connect(_worker, &LogReplayWorker::playbackPaused, this, &LogReplayLink::playbackPaused, Qt::QueuedConnection);
421 (void) connect(_worker, &LogReplayWorker::playbackPercentCompleteChanged, this, &LogReplayLink::playbackPercentCompleteChanged, Qt::QueuedConnection);
422 (void) connect(_worker, &LogReplayWorker::currentLogTimeSecs, this, &LogReplayLink::currentLogTimeSecs, Qt::QueuedConnection);
423 (void) connect(_worker, &LogReplayWorker::disconnected, this, &LogReplayLink::disconnected, Qt::QueuedConnection);
424
425 _workerThread->start();
426}
427
429{
430 if (isConnected()) {
431 (void) QMetaObject::invokeMethod(_worker, "disconnectFromLog", Qt::BlockingQueuedConnection);
432 _onDisconnected();
433 }
434
435 _workerThread->quit();
436 if (!_workerThread->wait()) {
437 qCWarning(LogReplayLinkLog) << "Failed to wait for LogReplay Thread to close";
438 }
439
440 qCDebug(LogReplayLinkLog) << this;
441}
442
444{
445 return _worker && _worker->isConnected();
446}
447
448bool LogReplayLink::_connect()
449{
450 return QMetaObject::invokeMethod(_worker, "connectToLog", Qt::QueuedConnection);
451}
452
454{
455 if (isConnected()) {
456 (void) QMetaObject::invokeMethod(_worker, "disconnectFromLog", Qt::QueuedConnection);
457 }
458}
459
460void LogReplayLink::_onConnected()
461{
462 _disconnectedEmitted = false;
463 emit connected();
464}
465
466void LogReplayLink::_onDisconnected()
467{
468 if (!_disconnectedEmitted.exchange(true)) {
469 emit disconnected();
470 }
471}
472
473void LogReplayLink::_onErrorOccurred(const QString &errorString)
474{
475 qCWarning(LogReplayLinkLog) << "Error:" << errorString;
476 emit communicationError(tr("Log Replay Link Error"), tr("Link: %1, %2.").arg(_logReplayConfig->name(), errorString));
477}
478
479void LogReplayLink::_onDataReceived(const QByteArray &data)
480{
481 emit bytesReceived(this, data);
482}
483
485{
486 return _worker && _worker->isPlaying();
487}
488
490{
491 (void) QMetaObject::invokeMethod(_worker, "play", Qt::QueuedConnection);
492}
493
495{
496 (void) QMetaObject::invokeMethod(_worker, "pause", Qt::QueuedConnection);
497}
498
499void LogReplayLink::setPlaybackSpeed(qreal playbackSpeed)
500{
501 (void) QMetaObject::invokeMethod(_worker, "setPlaybackSpeed", Qt::QueuedConnection, playbackSpeed);
502}
503
504void LogReplayLink::movePlayhead(qreal percentComplete)
505{
506 (void) QMetaObject::invokeMethod(_worker, "movePlayhead", Qt::QueuedConnection, percentComplete);
507}
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
QString errorString
struct __mavlink_message mavlink_message_t
#define QGC_LOGGING_CATEGORY(name, categoryStr)
Interface holding link specific settings.
The link interface defines the interface for all links used to communicate with the ground station ap...
void bytesReceived(LinkInterface *link, const QByteArray &data)
void disconnected()
void communicationError(const QString &title, const QString &error)
void connected()
void currentLogTimeSecs(uint32_t secs)
void dataReceived(const QByteArray &data)
void setPlaybackSpeed(qreal playbackSpeed)
void logFileStats(uint32_t logDurationSecs)
void errorOccurred(const QString &errorString)
bool isPlaying() const
void movePlayhead(qreal percentComplete)
void playbackPaused()
bool isConnected() const
LogReplayWorker(const LogReplayConfiguration *config, QObject *parent=nullptr)
void playbackAtEnd()
void playbackStarted()
void playbackPercentCompleteChanged(qreal percentComplete)
static MAVLinkProtocol * instance()
void suspendLogForReplay(bool suspend)
Suspend/Restart logging during replay.