Browse Source

Slightly better Log Replay

QGC4.4
DonLakeFlyer 7 years ago
parent
commit
0114a391b7
  1. 8
      src/FactSystem/ParameterManager.cc
  2. 24
      src/FactSystem/ParameterManager.h
  3. 6
      src/comm/LogReplayLink.cc
  4. 1
      src/comm/LogReplayLink.h
  5. 20
      src/ui/QGCMAVLinkLogPlayer.cc
  6. 2
      src/ui/QGCMAVLinkLogPlayer.h
  7. 9
      src/ui/QGCMAVLinkLogPlayer.ui

8
src/FactSystem/ParameterManager.cc

@ -86,7 +86,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle)
_waitingForDefaultComponent = false; _waitingForDefaultComponent = false;
emit parametersReadyChanged(_parametersReady); emit parametersReadyChanged(_parametersReady);
emit missingParametersChanged(_missingParameters); emit missingParametersChanged(_missingParameters);
} else { } else if (!_logReplay){
refreshAllParameters(); 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 // 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 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. // 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) { if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) {
// All reads just finished, update the cache // All reads just finished, update the cache
_writeLocalParamCache(vehicleId, componentId); _writeLocalParamCache(vehicleId, componentId);
@ -604,6 +604,10 @@ bool ParameterManager::_fillIndexBatchQueue(bool waitingParamTimeout)
void ParameterManager::_waitingParamTimeout(void) void ParameterManager::_waitingParamTimeout(void)
{ {
if (_logReplay) {
return;
}
bool paramsRequested = false; bool paramsRequested = false;
const int maxBatchSize = 10; const int maxBatchSize = 10;
int batchCount = 0; int batchCount = 0;

24
src/FactSystem/ParameterManager.h

@ -7,9 +7,7 @@
* *
****************************************************************************/ ****************************************************************************/
#pragma once
#ifndef ParameterManager_H
#define ParameterManager_H
#include <QObject> #include <QObject>
#include <QMap> #include <QMap>
@ -25,14 +23,10 @@
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "Vehicle.h" #include "Vehicle.h"
/// @file
/// @author Don Gagne <don@thegagnes.com>
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose1Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerVerbose2Log)
Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog) Q_DECLARE_LOGGING_CATEGORY(ParameterManagerDebugCacheFailureLog)
/// Connects to Parameter Manager to load/update Facts
class ParameterManager : public QObject class ParameterManager : public QObject
{ {
Q_OBJECT Q_OBJECT
@ -42,15 +36,12 @@ public:
ParameterManager (Vehicle* vehicle); ParameterManager (Vehicle* vehicle);
~ParameterManager (); ~ParameterManager ();
/// true: Parameters are ready for use Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) ///< true: Parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) ///< true: Parameters are missing from firmware response, false: all parameters received from firmware
bool parametersReady(void) { return _parametersReady; }
/// 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(double loadProgress READ loadProgress NOTIFY loadProgressChanged) Q_PROPERTY(double loadProgress READ loadProgress NOTIFY loadProgressChanged)
bool parametersReady (void) const { return _parametersReady; }
bool missingParameters (void) const { return _missingParameters; }
double loadProgress (void) const { return _loadProgress; } double loadProgress (void) const { return _loadProgress; }
/// @return Directory of parameter caches /// @return Directory of parameter caches
@ -59,7 +50,6 @@ public:
/// @return Location of parameter cache file /// @return Location of parameter cache file
static QString parameterCacheFile(int vehicleId, int componentId); static QString parameterCacheFile(int vehicleId, int componentId);
/// Re-request the full set of parameters from the autopilot /// Re-request the full set of parameters from the autopilot
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL); void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
@ -217,5 +207,3 @@ private:
static const char* _jsonParamNameKey; static const char* _jsonParamNameKey;
static const char* _jsonParamValueKey; static const char* _jsonParamValueKey;
}; };
#endif

6
src/comm/LogReplayLink.cc

@ -368,6 +368,12 @@ void LogReplayLink::_readNextLogEntry(void)
timeToNextExecutionMSecs = desiredPacedTimeMSecs - currentTimeMSecs; timeToNextExecutionMSecs = desiredPacedTimeMSecs - currentTimeMSecs;
} }
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
if (timeToNextExecutionMSecs == 0 || timeToNextExecutionMSecs > 100) {
qDebug() << timeToNextExecutionMSecs << _logCurrentTimeUSecs;
}
// And schedule the next execution of this function. // And schedule the next execution of this function.
_readTickTimer.start(timeToNextExecutionMSecs); _readTickTimer.start(timeToNextExecutionMSecs);
} }

1
src/comm/LogReplayLink.h

@ -94,6 +94,7 @@ signals:
void playbackAtEnd(void); void playbackAtEnd(void);
void playbackError(void); void playbackError(void);
void playbackPercentCompleteChanged(int percentComplete); void playbackPercentCompleteChanged(int percentComplete);
void currentLogTimeSecs(int secs);
// Internal signals // Internal signals
void _playOnThread(void); void _playOnThread(void);

20
src/ui/QGCMAVLinkLogPlayer.cc

@ -15,10 +15,11 @@
#include "QGCQFileDialog.h" #include "QGCQFileDialog.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(QWidget *parent) : QGCMAVLinkLogPlayer::QGCMAVLinkLogPlayer(QWidget *parent)
QWidget(parent), : QWidget (parent)
_replayLink(NULL), , _replayLink (NULL)
_ui(new Ui::QGCMAVLinkLogPlayer) , _lastCurrentTime (0)
, _ui (new Ui::QGCMAVLinkLogPlayer)
{ {
_ui->setupUi(this); _ui->setupUi(this);
_ui->horizontalLayout->setAlignment(Qt::AlignTop); _ui->horizontalLayout->setAlignment(Qt::AlignTop);
@ -96,6 +97,7 @@ void QGCMAVLinkLogPlayer::_selectLogFileForPlayback(void)
connect(_replayLink, &LogReplayLink::playbackStarted, this, &QGCMAVLinkLogPlayer::_playbackStarted); connect(_replayLink, &LogReplayLink::playbackStarted, this, &QGCMAVLinkLogPlayer::_playbackStarted);
connect(_replayLink, &LogReplayLink::playbackPaused, this, &QGCMAVLinkLogPlayer::_playbackPaused); connect(_replayLink, &LogReplayLink::playbackPaused, this, &QGCMAVLinkLogPlayer::_playbackPaused);
connect(_replayLink, &LogReplayLink::playbackPercentCompleteChanged, this, &QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged); connect(_replayLink, &LogReplayLink::playbackPercentCompleteChanged, this, &QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged);
connect(_replayLink, &LogReplayLink::currentLogTimeSecs, this, &QGCMAVLinkLogPlayer::_setCurrentLogTime);
connect(_replayLink, &LogReplayLink::disconnected, this, &QGCMAVLinkLogPlayer::_replayLinkDisconnected); connect(_replayLink, &LogReplayLink::disconnected, this, &QGCMAVLinkLogPlayer::_replayLinkDisconnected);
_ui->positionSlider->setValue(0); _ui->positionSlider->setValue(0);
@ -133,7 +135,7 @@ void QGCMAVLinkLogPlayer::_logFileStats(bool logTimestamped, ///< tru
_logDurationSeconds = logDurationSeconds; _logDurationSeconds = logDurationSeconds;
_ui->logStatsLabel->setText(_secondsToHMS(logDurationSeconds)); _ui->logLengthTime->setText(_secondsToHMS(logDurationSeconds));
} }
/// Signalled from LogReplayLink when replay starts /// Signalled from LogReplayLink when replay starts
@ -208,3 +210,11 @@ void QGCMAVLinkLogPlayer::_replayLinkDisconnected(void)
_enablePlaybackControls(false); _enablePlaybackControls(false);
_replayLink = NULL; _replayLink = NULL;
} }
void QGCMAVLinkLogPlayer::_setCurrentLogTime(int secs)
{
if (secs != _lastCurrentTime) {
_lastCurrentTime = secs;
_ui->logCurrentTime->setText(_secondsToHMS(secs));
}
}

2
src/ui/QGCMAVLinkLogPlayer.h

@ -42,6 +42,7 @@ private slots:
void _playbackPercentCompleteChanged(int percentComplete); void _playbackPercentCompleteChanged(int percentComplete);
void _playbackError(void); void _playbackError(void);
void _replayLinkDisconnected(void); void _replayLinkDisconnected(void);
void _setCurrentLogTime(int secs);
private: private:
void _finishPlayback(void); void _finishPlayback(void);
@ -50,6 +51,7 @@ private:
LogReplayLink* _replayLink; LogReplayLink* _replayLink;
int _logDurationSeconds; int _logDurationSeconds;
int _lastCurrentTime;
Ui::QGCMAVLinkLogPlayer* _ui; Ui::QGCMAVLinkLogPlayer* _ui;
}; };

9
src/ui/QGCMAVLinkLogPlayer.ui

@ -27,7 +27,7 @@
<number>0</number> <number>0</number>
</property> </property>
<item> <item>
<widget class="QLabel" name="logStatsLabel"> <widget class="QLabel" name="logCurrentTime">
<property name="text"> <property name="text">
<string/> <string/>
</property> </property>
@ -90,6 +90,13 @@
</widget> </widget>
</item> </item>
<item> <item>
<widget class="QLabel" name="logLengthTime">
<property name="text">
<string/>
</property>
</widget>
</item>
<item>
<widget class="QPushButton" name="selectFileButton"> <widget class="QPushButton" name="selectFileButton">
<property name="toolTip"> <property name="toolTip">
<string>Select the Flight Data to replay</string> <string>Select the Flight Data to replay</string>

Loading…
Cancel
Save