Unverified Commit 75770477 authored by Don Gagne's avatar Don Gagne Committed by GitHub

Merge pull request #7502 from DonLakeFlyer/LogReplay

Support Log Replay in new Qml only system
parents 83c7c3f2 fc8fd6a7
......@@ -604,6 +604,7 @@ HEADERS += \
src/comm/LinkConfiguration.h \
src/comm/LinkInterface.h \
src/comm/LinkManager.h \
src/comm/LogReplayLink.h \
src/comm/MAVLinkProtocol.h \
src/comm/ProtocolInterface.h \
src/comm/QGCMAVLink.h \
......@@ -664,7 +665,6 @@ HEADERS += \
src/GPS/vehicle_gps_position.h \
src/Joystick/JoystickSDL.h \
src/RunGuard.h \
src/comm/LogReplayLink.h \
src/comm/QGCHilLink.h \
src/comm/QGCJSBSimLink.h \
src/comm/QGCXPlaneLink.h \
......@@ -780,6 +780,7 @@ SOURCES += \
src/comm/LinkConfiguration.cc \
src/comm/LinkInterface.cc \
src/comm/LinkManager.cc \
src/comm/LogReplayLink.cc \
src/comm/MAVLinkProtocol.cc \
src/comm/QGCMAVLink.cc \
src/comm/TCPLink.cc \
......@@ -822,7 +823,6 @@ SOURCES += \
src/GPS/RTCM/RTCMMavlink.cc \
src/Joystick/JoystickSDL.cc \
src/RunGuard.cc \
src/comm/LogReplayLink.cc \
src/comm/QGCJSBSimLink.cc \
src/comm/QGCXPlaneLink.cc \
src/uas/FileManager.cc \
......
......@@ -77,6 +77,7 @@
<file alias="QGroundControl/Controls/GeoFenceMapVisuals.qml">src/PlanView/GeoFenceMapVisuals.qml</file>
<file alias="QGroundControl/Controls/IndicatorButton.qml">src/QmlControls/IndicatorButton.qml</file>
<file alias="QGroundControl/Controls/JoystickThumbPad.qml">src/QmlControls/JoystickThumbPad.qml</file>
<file alias="QGroundControl/Controls/LogReplayStatusBar.qml">src/QmlControls/LogReplayStatusBar.qml</file>
<file alias="QGroundControl/Controls/MAVLinkMessageButton.qml">src/QmlControls/MAVLinkMessageButton.qml</file>
<file alias="QGroundControl/Controls/MissionCommandDialog.qml">src/QmlControls/MissionCommandDialog.qml</file>
<file alias="QGroundControl/Controls/MissionItemEditor.qml">src/PlanView/MissionItemEditor.qml</file>
......
......@@ -312,7 +312,10 @@ Item {
Item {
id: _mapAndVideo
anchors.fill: parent
anchors.left: parent.left
anchors.right: parent.right
anchors.top: parent.top
anchors.bottom: logReplayStatusBar.top
//-- Map View
Item {
......@@ -737,6 +740,14 @@ Item {
}
}
LogReplayStatusBar {
id: logReplayStatusBar
anchors.left: parent.left
anchors.right: parent.right
anchors.bottom: parent.bottom
visible: QGroundControl.settingsManager.flyViewSettings.showLogReplayStatusBar.rawValue &&_flightMapContainer.state === "fullMode"
}
//-- Airspace Indicator
Rectangle {
id: airspaceIndicator
......
......@@ -26,7 +26,6 @@ import QGroundControl.Vehicle 1.0
FlightMap {
id: flightMap
anchors.fill: parent
mapName: _mapName
allowGCSLocationCenter: !userPanned
allowVehicleLocationCenter: !_keepVehicleCentered
......
......@@ -100,6 +100,7 @@
#include "MavlinkConsoleController.h"
#include "MAVLinkInspectorController.h"
#include "GeoTagController.h"
#include "LogReplayLink.h"
#ifndef __mobile__
#include "FirmwareUpgradeController.h"
......@@ -485,6 +486,9 @@ void QGCApplication::_initCommon()
qmlRegisterUncreatableType<QmlObjectListModel> ("QGroundControl", 1, 0, "QmlObjectListModel", kRefOnly);
qmlRegisterUncreatableType<MissionCommandTree> ("QGroundControl", 1, 0, "MissionCommandTree", kRefOnly);
qmlRegisterUncreatableType<CameraCalc> ("QGroundControl", 1, 0, "CameraCalc", kRefOnly);
qmlRegisterUncreatableType<LogReplayLink> ("QGroundControl", 1, 0, "LogReplayLink", kRefOnly);
qmlRegisterType<LogReplayLinkController> ("QGroundControl", 1, 0, "LogReplayLinkController");
qmlRegisterUncreatableType<AutoPilotPlugin> ("QGroundControl.AutoPilotPlugin", 1, 0, "AutoPilotPlugin", kRefOnly);
qmlRegisterUncreatableType<VehicleComponent> ("QGroundControl.AutoPilotPlugin", 1, 0, "VehicleComponent", kRefOnly);
......
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Layouts 1.11
import QtQuick.Dialogs 1.2
import QGroundControl 1.0
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
Rectangle {
height: visible ? (rowLayout.height + (_margins * 2)) : 0
color: qgcPal.window
property real _margins: ScreenTools.defaultFontPixelHeight / 4
property var _logReplayLink: null
function pickLogFile() {
if (mainWindow.activeVehicle) {
mainWindow.showMessageDialog(qsTr("Log Replay"), qsTr("You must close all connections prior to replaying a log."), StandardButton.Ok)
return
}
filePicker.openForLoad()
}
QGCPalette { id: qgcPal }
QGCFileDialog {
id: filePicker
title: qsTr("Select Telemetery Log")
nameFilters: [qsTr("Telemetry Logs (*.%1)").arg(QGroundControl.settingsManager.appSettings.telemetryFileExtension), qsTr("All Files (*)")]
selectExisting: true
folder: QGroundControl.settingsManager.appSettings.telemetrySavePath
onAcceptedForLoad: {
controller.link = QGroundControl.linkManager.startLogReplay(file)
close()
}
}
LogReplayLinkController {
id: controller
onPercentCompleteChanged: slider.updatePercentComplete(percentComplete)
}
RowLayout {
id: rowLayout
anchors.margins: _margins
anchors.top: parent.top
anchors.left: parent.left
anchors.right: parent.right
QGCButton {
text: controller.isPlaying ? qsTr("Pause") : qsTr("Play")
enabled: controller.link
onClicked: controller.isPlaying = !controller.isPlaying
}
QGCLabel { text: controller.playheadTime }
Slider {
id: slider
Layout.fillWidth: true
minimumValue: 0
maximumValue: 100
enabled: controller.link
property bool manualUpdate: false
function updatePercentComplete(percentComplete) {
manualUpdate = true
value = percentComplete
manualUpdate = false
}
onValueChanged: {
if (!manualUpdate) {
controller.percentComplete = value
}
}
}
QGCLabel { text: controller.totalTime }
QGCButton {
text: qsTr("Load Telemetry Log")
onClicked: pickLogFile()
visible: !controller.link
}
}
}
......@@ -20,6 +20,7 @@ GeoFenceMapVisuals 1.0 GeoFenceMapVisuals.qml
HackFileDialog 1.0 HackFileDialog.qml
IndicatorButton 1.0 IndicatorButton.qml
JoystickThumbPad 1.0 JoystickThumbPad.qml
LogReplayStatusBar 1.0 LogReplayStatusBar.qml
MAVLinkMessageButton 1.0 MAVLinkMessageButton.qml
MissionCommandDialog 1.0 MissionCommandDialog.qml
MissionItemEditor 1.0 MissionItemEditor.qml
......
......@@ -12,5 +12,11 @@
"type": "double",
"units": "m",
"defaultValue": 121.92
},
{
"name": "showLogReplayStatusBar",
"shortDescription": "Show/Hide Log Replay status bar",
"type": "bool",
"defaultValue": false
}
]
......@@ -19,3 +19,4 @@ DECLARE_SETTINGGROUP(FlyView, "FlyView")
DECLARE_SETTINGSFACT(FlyViewSettings, guidedMinimumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, guidedMaximumAltitude)
DECLARE_SETTINGSFACT(FlyViewSettings, showLogReplayStatusBar)
......@@ -16,7 +16,10 @@ class FlyViewSettings : public SettingsGroup
Q_OBJECT
public:
FlyViewSettings(QObject* parent = nullptr);
DEFINE_SETTING_NAME_GROUP()
DEFINE_SETTINGFACT(guidedMinimumAltitude)
DEFINE_SETTINGFACT(guidedMaximumAltitude)
DEFINE_SETTINGFACT(showLogReplayStatusBar)
};
......@@ -40,11 +40,14 @@ void SubtitleWriter::setVideoReceiver(VideoReceiver* videoReceiver)
return;
}
_videoReceiver = videoReceiver;
#if defined(QGC_GST_STREAMING)
// Only start writing subtitles once the recording pipeline actually starts
connect(_videoReceiver, &VideoReceiver::gotFirstRecordingKeyFrame, this, &SubtitleWriter::_startCapturingTelemetry);
// Captures recordingChanged() signals to stop writing subtitles
connect(_videoReceiver, &VideoReceiver::recordingChanged, this, &SubtitleWriter::_onVideoRecordingChanged);
#endif
// Timer for telemetry capture and writing to file
connect(&_timer, &QTimer::timeout, this, &SubtitleWriter::_captureTelemetry);
......@@ -52,12 +55,14 @@ void SubtitleWriter::setVideoReceiver(VideoReceiver* videoReceiver)
void SubtitleWriter::_onVideoRecordingChanged()
{
#if defined(QGC_GST_STREAMING)
// Stop capturing data if recording stopped
if(!_videoReceiver->recording()) {
qCDebug(SubtitleWriterLog) << "Stopping writing";
_timer.stop();
_file.close();
}
#endif
}
void SubtitleWriter::_startCapturingTelemetry()
......
......@@ -20,9 +20,7 @@
#endif
#include "UDPLink.h"
#include "TCPLink.h"
#if !defined(__mobile__)
#include "LogReplayLink.h"
#endif
#ifdef QGC_ENABLE_BLUETOOTH
#include "BluetoothLink.h"
#endif
......@@ -98,11 +96,9 @@ LinkConfiguration* LinkConfiguration::createSettings(int type, const QString& na
config = new BluetoothConfiguration(name);
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay:
config = new LogReplayLinkConfiguration(name);
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
config = new MockConfiguration(name);
......@@ -136,11 +132,9 @@ LinkConfiguration* LinkConfiguration::duplicateSettings(LinkConfiguration* sourc
dupe = new BluetoothConfiguration(dynamic_cast<BluetoothConfiguration*>(source));
break;
#endif
#ifndef __mobile__
case TypeLogReplay:
dupe = new LogReplayLinkConfiguration(dynamic_cast<LogReplayLinkConfiguration*>(source));
break;
#endif
#ifdef QT_DEBUG
case TypeMock:
dupe = new MockConfiguration(dynamic_cast<MockConfiguration*>(source));
......
......@@ -57,9 +57,7 @@ public:
#ifdef QT_DEBUG
TypeMock, ///< Mock Link for Unitesting
#endif
#ifndef __mobile__
TypeLogReplay,
#endif
TypeLast // Last type value (type >= TypeLast == invalid)
};
Q_ENUM(LinkType)
......
......@@ -21,6 +21,7 @@
#include "UDPLink.h"
#include "TCPLink.h"
#include "SettingsManager.h"
#include "LogReplayLink.h"
#ifdef QGC_ENABLE_BLUETOOTH
#include "BluetoothLink.h"
#endif
......@@ -139,11 +140,9 @@ LinkInterface* LinkManager::createConnectedLink(SharedLinkConfigurationPointer&
pLink = new BluetoothLink(config);
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay:
pLink = new LogReplayLink(config);
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
pLink = new MockLink(config);
......@@ -393,11 +392,9 @@ void LinkManager::loadLinkConfigurationList()
pLink = dynamic_cast<LinkConfiguration*>(new BluetoothConfiguration(name));
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay:
pLink = dynamic_cast<LinkConfiguration*>(new LogReplayLinkConfiguration(name));
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
pLink = dynamic_cast<LinkConfiguration*>(new MockConfiguration(name));
......@@ -847,7 +844,6 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
}
break;
#endif
#ifndef __mobile__
case LinkConfiguration::TypeLogReplay: {
LogReplayLinkConfiguration* tconfig = dynamic_cast<LogReplayLinkConfiguration*>(config);
if(tconfig) {
......@@ -855,7 +851,6 @@ void LinkManager::_fixUnnamed(LinkConfiguration* config)
}
}
break;
#endif
#ifdef QT_DEBUG
case LinkConfiguration::TypeMock:
config->setName(QString("Mock Link"));
......@@ -1015,3 +1010,13 @@ void LinkManager::_freeMavlinkChannel(int channel)
void LinkManager::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t message) {
link->startMavlinkMessagesTimer(message.sysid);
}
LogReplayLink* LinkManager::startLogReplay(const QString& logFile)
{
LogReplayLinkConfiguration* linkConfig = new LogReplayLinkConfiguration(tr("Log Replay"));
linkConfig->setLogFilename(logFile);
linkConfig->setName(linkConfig->logFilenameShort());
SharedLinkConfigurationPointer sharedConfig = addConfiguration(linkConfig);
return qobject_cast<LogReplayLink*>(createConnectedLink(sharedConfig));
}
......@@ -43,6 +43,7 @@ Q_DECLARE_LOGGING_CATEGORY(LinkManagerVerboseLog)
class QGCApplication;
class UDPConfiguration;
class AutoConnectSettings;
class LogReplayLink;
/// Manage communication links
///
......@@ -129,6 +130,8 @@ public:
// Called to signal app shutdown. Disconnects all links while turning off auto-connect.
Q_INVOKABLE void shutdown(void);
Q_INVOKABLE LogReplayLink* startLogReplay(const QString& logFile);
#ifdef QT_DEBUG
// Only used by unit test tp restart after a shutdown
void restart(void) { setConnectionsAllowed(); }
......
......@@ -19,13 +19,13 @@
const char* LogReplayLinkConfiguration::_logFilenameKey = "logFilename";
LogReplayLinkConfiguration::LogReplayLinkConfiguration(const QString& name)
: LinkConfiguration(name)
: LinkConfiguration(name)
{
}
LogReplayLinkConfiguration::LogReplayLinkConfiguration(LogReplayLinkConfiguration* copy)
: LinkConfiguration(copy)
: LinkConfiguration(copy)
{
_logFilename = copy->logFilename();
}
......@@ -448,7 +448,7 @@ void LogReplayLink::_resetPlaybackToBeginning(void)
_logCurrentTimeUSecs = _logStartTimeUSecs;
}
void LogReplayLink::movePlayhead(int percentComplete)
void LogReplayLink::movePlayhead(qreal percentComplete)
{
if (isPlaying()) {
_pauseOnThread();
......@@ -459,17 +459,19 @@ void LogReplayLink::movePlayhead(int percentComplete)
}
}
if (percentComplete < 0 || percentComplete > 100) {
qWarning() << "Bad percentage value" << percentComplete;
return;
if (percentComplete < 0) {
percentComplete = 0;
}
if (percentComplete > 100) {
percentComplete = 100;
}
float floatPercentComplete = (float)percentComplete / 100.0f;
qreal percentCompleteMult = percentComplete / 100.0;
if (_logTimestamped) {
// But if we have a timestamped MAVLink log, then actually aim to hit that percentage in terms of
// time through the file.
qint64 newFilePos = (qint64)(floatPercentComplete * (float)_logFile.size());
qint64 newFilePos = (qint64)(percentCompleteMult * (qreal)_logFile.size());
// Now seek to the appropriate position, failing gracefully if we can't.
if (!_logFile.seek(newFilePos)) {
......@@ -482,13 +484,13 @@ void LogReplayLink::movePlayhead(int percentComplete)
_logCurrentTimeUSecs = _seekToNextMavlinkMessage(&dummy);
// Now calculate the current file location based on time.
float newRelativeTimeUSecs = (float)(_logCurrentTimeUSecs - _logStartTimeUSecs);
qreal newRelativeTimeUSecs = (qreal)(_logCurrentTimeUSecs - _logStartTimeUSecs);
// Calculate the effective baud rate of the file in bytes/s.
float baudRate = _logFile.size() / (float)_logDurationUSecs / 1e6;
qreal baudRate = _logFile.size() / (qreal)_logDurationUSecs / 1e6;
// And the desired time is:
float desiredTimeUSecs = floatPercentComplete * _logDurationUSecs;
qreal desiredTimeUSecs = percentCompleteMult * _logDurationUSecs;
// And now jump the necessary number of bytes in the proper direction
qint64 offset = (newRelativeTimeUSecs - desiredTimeUSecs) * baudRate;
......@@ -503,13 +505,13 @@ void LogReplayLink::movePlayhead(int percentComplete)
_signalCurrentLogTimeSecs();
// Now update the UI with our actual final position.
newRelativeTimeUSecs = (float)(_logCurrentTimeUSecs - _logStartTimeUSecs);
newRelativeTimeUSecs = (qreal)(_logCurrentTimeUSecs - _logStartTimeUSecs);
percentComplete = (newRelativeTimeUSecs / _logDurationUSecs) * 100;
emit playbackPercentCompleteChanged(percentComplete);
} else {
// If we're working with a non-timestamped file, we just jump to that percentage of the file,
// align to the next MAVLink message and roll with it. No reason to do anything more complicated.
qint64 newFilePos = (qint64)(floatPercentComplete * (float)_logFile.size());
qint64 newFilePos = (qint64)(percentCompleteMult * (qreal)_logFile.size());
// Now seek to the appropriate position, failing gracefully if we can't.
if (!_logFile.seek(newFilePos)) {
......@@ -560,15 +562,117 @@ void LogReplayLink::_finishPlayback(void)
emit playbackAtEnd();
}
/// @brief Called when an error occurs during playback to reset playback system state.
void LogReplayLink::_playbackError(void)
void LogReplayLink::_signalCurrentLogTimeSecs(void)
{
_pause();
_logFile.close();
emit playbackError();
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
}
void LogReplayLink::_signalCurrentLogTimeSecs(void)
LogReplayLinkController::LogReplayLinkController(void)
: _link (nullptr)
, _isPlaying (false)
, _percentComplete (0)
, _playheadSecs (0)
{
emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000);
}
void LogReplayLinkController::setLink(LogReplayLink* link)
{
if (_link) {
disconnect(_link);
_isPlaying = false;
_percentComplete = 0;
_playheadTime.clear();
_totalTime.clear();
_link = nullptr;
emit isPlayingChanged(false);
emit percentCompleteChanged(0);
emit playheadTimeChanged(QString());
emit totalTimeChanged(QString());
emit linkChanged(nullptr);
}
if (link) {
_link = link;
connect(_link, &LogReplayLink::logFileStats, this, &LogReplayLinkController::_logFileStats);
connect(_link, &LogReplayLink::playbackStarted, this, &LogReplayLinkController::_playbackStarted);
connect(_link, &LogReplayLink::playbackPaused, this, &LogReplayLinkController::_playbackPaused);
connect(_link, &LogReplayLink::playbackPercentCompleteChanged, this, &LogReplayLinkController::_playbackPercentCompleteChanged);
connect(_link, &LogReplayLink::currentLogTimeSecs, this, &LogReplayLinkController::_currentLogTimeSecs);
connect(_link, &LogReplayLink::disconnected, this, &LogReplayLinkController::_linkDisconnected);
emit linkChanged(_link);
}
}
void LogReplayLinkController::setIsPlaying(bool isPlaying)
{
if (isPlaying) {
_link->play();
} else {
_link->pause();
}
}
void LogReplayLinkController::setPercentComplete(qreal percentComplete)
{
_link->movePlayhead(percentComplete);
}
void LogReplayLinkController::_logFileStats(bool logTimestamped, int logDurationSecs, int binaryBaudRate)
{
Q_UNUSED(logTimestamped);
Q_UNUSED(binaryBaudRate);
_totalTime = _secondsToHMS(logDurationSecs);
emit totalTimeChanged(_totalTime);
}
void LogReplayLinkController::_playbackStarted(void)
{
_isPlaying = true;
emit isPlayingChanged(true);
}
void LogReplayLinkController::_playbackPaused(void)
{
_isPlaying = false;
emit isPlayingChanged(true);
}
void LogReplayLinkController::_playbackAtEnd(void)
{
_isPlaying = false;
emit isPlayingChanged(true);
}
void LogReplayLinkController::_playbackPercentCompleteChanged(qreal percentComplete)
{
_percentComplete = percentComplete;
emit percentCompleteChanged(_percentComplete);
}
void LogReplayLinkController::_currentLogTimeSecs(int secs)
{
if (_playheadSecs != secs) {
_playheadSecs = secs;
_playheadTime = _secondsToHMS(secs);
emit playheadTimeChanged(_playheadTime);
}
}
void LogReplayLinkController::_linkDisconnected(void)
{
setLink(nullptr);
}
QString LogReplayLinkController::_secondsToHMS(int seconds)
{
int secondsPart = seconds;
int minutesPart = secondsPart / 60;
int hoursPart = minutesPart / 60;
secondsPart -= 60 * minutesPart;
minutesPart -= 60 * hoursPart;
return tr("%1h:%2m:%3s").arg(hoursPart, 2).arg(minutesPart, 2).arg(secondsPart, 2);
}
......@@ -7,11 +7,9 @@
*
****************************************************************************/
#pragma once
#include "LinkInterface.h"
#include "LinkConfiguration.h"
#include "LinkManager.h"
#include "MAVLinkProtocol.h"
#include <QTimer>
......@@ -22,7 +20,6 @@ class LogReplayLinkConfiguration : public LinkConfiguration
Q_OBJECT
public:
Q_PROPERTY(QString fileName READ logFilename WRITE setLogFilename NOTIFY fileNameChanged)
LogReplayLinkConfiguration(const QString& name);
......@@ -41,6 +38,7 @@ public:
void updateSettings ();
QString settingsURL () { return "LogReplaySettings.qml"; }
QString settingsTitle () { return tr("Log Replay Link Settings"); }
signals:
void fileNameChanged();
......@@ -66,7 +64,7 @@ public:
void pause(void) { emit _pauseOnThread(); }
/// Move the playhead to the specified percent complete
void movePlayhead(int percentComplete);
void movePlayhead(qreal percentComplete);
/// Sets the acceleration factor: -100: 0.01X, 0: 1.0X, 100: 100.0X
void setAccelerationFactor(int factor) { emit _setAccelerationFactorOnThread(factor); }
......@@ -92,8 +90,7 @@ signals:
void playbackStarted(void);
void playbackPaused(void);
void playbackAtEnd(void);
void playbackError(void);
void playbackPercentCompleteChanged(int percentComplete);
void playbackPercentCompleteChanged(qreal percentComplete);
void currentLogTimeSecs(int secs);
// Internal signals
......@@ -118,7 +115,6 @@ private:
quint64 _readNextMavlinkMessage(QByteArray& bytes);
bool _loadLogFile(void);
void _finishPlayback(void);
void _playbackError(void);
void _resetPlaybackToBeginning(void);
void _signalCurrentLogTimeSecs(void);
......@@ -156,3 +152,51 @@ private:
static const int cbTimestamp = sizeof(quint64);
};
class LogReplayLinkController : public QObject
{
Q_OBJECT
public:
Q_PROPERTY(LogReplayLink* link READ link WRITE setLink NOTIFY linkChanged)
Q_PROPERTY(bool isPlaying READ isPlaying WRITE setIsPlaying NOTIFY isPlayingChanged)
Q_PROPERTY(qreal percentComplete READ percentComplete WRITE setPercentComplete NOTIFY percentCompleteChanged)
Q_PROPERTY(QString totalTime MEMBER _totalTime NOTIFY totalTimeChanged)
Q_PROPERTY(QString playheadTime MEMBER _playheadTime NOTIFY playheadTimeChanged)
LogReplayLinkController(void);
LogReplayLink* link (void) { return _link; }
bool isPlaying (void) { return _isPlaying; }
qreal percentComplete (void) { return _percentComplete; }
void setLink (LogReplayLink* link);
void setIsPlaying (bool isPlaying);
void setPercentComplete (qreal percentComplete);
signals:
void linkChanged (LogReplayLink* link);
void isPlayingChanged (bool isPlaying);
void percentCompleteChanged (qreal percentComplete);
void playheadTimeChanged (QString playheadTime);
void totalTimeChanged (QString totalTime);
private slots:
void _logFileStats (bool logTimestamped, int logDurationSecs, int binaryBaudRate);
void _playbackStarted (void);
void _playbackPaused (void);
void _playbackAtEnd (void);
void _playbackPercentCompleteChanged (qreal percentComplete);
void _currentLogTimeSecs (int secs);
void _linkDisconnected (void);
private:
QString _secondsToHMS(int seconds);
LogReplayLink* _link;
bool _isPlaying;
qreal _percentComplete;
int _playheadSecs;
QString _playheadTime;
QString _totalTime;
};
......@@ -247,7 +247,6 @@ Rectangle {
}
}
FactCheckBox {
text: qsTr("Mute all audio output")
fact: _audioMuted
......@@ -430,13 +429,21 @@ Rectangle {
spacing: _margins
FactCheckBox {
text: qsTr("Use preflight checklist")
text: qsTr("Use Preflight Checklist")
fact: _useChecklist
visible: _useChecklist.visible
property Fact _useChecklist: QGroundControl.settingsManager.appSettings.useChecklist
}
FactCheckBox {
text: qsTr("Show Telemetry Log Replay Status Bar")
fact: _showLogReplayStatusBar
visible: _showLogReplayStatusBar.visible
property Fact _showLogReplayStatusBar: QGroundControl.settingsManager.flyViewSettings.showLogReplayStatusBar
}
FactCheckBox {
text: qsTr("Virtual Joystick")
visible: _virtualJoystick.visible
......
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