Commit 0114a391 authored by DonLakeFlyer's avatar DonLakeFlyer

Slightly better Log Replay

parent 1d10b2ad
......@@ -86,7 +86,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
_waitingForDefaultComponent = false;
emit parametersReadyChanged(_parametersReady);
emit missingParametersChanged(_missingParameters);
} else {
} else if (!_logReplay){
refreshAllParameters();
}
}
......@@ -358,7 +358,7 @@ void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString
// Update param cache. The param cache is only used on PX4 Firmware since ArduPilot and Solo have volatile params
// which invalidate the cache. The Solo also streams param updates in flight for things like gimbal values
// which in turn causes a perf problem with all the param cache updates.
if (_vehicle->px4Firmware()) {
if (!_logReplay && _vehicle->px4Firmware()) {
if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
// All reads just finished, update the cache
_writeLocalParamCache(vehicleId, componentId);
......@@ -604,6 +604,10 @@ bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
void ParameterManager::_waitingParamTimeout(void)
{
if (_logReplay) {
return;
}
bool paramsRequested = false;
const int maxBatchSize = 10;
int batchCount = 0;
......
......@@ -7,9 +7,7 @@
*
****************************************************************************/
#ifndef ParameterManager_H
#define ParameterManager_H
#pragma once
#include <QObject>
#include <QMap>
......@@ -25,33 +23,26 @@
#include "QGCMAVLink.h"
#include "Vehicle.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
/// Connects to Parameter Manager to load/update Facts
class ParameterManager : public QObject
{
Q_OBJECT
public:
/// @param uas Uas which this set of facts is associated with
ParameterManager(Vehicle* vehicle);
~ParameterManager();
/// true: Parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
bool parametersReady(void) { return _parametersReady; }
ParameterManager (Vehicle* vehicle);
~ParameterManager ();
/// true: Parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
bool missingParameters(void) { return _missingParameters; }
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) ///< true: Parameters are ready for use
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) ///< true: Parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
double loadProgress(void) const { return _loadProgress; }
bool parametersReady (void) const { return _parametersReady; }
bool missingParameters (void) const { return _missingParameters; }
double loadProgress (void) const { return _loadProgress; }
/// @return Directory of parameter caches
static QDir parameterCacheDir();
......@@ -59,7 +50,6 @@ public:
/// @return Location of parameter cache file
static QString parameterCacheFile(int vehicleId, int componentId);
/// Re-request the full set of parameters from the autopilot
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
......@@ -217,5 +207,3 @@ private:
static const char* _jsonParamNameKey;
static const char* _jsonParamValueKey;
};
#endif
......@@ -367,6 +367,12 @@ void LogReplayLink::_readNextLogEntry(void)
quint64 currentTimeMSecs = (quint64)QDateTime::currentMSecsSinceEpoch();
timeToNextExecutionMSecs = desiredPacedTimeMSecs - currentTimeMSecs;
}
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
if (timeToNextExecutionMSecs == 0 || timeToNextExecutionMSecs > 100) {
qDebug() << timeToNextExecutionMSecs << _logCurrentTimeUSecs;
}
// And schedule the next execution of this function.
_readTickTimer.start(timeToNextExecutionMSecs);
......
......@@ -94,6 +94,7 @@ signals:
void playbackAtEnd(void);
void playbackError(void);
void playbackPercentCompleteChanged(int percentComplete);
void currentLogTimeSecs(int secs);
// Internal signals
void _playOnThread(void);
......
......@@ -15,10 +15,11 @@
#include "QGCQFileDialog.h"
#include "QGCMessageBox.h"
QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(QWidget *parent) :
QWidget(parent),
_replayLink(NULL),
_ui(new Ui::QGCMAVLinkLogPlayer)
QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(QWidget *parent)
: QWidget (parent)
, _replayLink (NULL)
, _lastCurrentTime (0)
, _ui (new Ui::QGCMAVLinkLogPlayer)
{
_ui->setupUi(this);
_ui->horizontalLayout->setAlignment(Qt::AlignTop);
......@@ -92,11 +93,12 @@ void QGCMAVLinkLogPlayer::_selectLogFileForPlayback(void)
SharedLinkConfigurationPointer sharedConfig = linkMgr->addConfiguration(linkConfig);
_replayLink = (LogReplayLink*)qgcApp()->toolbox()->linkManager()->createConnectedLink(sharedConfig);
connect(_replayLink, &LogReplayLink::logFileStats, this, &QGCMAVLinkLogPlayer::_logFileStats);
connect(_replayLink, &LogReplayLink::playbackStarted, this, &QGCMAVLinkLogPlayer::_playbackStarted);
connect(_replayLink, &LogReplayLink::playbackPaused, this, &QGCMAVLinkLogPlayer::_playbackPaused);
connect(_replayLink, &LogReplayLink::playbackPercentCompleteChanged, this, &QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged);
connect(_replayLink, &LogReplayLink::disconnected, this, &QGCMAVLinkLogPlayer::_replayLinkDisconnected);
connect(_replayLink, &LogReplayLink::logFileStats, this, &QGCMAVLinkLogPlayer::_logFileStats);
connect(_replayLink, &LogReplayLink::playbackStarted, this, &QGCMAVLinkLogPlayer::_playbackStarted);
connect(_replayLink, &LogReplayLink::playbackPaused, this, &QGCMAVLinkLogPlayer::_playbackPaused);
connect(_replayLink, &LogReplayLink::playbackPercentCompleteChanged, this, &QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged);
connect(_replayLink, &LogReplayLink::currentLogTimeSecs, this, &QGCMAVLinkLogPlayer::_setCurrentLogTime);
connect(_replayLink, &LogReplayLink::disconnected, this, &QGCMAVLinkLogPlayer::_replayLinkDisconnected);
_ui->positionSlider->setValue(0);
#if 0
......@@ -133,7 +135,7 @@ void QGCMAVLinkLogPlayer::_logFileStats(bool logTimestamped, ///< tru
_logDurationSeconds = logDurationSeconds;
_ui->logStatsLabel->setText(_secondsToHMS(logDurationSeconds));
_ui->logLengthTime->setText(_secondsToHMS(logDurationSeconds));
}
/// Signalled from LogReplayLink when replay starts
......@@ -208,3 +210,11 @@ void QGCMAVLinkLogPlayer::_replayLinkDisconnected(void)
_enablePlaybackControls(false);
_replayLink = NULL;
}
void QGCMAVLinkLogPlayer::_setCurrentLogTime(int secs)
{
if (secs != _lastCurrentTime) {
_lastCurrentTime = secs;
_ui->logCurrentTime->setText(_secondsToHMS(secs));
}
}
......@@ -42,6 +42,7 @@ private slots:
void _playbackPercentCompleteChanged(int percentComplete);
void _playbackError(void);
void _replayLinkDisconnected(void);
void _setCurrentLogTime(int secs);
private:
void _finishPlayback(void);
......@@ -50,6 +51,7 @@ private:
LogReplayLink* _replayLink;
int _logDurationSeconds;
int _lastCurrentTime;
Ui::QGCMAVLinkLogPlayer* _ui;
};
......
......@@ -27,7 +27,7 @@
<number>0</number>
</property>
<item>
<widget class="QLabel" name="logStatsLabel">
<widget class="QLabel" name="logCurrentTime">
<property name="text">
<string/>
</property>
......@@ -89,6 +89,13 @@
</property>
</widget>
</item>
<item>
<widget class="QLabel" name="logLengthTime">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="selectFileButton">
<property name="toolTip">
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment