7#include <QtCore/QFileInfo>
8#include <QtCore/QtEndian>
9#include <QtCore/QThread>
10#include <QtCore/QTimer>
19 qCDebug(LogReplayLinkLog) <<
this;
24 , _logFilename(copy->logFilename())
26 qCDebug(LogReplayLinkLog) <<
this;
29LogReplayConfiguration::~LogReplayConfiguration()
31 qCDebug(LogReplayLinkLog) <<
this;
36 LinkConfiguration::copyFrom(source);
40 setLogFilename(logReplaySource->logFilename());
43void LogReplayConfiguration::loadSettings(QSettings &settings,
const QString &root)
45 settings.beginGroup(root);
47 setLogFilename(settings.value(
"logFilename",
"").toString());
52void LogReplayConfiguration::saveSettings(QSettings &settings,
const QString &root)
const
54 settings.beginGroup(root);
56 settings.setValue(
"logFilename", _logFilename);
61QString LogReplayConfiguration::logFilenameShort()
const
63 return QFileInfo(_logFilename).fileName();
66void LogReplayConfiguration::setLogFilename(
const QString &logFilename)
68 if (logFilename != _logFilename) {
69 _logFilename = logFilename;
78 , _logReplayConfig(config)
80 qCDebug(LogReplayLinkLog) <<
this;
87 qCDebug(LogReplayLinkLog) <<
this;
92 if (!_readTickTimer) {
93 _readTickTimer =
new QTimer(
this);
96 (void) connect(_readTickTimer, &QTimer::timeout,
this, &LogReplayWorker::_readNextLogEntry);
102 qCWarning(LogReplayLinkLog) <<
"Already connected";
106 if (MultiVehicleManager::instance()->activeVehicle()) {
107 emit
errorOccurred(tr(
"You must close all connections prior to replaying a log."));
111 if (!_loadLogFile()) {
125 qCDebug(LogReplayLinkLog) <<
"Already disconnected";
129 qCDebug(LogReplayLinkLog) <<
"Disconnecting from log";
131 if (_readTickTimer) {
132 _readTickTimer->stop();
135 if (_logFile.isOpen()) {
139 _isConnected =
false;
145 return (_readTickTimer && _readTickTimer->isActive());
150 LinkManager::instance()->setConnectionsSuspended(tr(
"Connect not allowed during Flight Data replay."));
153 if (_logFile.atEnd()) {
154 _resetPlaybackToBeginning();
157 _playbackStartTimeMSecs =
static_cast<quint64
>(QDateTime::currentMSecsSinceEpoch());
158 _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
159 _readTickTimer->start(1);
166 LinkManager::instance()->setConnectionsAllowed();
169 _readTickTimer->stop();
176 _playbackSpeed = playbackSpeed;
177 _playbackStartTimeMSecs =
static_cast<quint64
>(QDateTime::currentMSecsSinceEpoch());
178 _playbackStartLogTimeUSecs = _logCurrentTimeUSecs;
179 _readTickTimer->start(1);
186 if (_readTickTimer->isActive()) {
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)) {
200 _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy);
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)) {
211 _logCurrentTimeUSecs = _seekToNextMavlinkMessage(dummy);
212 _signalCurrentLogTimeSecs();
214 newRelativeTimeUSecs =
static_cast<qreal
>(_logCurrentTimeUSecs - _logStartTimeUSecs);
215 percentComplete = ((newRelativeTimeUSecs / _logDurationUSecs) * 100);
219void LogReplayWorker::_resetPlaybackToBeginning()
221 if (_logFile.isOpen()) {
222 if (!_logFile.reset()) {
223 qCWarning(LogReplayLinkLog) <<
"failed to reset log file:" << _logFile.error() << _logFile.errorString();
227 _playbackStartTimeMSecs = 0;
228 _playbackStartLogTimeUSecs = 0;
229 _logCurrentTimeUSecs = _logStartTimeUSecs;
232void LogReplayWorker::_readNextLogEntry()
234 int timeToNextExecutionMSecs = 0;
235 while (timeToNextExecutionMSecs < 3) {
237 bytes.reserve(_logFile.bytesAvailable());
238 const qint64 nextTimeUSecs = _readNextMavlinkMessage(bytes);
240 emit
playbackPercentCompleteChanged((
static_cast<float>(_logCurrentTimeUSecs - _logStartTimeUSecs) /
static_cast<float>(_logDurationUSecs)) * 100);
242 if (_logFile.atEnd()) {
248 _logCurrentTimeUSecs = nextTimeUSecs;
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;
256 _signalCurrentLogTimeSecs();
258 _readTickTimer->start(timeToNextExecutionMSecs);
261void LogReplayWorker::_signalCurrentLogTimeSecs()
266bool LogReplayWorker::_loadLogFile()
268 if (_logFile.isOpen()) {
270 emit
errorOccurred(tr(
"Attempt to load new log while log being played"));
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()));
281 QFileInfo logFileInfo;
282 logFileInfo.setFile(logFilename);
283 _logFileSize = logFileInfo.size();
285 const quint64 startTimeUSecs = _parseTimestamp(_logFile.read(kTimestamp));
286 const quint64 endTimeUSecs = _findLastTimestamp();
287 if (endTimeUSecs <= startTimeUSecs) {
289 emit
errorOccurred(tr(
"The log file '%1' is corrupt or empty.").arg(logFilename));
293 _logEndTimeUSecs = endTimeUSecs;
294 _logStartTimeUSecs = startTimeUSecs;
295 _logDurationUSecs = endTimeUSecs - startTimeUSecs;
296 _logCurrentTimeUSecs = startTimeUSecs;
298 if (!_logFile.reset()) {
299 qCWarning(LogReplayLinkLog) <<
"failed to reset log file:" << _logFile.error() << _logFile.errorString();
302 const quint64 logDurationSecondsTotal = _logDurationUSecs / 1000000;
308quint64 LogReplayWorker::_parseTimestamp(
const QByteArray &bytes)
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);
319quint64 LogReplayWorker::_readNextMavlinkMessage(QByteArray &bytes)
324 while (_logFile.getChar(&nextByte)) {
326 mavlink_status_t status{};
327 const bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &message, &status);
329 if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
332 (void) bytes.append(nextByte);
335 const QByteArray rawTime = _logFile.read(kTimestamp);
336 return _parseTimestamp(rawTime);
345 mavlink_reset_channel_status(_mavlinkChannel);
347 qint64 messageStartPos = -1;
349 while (_logFile.getChar(&nextByte)) {
350 mavlink_status_t status{};
351 const bool messageFound = mavlink_parse_char(_mavlinkChannel, nextByte, &nextMsg, &status);
353 if (status.parse_state == MAVLINK_PARSE_STATE_GOT_STX) {
354 messageStartPos = _logFile.pos() - 1;
357 if (messageFound && (messageStartPos != -1)) {
358 if (!_logFile.seek(messageStartPos - kTimestamp)) {
359 qCWarning(LogReplayLinkLog) <<
"Failed to seek next message:" << _logFile.error() << _logFile.errorString();
363 const QByteArray rawTime = _logFile.read(kTimestamp);
364 return _parseTimestamp(rawTime);
371quint64 LogReplayWorker::_findLastTimestamp()
373 if (!_logFile.reset()) {
374 qCWarning(LogReplayLinkLog) <<
"failed to reset log file:" << _logFile.error() << _logFile.errorString();
377 mavlink_reset_channel_status(_mavlinkChannel);
379 quint64 lastTimestamp = 0;
381 while (_logFile.bytesAvailable() >
static_cast<qint64
>(kTimestamp)) {
382 lastTimestamp = _parseTimestamp(_logFile.read(kTimestamp));
384 bool endOfMessage =
false;
386 while (!endOfMessage && _logFile.getChar(&nextByte)) {
388 mavlink_status_t status{};
389 endOfMessage = mavlink_parse_char(_mavlinkChannel, nextByte, &msg, &status);
393 return lastTimestamp;
402 , _workerThread(new QThread(this))
404 qCDebug(LogReplayLinkLog) <<
this;
406 _workerThread->setObjectName(QStringLiteral(
"LogReplay_%1").arg(_logReplayConfig->name()));
408 _worker->moveToThread(_workerThread);
411 (void) connect(_workerThread, &QThread::finished, _worker, &QObject::deleteLater);
425 _workerThread->start();
431 (void) QMetaObject::invokeMethod(_worker,
"disconnectFromLog", Qt::BlockingQueuedConnection);
435 _workerThread->quit();
436 if (!_workerThread->wait()) {
437 qCWarning(LogReplayLinkLog) <<
"Failed to wait for LogReplay Thread to close";
440 qCDebug(LogReplayLinkLog) <<
this;
448bool LogReplayLink::_connect()
450 return QMetaObject::invokeMethod(_worker,
"connectToLog", Qt::QueuedConnection);
456 (void) QMetaObject::invokeMethod(_worker,
"disconnectFromLog", Qt::QueuedConnection);
460void LogReplayLink::_onConnected()
462 _disconnectedEmitted =
false;
466void LogReplayLink::_onDisconnected()
468 if (!_disconnectedEmitted.exchange(
true)) {
473void LogReplayLink::_onErrorOccurred(
const QString &
errorString)
475 qCWarning(LogReplayLinkLog) <<
"Error:" <<
errorString;
479void LogReplayLink::_onDataReceived(
const QByteArray &data)
491 (void) QMetaObject::invokeMethod(_worker,
"play", Qt::QueuedConnection);
496 (void) QMetaObject::invokeMethod(_worker,
"pause", Qt::QueuedConnection);
501 (void) QMetaObject::invokeMethod(_worker,
"setPlaybackSpeed", Qt::QueuedConnection, playbackSpeed);
506 (void) QMetaObject::invokeMethod(_worker,
"movePlayhead", Qt::QueuedConnection, percentComplete);
std::shared_ptr< LinkConfiguration > SharedLinkConfigurationPtr
struct __mavlink_message mavlink_message_t
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 communicationError(const QString &title, const QString &error)
void disconnect() override
bool isConnected() const override
void playbackPercentCompleteChanged(qreal percentComplete)
void logFileStats(uint32_t logDurationSecs)
void currentLogTimeSecs(uint32_t secs)
void setPlaybackSpeed(qreal playbackSpeed)
void movePlayhead(qreal percentComplete)
LogReplayLink(SharedLinkConfigurationPtr &config, QObject *parent=nullptr)
void currentLogTimeSecs(uint32_t secs)
void dataReceived(const QByteArray &data)
void setPlaybackSpeed(qreal playbackSpeed)
void logFileStats(uint32_t logDurationSecs)
void errorOccurred(const QString &errorString)
void movePlayhead(qreal percentComplete)
LogReplayWorker(const LogReplayConfiguration *config, QObject *parent=nullptr)
void playbackPercentCompleteChanged(qreal percentComplete)
static MAVLinkProtocol * instance()
void suspendLogForReplay(bool suspend)
Suspend/Restart logging during replay.