diff --git a/ChangeLog.md b/ChangeLog.md index a8cb182a0a8a6651f02ff240ad01b88ea535ea8b..ab2df547ca036dc7ed117191610fdcf8145ccbd6 100644 --- a/ChangeLog.md +++ b/ChangeLog.md @@ -6,6 +6,8 @@ Note: This file only contains high level features or important fixes. ### 3.6.0 - Daily Build +* ArduPilot: Copter - Add suppor for Simple and Super Simple flight modes +* ArduPilot: Flight Mode setup - Switch Options were not showing up for all firmware revs * ArduCopter: Add PID Tuning page to Tuning Setup * ArduPilot: Copter - Advanced Tuning support * ArduPilot: Rover - Frame setup support diff --git a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java index b10ce7ccd3975ea183f14d25bcdca36fd946d043..2c772f6b4f834590af78d1ffaa7072a4fb59372c 100644 --- a/android/src/org/mavlink/qgroundcontrol/QGCActivity.java +++ b/android/src/org/mavlink/qgroundcontrol/QGCActivity.java @@ -76,6 +76,7 @@ public class QGCActivity extends QtActivity private static final String ACTION_USB_PERMISSION = "org.mavlink.qgroundcontrol.action.USB_PERMISSION"; private static PendingIntent _usbPermissionIntent = null; private TaiSync taiSync = null; + private Timer probeAccessoriesTimer = null; public static Context m_context; @@ -225,7 +226,15 @@ public class QGCActivity extends QtActivity IntentFilter accessoryFilter = new IntentFilter(ACTION_USB_PERMISSION); filter.addAction(UsbManager.ACTION_USB_ACCESSORY_DETACHED); registerReceiver(mOpenAccessoryReceiver, accessoryFilter); - probeAccessories(); + + probeAccessoriesTimer = new Timer(); + probeAccessoriesTimer.schedule(new TimerTask() { + @Override + public void run() + { + probeAccessories(); + } + }, 0, 3000); } catch(Exception e) { Log.e(TAG, "Exception: " + e); } @@ -243,6 +252,9 @@ public class QGCActivity extends QtActivity @Override protected void onDestroy() { + if (probeAccessoriesTimer != null) { + probeAccessoriesTimer.cancel(); + } unregisterReceiver(mOpenAccessoryReceiver); try { if(_wakeLock != null) { @@ -706,22 +718,26 @@ public class QGCActivity extends QtActivity } } + Object probeAccessoriesLock = new Object(); + private void probeAccessories() { final PendingIntent pendingIntent = PendingIntent.getBroadcast(this, 0, new Intent(ACTION_USB_PERMISSION), 0); new Thread(new Runnable() { public void run() { - Log.i(TAG, "probeAccessories"); - UsbAccessory[] accessories = _usbManager.getAccessoryList(); - if (accessories != null) { - for (UsbAccessory usbAccessory : accessories) { - if (_usbManager.hasPermission(usbAccessory)) { - openAccessory(usbAccessory); - } else { - Log.i(TAG, "requestPermission"); - _usbManager.requestPermission(usbAccessory, pendingIntent); + synchronized(openAccessoryLock) { + Log.i(TAG, "probeAccessories"); + UsbAccessory[] accessories = _usbManager.getAccessoryList(); + if (accessories != null) { + for (UsbAccessory usbAccessory : accessories) { + if (_usbManager.hasPermission(usbAccessory)) { + openAccessory(usbAccessory); + } else { + Log.i(TAG, "requestPermission"); + _usbManager.requestPermission(usbAccessory, pendingIntent); + } } - } + } } } }).start(); diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index ee194b386220779065408295c7c6d86fe7fb611f..318dfed265c3925408eb446b122467cbb060fa10 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -201,7 +201,7 @@ void APMAutoPilotPlugin::_checkForBadCubeBlack(void) if (paramMgr->parameterExists(-1, paramAcc3) && paramMgr->getParameter(-1, paramAcc3)->rawValue().toInt() == 0 && paramMgr->parameterExists(-1, paramGyr3) && paramMgr->getParameter(-1, paramGyr3)->rawValue().toInt() == 0 && paramMgr->parameterExists(-1, paramEnableMask) && paramMgr->getParameter(-1, paramEnableMask)->rawValue().toInt() >= 7) { - qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against ti which advise against flying. https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406")); + qgcApp()->showMessage(tr("WARNING: The flight board you are using has a critical service bulletin against it which advises against flying. For details see: https://discuss.cubepilot.org/t/sb-0000002-critical-service-bulletin-for-cubes-purchased-between-january-2019-to-present-do-not-fly/406")); } } diff --git a/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml b/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml index 091b4277c29f52139dcd30be3ac7c691f412e60c..78277b9615ae1e19cc0ca838bd199ddcc5fcb6bc 100644 --- a/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml +++ b/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml @@ -8,8 +8,9 @@ ****************************************************************************/ -import QtQuick 2.3 -import QtQuick.Controls 1.2 +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtQuick.Layouts 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 @@ -24,14 +25,16 @@ SetupPage { readonly property string _modeChannelParam: controller.modeChannelParam readonly property string _modeParamPrefix: controller.modeParamPrefix + readonly property var _pwmStrings: [ "PWM 0 - 1230", "PWM 1231 - 1360", "PWM 1361 - 1490", "PWM 1491 - 1620", "PWM 1621 - 1749", "PWM 1750 +"] property real _margins: ScreenTools.defaultFontPixelHeight - property bool _channel7OptionsAvailable: controller.parameterExists(-1, "CH7_OPT") // Not available in all firmware types - property bool _channel9OptionsAvailable: controller.parameterExists(-1, "CH9_OPT") // Not available in all firmware types - property int _channelOptionCount: _channel7OptionsAvailable ? (_channel9OptionsAvailable ? 6 : 2) : 0 property Fact _nullFact property bool _fltmodeChExists: controller.parameterExists(-1, _modeChannelParam) property Fact _fltmodeCh: _fltmodeChExists ? controller.getParameterFact(-1, _modeChannelParam) : _nullFact + property bool _ch7OptAvailable: controller.parameterExists(-1, "CH7_OPT") + property int _rcOptionStart: _ch7OptAvailable ? 7 : 6 + property int _rcOptionStop: _ch7OptAvailable ? 12 : 16 + property bool _customSimpleMode: controller.simpleMode === APMFlightModesComponentController.SimpleModeCustom QGCPalette { id: qgcPal; colorGroupEnabled: true } @@ -42,136 +45,186 @@ SetupPage { Component { id: flightModePageComponent - Flow { - id: flowLayout - width: availableWidth - spacing: _margins - - Column { - spacing: _margins - - QGCLabel { - id: flightModeLabel - text: qsTr("Flight Mode Settings") + (_fltmodeChExists ? "" : qsTr(" (Channel 5)")) - font.family: ScreenTools.demiboldFontFamily - } - - Rectangle { - id: flightModeSettings - width: flightModeColumn.width + (_margins * 2) - height: flightModeColumn.height + ScreenTools.defaultFontPixelHeight - color: qgcPal.windowShade - - Column { - id: flightModeColumn - anchors.margins: ScreenTools.defaultFontPixelWidth - anchors.left: parent.left - anchors.top: parent.top - spacing: ScreenTools.defaultFontPixelHeight + Flow { + id: flowLayout + width: availableWidth + spacing: _margins + + Column { + spacing: _margins + + QGCLabel { + id: flightModeLabel + text: qsTr("Flight Mode Settings") + (_fltmodeChExists ? "" : qsTr(" (Channel 5)")) + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: flightModeSettings + width: flightModeColumn.width + (_margins * 2) + height: flightModeColumn.height + ScreenTools.defaultFontPixelHeight + color: qgcPal.windowShade + + Column { + id: flightModeColumn + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.left: parent.left + anchors.top: parent.top + spacing: ScreenTools.defaultFontPixelHeight + + Row { + spacing: _margins + visible: _fltmodeChExists + + QGCLabel { + id: modeChannelLabel + anchors.baseline: modeChannelCombo.baseline + text: qsTr("Flight mode channel:") + } - Row { - spacing: _margins - visible: _fltmodeChExists + QGCComboBox { + id: modeChannelCombo + width: ScreenTools.defaultFontPixelWidth * 15 + model: [ qsTr("Not assigned"), qsTr("Channel 1"), qsTr("Channel 2"), + qsTr("Channel 3"), qsTr("Channel 4"), qsTr("Channel 5"), + qsTr("Channel 6"), qsTr("Channel 7"), qsTr("Channel 8") ] + + currentIndex: _fltmodeCh.value + onActivated: _fltmodeCh.value = index + } + } + + GridLayout { + rows: _customSimpleMode ? 7 : 6 + flow: GridLayout.TopToBottom + + QGCLabel { text: ""; visible: _customSimpleMode } + Repeater { + model: 6 QGCLabel { - id: modeChannelLabel - anchors.baseline: modeChannelCombo.baseline - text: qsTr("Flight mode channel:") + text: qsTr("Flight Mode ") + index + color: controller.activeFlightMode == index ? "yellow" : qgcPal.text + + property int index: modelData + 1 } + } - QGCComboBox { - id: modeChannelCombo - width: ScreenTools.defaultFontPixelWidth * 15 - model: [ qsTr("Not assigned"), qsTr("Channel 1"), qsTr("Channel 2"), - qsTr("Channel 3"), qsTr("Channel 4"), qsTr("Channel 5"), - qsTr("Channel 6"), qsTr("Channel 7"), qsTr("Channel 8") ] + QGCLabel { text: ""; visible: _customSimpleMode } + Repeater { + model: 6 - currentIndex: _fltmodeCh.value - onActivated: _fltmodeCh.value = index + FactComboBox { + Layout.preferredWidth: ScreenTools.defaultFontPixelWidth * 15 + fact: controller.getParameterFact(-1, _modeParamPrefix + index) + indexModel: false + + property int index: modelData + 1 } } + QGCLabel { + text: qsTr("Simple") + font.pointSize: ScreenTools.smallFontPointSize + visible: _customSimpleMode + } Repeater { - model: 6 + model: controller.simpleModeEnabled + QGCCheckBox { + Layout.alignment: Qt.AlignHCenter + visible: _customSimpleMode + checked: modelData + onClicked: controller.setSimpleMode(index, checked) + } + } - Row { - spacing: ScreenTools.defaultFontPixelWidth - - property int index: modelData + 1 - property var pwmStrings: [ "PWM 0 - 1230", "PWM 1231 - 1360", "PWM 1361 - 1490", "PWM 1491 - 1620", "PWM 1621 - 1749", "PWM 1750 +"] - - QGCLabel { - anchors.baseline: modeCombo.baseline - text: qsTr("Flight Mode ") + index + ":" - color: controller.activeFlightMode == index ? "yellow" : qgcPal.text - } - - FactComboBox { - id: modeCombo - width: ScreenTools.defaultFontPixelWidth * 15 - fact: controller.getParameterFact(-1, _modeParamPrefix + index) - indexModel: false - } - - QGCLabel { - anchors.baseline: modeCombo.baseline - text: pwmStrings[modelData] - } + QGCLabel { + text: qsTr("Super-Simple") + font.pointSize: ScreenTools.smallFontPointSize + visible: _customSimpleMode + } + Repeater { + model: controller.superSimpleModeEnabled + QGCCheckBox { + Layout.alignment: Qt.AlignHCenter + visible: _customSimpleMode + checked: modelData + onClicked: controller.setSuperSimpleMode(index, checked) } - } // Repeater - Flight Modes - } // Column - Flight Modes - } // Rectangle - Flight Modes - } // Column - Flight Modes - - Column { - spacing: _margins - visible: _channelOptionCount != 0 - - QGCLabel { - id: channelOptionsLabel - text: qsTr("Channel Options") - font.family: ScreenTools.demiboldFontFamily - } - - Rectangle { - id: channelOptionsSettings - width: channelOptColumn.width + (_margins * 2) - height: channelOptColumn.height + ScreenTools.defaultFontPixelHeight - color: qgcPal.windowShade - - Column { - id: channelOptColumn - anchors.margins: ScreenTools.defaultFontPixelWidth - anchors.left: parent.left - anchors.top: parent.top - spacing: ScreenTools.defaultFontPixelHeight + } + QGCLabel { text: ""; visible: _customSimpleMode } Repeater { - model: _channelOptionCount - - Row { - spacing: ScreenTools.defaultFontPixelWidth - - property int index: modelData + 7 - property Fact nullFact: Fact { } - - QGCLabel { - anchors.baseline: optCombo.baseline - text: qsTr("Channel option %1 :").arg(index) - color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text - } - - FactComboBox { - id: optCombo - width: ScreenTools.defaultFontPixelWidth * 15 - fact: controller.getParameterFact(-1, "CH" + index + "_OPT") - indexModel: false - } + model: 6 + + QGCLabel { text: _pwmStrings[modelData] } + } + } + + RowLayout { + spacing: _margins + visible: controller.simpleModesSupported + + QGCLabel { text: qsTr("Simple Mode") } + + QGCComboBox { + model: controller.simpleModeNames + currentIndex: controller.simpleMode + onActivated: controller.simpleMode = index + } + } + } // Column - Flight Modes + } // Rectangle - Flight Modes + } // Column - Flight Modes + + Column { + spacing: _margins + + QGCLabel { + id: channelOptionsLabel + text: qsTr("Switch Options") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: channelOptionsSettings + width: channelOptColumn.width + (_margins * 2) + height: channelOptColumn.height + ScreenTools.defaultFontPixelHeight + color: qgcPal.windowShade + + Column { + id: channelOptColumn + anchors.margins: ScreenTools.defaultFontPixelWidth + anchors.left: parent.left + anchors.top: parent.top + spacing: ScreenTools.defaultFontPixelHeight + + Repeater { + model: _rcOptionStop - _rcOptionStart + 1 + + Row { + spacing: ScreenTools.defaultFontPixelWidth + + property int index: modelData + _rcOptionStart + property Fact nullFact: Fact { } + + QGCLabel { + anchors.baseline: optCombo.baseline + text: qsTr("Channel option %1 :").arg(index) + color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text + } + + FactComboBox { + id: optCombo + width: ScreenTools.defaultFontPixelWidth * 15 + fact: controller.getParameterFact(-1, "r.RC" + index + "_OPTION") + indexModel: false } - } // Repeater -- Channel options - } // Column - Channel options - } // Rectangle - Channel options - } // Column - Channel options - } // Flow + } + } // Repeater -- Channel options + } // Column - Channel options + } // Rectangle - Channel options + } // Column - Channel options + } // Flow } // Component - flightModePageComponent } // SetupPage diff --git a/src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc b/src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc index f13e78858f844a92ddc59d95fa1cdd684a417a2e..8eb4feaedc14a55c198658280f7e03dceecc04cd 100644 --- a/src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMFlightModesComponentController.cc @@ -14,13 +14,50 @@ #include <QVariant> #include <QQmlProperty> +bool APMFlightModesComponentController::_typeRegistered = false; + +const char* APMFlightModesComponentController::_simpleParamName = "SIMPLE"; +const char* APMFlightModesComponentController::_superSimpleParamName = "SUPER_SIMPLE"; + APMFlightModesComponentController::APMFlightModesComponentController(void) - : _activeFlightMode(0) - , _channelCount(Vehicle::cMaxRcChannels) + : _activeFlightMode (0) + , _channelCount (Vehicle::cMaxRcChannels) + , _simpleMode (SimpleModeStandard) + , _simpleModeFact (parameterExists(-1, _simpleParamName) ? getParameterFact(-1, _simpleParamName) : nullptr) + , _superSimpleModeFact (parameterExists(-1, _superSimpleParamName) ? getParameterFact(-1, _superSimpleParamName) : nullptr) + , _simpleModesSupported (_simpleModeFact && _superSimpleModeFact) { + if (!_typeRegistered) { + qmlRegisterUncreatableType<APMFlightModesComponentController>("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController", "Reference only"); + } + _modeParamPrefix = _vehicle->rover() ? QStringLiteral("MODE") : QStringLiteral("FLTMODE"); _modeChannelParam = _vehicle->rover() ? QStringLiteral("MODE_CH") : QStringLiteral("FLTMODE_CH"); + _simpleModeNames << tr("Off") << tr("Simple") << tr("Super-Simple") << tr("Custom"); + for (int i=0; i<_cFltModes; i++) { + _simpleModeEnabled.append(QVariant(false)); + _superSimpleModeEnabled.append(QVariant(false)); + } + + if (_simpleModesSupported) { + _setupSimpleModeEnabled(); + + uint8_t simpleModeValue = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt()); + uint8_t superSimpleModeValue = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt()); + if (simpleModeValue == 0 && superSimpleModeValue == 0) { + _simpleMode = SimpleModeStandard; + } else if (simpleModeValue == _allSimpleBits && superSimpleModeValue == 0) { + _simpleMode = SimpleModeSimple; + } else if (simpleModeValue == 0 && superSimpleModeValue == _allSimpleBits) { + _simpleMode = SimpleModeSuperSimple; + } else { + _simpleMode = SimpleModeCustom; + } + + connect(this, &APMFlightModesComponentController::simpleModeChanged, this, &APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode); + } + QStringList usedParams; for (int i=1; i<7; i++) { usedParams << QStringLiteral("%1%2").arg(_modeParamPrefix).arg(i); @@ -29,8 +66,10 @@ APMFlightModesComponentController::APMFlightModesComponentController(void) return; } - _rgChannelOptionEnabled << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false) << QVariant(false); - + for (int i=0; i<_cChannelOptions; i++) { + _rgChannelOptionEnabled.append(QVariant(false)); + } + connect(_vehicle, &Vehicle::rcChannelsChanged, this, &APMFlightModesComponentController::_rcChannelsChanged); } @@ -65,7 +104,7 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int } emit activeFlightModeChanged(_activeFlightMode); - for (int i=0; i<6; i++) { + for (int i=0; i<_cChannelOptions; i++) { _rgChannelOptionEnabled[i] = QVariant(false); channelValue = pwmValues[i+6]; if (channelValue > 1800) { @@ -74,3 +113,66 @@ void APMFlightModesComponentController::_rcChannelsChanged(int channelCount, int } emit channelOptionEnabledChanged(); } + +void APMFlightModesComponentController::_updateSimpleParamsFromSimpleMode(void) +{ + int newSimpleModeValue = 0; + int newSuperSimpleModeValue = 0; + + if (_simpleMode == SimpleModeSimple) { + newSimpleModeValue = _allSimpleBits; + } else if (_simpleMode == SimpleModeSuperSimple) { + newSuperSimpleModeValue = _allSimpleBits; + } + + for (int i=0; i<_cFltModes; i++) { + _simpleModeEnabled[i] = false; + _superSimpleModeEnabled[i] = false; + } + emit simpleModeEnabledChanged(); + emit superSimpleModeEnabledChanged(); + + _simpleModeFact->setRawValue(newSimpleModeValue); + _superSimpleModeFact->setRawValue(newSuperSimpleModeValue); +} + +void APMFlightModesComponentController::setSimpleMode(int fltModeIndex, bool enabled) +{ + if (fltModeIndex < _cFltModes) { + uint8_t mode = static_cast<uint8_t>(_simpleModeFact->rawValue().toInt()); + if (enabled) { + mode |= 1 << fltModeIndex; + } else { + mode &= ~(1 << fltModeIndex); + } + _simpleModeFact->setRawValue(mode); + } +} + +void APMFlightModesComponentController::setSuperSimpleMode(int fltModeIndex, bool enabled) +{ + if (fltModeIndex < _cFltModes) { + uint8_t mode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toInt()); + if (enabled) { + mode |= 1 << fltModeIndex; + } else { + mode &= ~(1 << fltModeIndex); + } + _superSimpleModeFact->setRawValue(mode); + } +} + +void APMFlightModesComponentController::_setupSimpleModeEnabled(void) +{ + uint8_t simpleMode = static_cast<uint8_t>(_simpleModeFact->rawValue().toUInt()); + uint8_t superSimpleMode = static_cast<uint8_t>(_superSimpleModeFact->rawValue().toUInt()); + + for (int i=0; i<_cFltModes; i++) { + uint8_t bitSet = static_cast<uint8_t>(1 << i); + _simpleModeEnabled[i] = !!(simpleMode & bitSet); + _superSimpleModeEnabled[i] = !!(superSimpleMode & bitSet); + } + + emit simpleModeEnabledChanged(); + emit superSimpleModeEnabledChanged(); +} diff --git a/src/AutoPilotPlugins/APM/APMFlightModesComponentController.h b/src/AutoPilotPlugins/APM/APMFlightModesComponentController.h index d193f7202f231a1f0e5f7e7ef35da6ce8543db9c..459111822ac3b808c29bd44a08094854003c2d9e 100644 --- a/src/AutoPilotPlugins/APM/APMFlightModesComponentController.h +++ b/src/AutoPilotPlugins/APM/APMFlightModesComponentController.h @@ -27,30 +27,68 @@ class APMFlightModesComponentController : public FactPanelController Q_OBJECT public: + enum SimpleModeValues { + SimpleModeStandard = 0, + SimpleModeSimple, + SimpleModeSuperSimple, + SimpleModeCustom + }; + Q_ENUM(SimpleModeValues) + APMFlightModesComponentController(void); - Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT) - Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT) - Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged) - Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT) - Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged) + Q_PROPERTY(QString modeParamPrefix MEMBER _modeParamPrefix CONSTANT) + Q_PROPERTY(QString modeChannelParam MEMBER _modeChannelParam CONSTANT) + Q_PROPERTY(int activeFlightMode READ activeFlightMode NOTIFY activeFlightModeChanged) + Q_PROPERTY(int channelCount MEMBER _channelCount CONSTANT) + Q_PROPERTY(QVariantList channelOptionEnabled READ channelOptionEnabled NOTIFY channelOptionEnabledChanged) + Q_PROPERTY(bool simpleModesSupported MEMBER _simpleModesSupported CONSTANT) + Q_PROPERTY(QStringList simpleModeNames MEMBER _simpleModeNames CONSTANT) + Q_PROPERTY(int simpleMode MEMBER _simpleMode NOTIFY simpleModeChanged) + Q_PROPERTY(QVariantList simpleModeEnabled MEMBER _simpleModeEnabled NOTIFY simpleModeEnabledChanged) + Q_PROPERTY(QVariantList superSimpleModeEnabled MEMBER _superSimpleModeEnabled NOTIFY superSimpleModeEnabledChanged) + + Q_INVOKABLE void setSimpleMode(int fltModeIndex, bool enabled); + Q_INVOKABLE void setSuperSimpleMode(int fltModeIndex, bool enabled); int activeFlightMode(void) const { return _activeFlightMode; } QVariantList channelOptionEnabled(void) const { return _rgChannelOptionEnabled; } signals: - void activeFlightModeChanged(int activeFlightMode); - void channelOptionEnabledChanged(void); - + void activeFlightModeChanged (int activeFlightMode); + void channelOptionEnabledChanged (void); + void simpleModeChanged (int simpleMode); + void simpleModeEnabledChanged (void); + void superSimpleModeEnabledChanged (void); + private slots: - void _rcChannelsChanged(int channelCount, int pwmValues[Vehicle::cMaxRcChannels]); - + void _rcChannelsChanged (int channelCount, int pwmValues[Vehicle::cMaxRcChannels]); + void _updateSimpleParamsFromSimpleMode (void); + void _setupSimpleModeEnabled (void); + private: QString _modeParamPrefix; QString _modeChannelParam; int _activeFlightMode; int _channelCount; QVariantList _rgChannelOptionEnabled; + QStringList _simpleModeNames; + int _simpleMode; + Fact* _simpleModeFact; + Fact* _superSimpleModeFact; + bool _simpleModesSupported; + QVariantList _simpleModeEnabled; + QVariantList _superSimpleModeEnabled; + + static const uint8_t _allSimpleBits = 0x3F; + static const int _cChannelOptions = 10; + static const int _cSimpleModeBits = 8; + static const int _cFltModes = 6; + + static const char* _simpleParamName; + static const char* _superSimpleParamName; + + static bool _typeRegistered; }; #endif diff --git a/src/AutoPilotPlugins/APM/APMPowerComponent.qml b/src/AutoPilotPlugins/APM/APMPowerComponent.qml index 355535e6bd6dcd979f9a260713dcaaf88d00a759..025cfba7dff5b9155294037bf8c42beaebae60d9 100644 --- a/src/AutoPilotPlugins/APM/APMPowerComponent.qml +++ b/src/AutoPilotPlugins/APM/APMPowerComponent.qml @@ -515,7 +515,7 @@ SetupPage { QGCLabel { width: parent.width wrapMode: Text.WordWrap - text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new voltage multiplier.") + text: qsTr("Measure battery voltage using an external voltmeter and enter the value below. Click Calculate to set the new adjusted voltage multiplier.") } Grid { @@ -536,7 +536,7 @@ SetupPage { } QGCButton { - text: "Calculate" + text: qsTr("Calculate And Set") onClicked: { var measuredVoltageValue = parseFloat(measuredVoltage.text) @@ -598,7 +598,7 @@ SetupPage { } QGCButton { - text: "Calculate" + text: qsTr("Calculate And Set") onClicked: { var measuredCurrentValue = parseFloat(measuredCurrent.text) diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index a4b944c8ad2af92323688ee11f374336886ace00..f01fbc8eb4547ec5b53021e68b995f5f4328d054 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -692,16 +692,25 @@ SetupPage { calValid: controller.orientationCalDownSideDone calInProgress: controller.orientationCalDownSideInProgress calInProgressText: controller.orientationCalDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalDownSideRotate ? "qrc:///qmlimages/VehicleDownRotate.png" : "qrc:///qmlimages/VehicleDown.png" + imageSource: "qrc:///qmlimages/VehicleDown.png" } VehicleRotationCal { width: parent.indicatorWidth height: parent.indicatorHeight - visible: controller.orientationCalUpsideDownSideVisible - calValid: controller.orientationCalUpsideDownSideDone - calInProgress: controller.orientationCalUpsideDownSideInProgress - calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalUpsideDownSideRotate ? "qrc:///qmlimages/VehicleUpsideDownRotate.png" : "qrc:///qmlimages/VehicleUpsideDown.png" + visible: controller.orientationCalLeftSideVisible + calValid: controller.orientationCalLeftSideDone + calInProgress: controller.orientationCalLeftSideInProgress + calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: "qrc:///qmlimages/VehicleLeft.png" + } + VehicleRotationCal { + width: parent.indicatorWidth + height: parent.indicatorHeight + visible: controller.orientationCalRightSideVisible + calValid: controller.orientationCalRightSideDone + calInProgress: controller.orientationCalRightSideInProgress + calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: "qrc:///qmlimages/VehicleRight.png" } VehicleRotationCal { width: parent.indicatorWidth @@ -710,7 +719,7 @@ SetupPage { calValid: controller.orientationCalNoseDownSideDone calInProgress: controller.orientationCalNoseDownSideInProgress calInProgressText: controller.orientationCalNoseDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalNoseDownSideRotate ? "qrc:///qmlimages/VehicleNoseDownRotate.png" : "qrc:///qmlimages/VehicleNoseDown.png" + imageSource: "qrc:///qmlimages/VehicleNoseDown.png" } VehicleRotationCal { width: parent.indicatorWidth @@ -719,25 +728,16 @@ SetupPage { calValid: controller.orientationCalTailDownSideDone calInProgress: controller.orientationCalTailDownSideInProgress calInProgressText: controller.orientationCalTailDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalTailDownSideRotate ? "qrc:///qmlimages/VehicleTailDownRotate.png" : "qrc:///qmlimages/VehicleTailDown.png" + imageSource: "qrc:///qmlimages/VehicleTailDown.png" } VehicleRotationCal { width: parent.indicatorWidth height: parent.indicatorHeight - visible: controller.orientationCalLeftSideVisible - calValid: controller.orientationCalLeftSideDone - calInProgress: controller.orientationCalLeftSideInProgress - calInProgressText: controller.orientationCalLeftSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalLeftSideRotate ? "qrc:///qmlimages/VehicleLeftRotate.png" : "qrc:///qmlimages/VehicleLeft.png" - } - VehicleRotationCal { - width: parent.indicatorWidth - height: parent.indicatorHeight - visible: controller.orientationCalRightSideVisible - calValid: controller.orientationCalRightSideDone - calInProgress: controller.orientationCalRightSideInProgress - calInProgressText: controller.orientationCalRightSideRotate ? qsTr("Rotate") : qsTr("Hold Still") - imageSource: controller.orientationCalRightSideRotate ? "qrc:///qmlimages/VehicleRightRotate.png" : "qrc:///qmlimages/VehicleRight.png" + visible: controller.orientationCalUpsideDownSideVisible + calValid: controller.orientationCalUpsideDownSideDone + calInProgress: controller.orientationCalUpsideDownSideInProgress + calInProgressText: controller.orientationCalUpsideDownSideRotate ? qsTr("Rotate") : qsTr("Hold Still") + imageSource: "qrc:///qmlimages/VehicleUpsideDown.png" } } } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index adc0019f3ddc93cf75cfcdccbe6521d6043f6d4f..1d45eb05abbbb949b9489ab5e723147db7f5eb36 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -227,7 +227,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone _startLogCalibration(); uint8_t compassBits = 0; if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID"))->rawValue().toInt() > 0 && - getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE"))->rawValue().toBool()) { + getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE"))->rawValue().toBool()) { compassBits |= 1 << 0; qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 1"; } else { @@ -236,7 +236,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone _rgCompassCalFitness[0] = 0; } if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID2"))->rawValue().toInt() > 0 && - getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE2"))->rawValue().toBool()) { + getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE2"))->rawValue().toBool()) { compassBits |= 1 << 1; qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 2"; } else { @@ -245,7 +245,7 @@ void APMSensorsComponentController::_mavCommandResult(int vehicleId, int compone _rgCompassCalFitness[1] = 0; } if (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_DEV_ID3"))->rawValue().toInt() > 0 && - getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE3"))->rawValue().toBool()) { + getParameterFact(FactSystem::defaultComponentId, QStringLiteral("COMPASS_USE3"))->rawValue().toBool()) { compassBits |= 1 << 2; qCDebug(APMSensorsComponentControllerLog) << "Performing onboard compass cal for compass 3"; } else { @@ -335,11 +335,118 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, return; } - if (text.startsWith(QLatin1Literal("PreArm:")) || text.startsWith(QLatin1Literal("EKF")) - || text.startsWith(QLatin1Literal("Arm")) || text.startsWith(QLatin1Literal("Initialising"))) { + QString originalMessageText = text; + text = text.toLower(); + + QStringList hidePrefixList = { QStringLiteral("prearm:"), QStringLiteral("ekf"), QStringLiteral("arm"), QStringLiteral("initialising") }; + for (const QString& hidePrefix: hidePrefixList) { + if (text.startsWith(hidePrefix)) { + return; + } + } + + if (_calTypeInProgress == CalTypeAccel) { + if (text == QStringLiteral("place vehicle level and press any key.")) { + _startVisualCalibration(); + _cancelButton->setEnabled(false); + + // Reset all progress indication + _orientationCalDownSideDone = false; + _orientationCalUpsideDownSideDone = false; + _orientationCalLeftSideDone = false; + _orientationCalRightSideDone = false; + _orientationCalTailDownSideDone = false; + _orientationCalNoseDownSideDone = false; + _orientationCalDownSideInProgress = false; + _orientationCalUpsideDownSideInProgress = false; + _orientationCalLeftSideInProgress = false; + _orientationCalRightSideInProgress = false; + _orientationCalNoseDownSideInProgress = false; + _orientationCalTailDownSideInProgress = false; + + // Reset all visibility + _orientationCalDownSideVisible = false; + _orientationCalUpsideDownSideVisible = false; + _orientationCalLeftSideVisible = false; + _orientationCalRightSideVisible = false; + _orientationCalTailDownSideVisible = false; + _orientationCalNoseDownSideVisible = false; + + _calTypeInProgress = CalTypeAccel; + _orientationCalDownSideVisible = true; + _orientationCalUpsideDownSideVisible = true; + _orientationCalLeftSideVisible = true; + _orientationCalRightSideVisible = true; + _orientationCalTailDownSideVisible = true; + _orientationCalNoseDownSideVisible = true; + + emit orientationCalSidesDoneChanged(); + emit orientationCalSidesVisibleChanged(); + emit orientationCalSidesInProgressChanged(); + _updateAndEmitShowOrientationCalArea(true); + } + + QString placeVehicle("place vehicle "); + if (_calTypeInProgress == CalTypeAccel && text.startsWith(placeVehicle)) { + text = text.right(text.length() - placeVehicle.length()); + if (text.startsWith("level")) { + _orientationCalDownSideInProgress = true; + _nextButton->setEnabled(true); + } else if (text.startsWith("on its left")) { + _orientationCalDownSideDone = true; + _orientationCalDownSideInProgress = false; + _orientationCalLeftSideInProgress = true; + _progressBar->setProperty("value", (qreal)(17 / 100.0)); + } else if (text.startsWith("on its right")) { + _orientationCalLeftSideDone = true; + _orientationCalLeftSideInProgress = false; + _orientationCalRightSideInProgress = true; + _progressBar->setProperty("value", (qreal)(34 / 100.0)); + } else if (text.startsWith("nose down")) { + _orientationCalRightSideDone = true; + _orientationCalRightSideInProgress = false; + _orientationCalNoseDownSideInProgress = true; + _progressBar->setProperty("value", (qreal)(51 / 100.0)); + } else if (text.startsWith("nose up")) { + _orientationCalNoseDownSideDone = true; + _orientationCalNoseDownSideInProgress = false; + _orientationCalTailDownSideInProgress = true; + _progressBar->setProperty("value", (qreal)(68 / 100.0)); + } else if (text.startsWith("on its back")) { + _orientationCalTailDownSideDone = true; + _orientationCalTailDownSideInProgress = false; + _orientationCalUpsideDownSideInProgress = true; + _progressBar->setProperty("value", (qreal)(85 / 100.0)); + } + + _orientationCalAreaHelpText->setProperty("text", tr("Hold still in the current orientation and press Next when ready")); + + emit orientationCalSidesDoneChanged(); + emit orientationCalSidesInProgressChanged(); + emit orientationCalSidesRotateChanged(); + } + } + + _appendStatusLog(originalMessageText); + qCDebug(APMSensorsComponentControllerLog) << originalMessageText << severity; + + if (text.contains(QLatin1String("calibration successful"))) { + _stopCalibration(StopCalibrationSuccess); return; } + if (text.startsWith(QStringLiteral("calibration cancelled"))) { + _stopCalibration(_waitingForCancel ? StopCalibrationCancelled : StopCalibrationFailed); + return; + } + + if (text.startsWith(QStringLiteral("calibration failed"))) { + _stopCalibration(StopCalibrationFailed); + return; + } + +#if 0 + if (text.contains(QLatin1Literal("progress <"))) { QString percent = text.split("<").last().split(">").first(); bool ok; @@ -533,6 +640,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, _stopCalibration(StopCalibrationFailed); return; } +#endif } void APMSensorsComponentController::_refreshParams(void) diff --git a/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml b/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml index 06c2c2c37d678af40f7113ae22074cdc3031fb49..202f9ef05571db56945098229c23bf4f49e6a6fe 100644 --- a/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml +++ b/src/AutoPilotPlugins/PX4/PX4TuningComponentCopter.qml @@ -59,26 +59,6 @@ SetupPage { max: 15 step: 1 } - /* - These seem to have disappeared from PX4 firmware! - ListElement { - title: qsTr("Roll sensitivity") - description: qsTr("Slide to the left to make roll control faster and more accurate. Slide to the right if roll oscillates or is too twitchy.") - param: "MC_ROLL_TC" - min: 0.15 - max: 0.25 - step: 0.01 - } - - ListElement { - title: qsTr("Pitch sensitivity") - description: qsTr("Slide to the left to make pitch control faster and more accurate. Slide to the right if pitch oscillates or is too twitchy.") - param: "MC_PITCH_TC" - min: 0.15 - max: 0.25 - step: 0.01 - } -*/ } } diff --git a/src/FactSystem/FactGroup.cc b/src/FactSystem/FactGroup.cc index c67c02d8f55a2a2ec118db30cf9dd7b46747aa6d..55aedaf9869c6f4bc047fc5954ef7414c5918139 100644 --- a/src/FactSystem/FactGroup.cc +++ b/src/FactSystem/FactGroup.cc @@ -46,7 +46,8 @@ void FactGroup::_setupTimer() if (_updateRateMSecs > 0) { connect(&_updateTimer, &QTimer::timeout, this, &FactGroup::_updateAllValues); _updateTimer.setSingleShot(false); - _updateTimer.start(_updateRateMSecs); + _updateTimer.setInterval(_updateRateMSecs); + _updateTimer.start(); } } @@ -125,3 +126,19 @@ void FactGroup::_updateAllValues(void) fact->sendDeferredValueChangedSignal(); } } + +void FactGroup::setLiveUpdates(bool liveUpdates) +{ + if (_updateTimer.interval() == 0) { + return; + } + + if (liveUpdates) { + _updateTimer.stop(); + } else { + _updateTimer.start(); + } + for(Fact* fact: _nameToFactMap) { + fact->setSendValueChangedSignals(liveUpdates); + } +} diff --git a/src/FactSystem/FactGroup.h b/src/FactSystem/FactGroup.h index 78a97fcb60c79ddc140b68a7476d50ae2e8930f2..9e8320fca0cfcc977f8f70f23e23aac04a58ba6b 100644 --- a/src/FactSystem/FactGroup.h +++ b/src/FactSystem/FactGroup.h @@ -38,6 +38,9 @@ public: /// @return FactGroup for specified name, NULL if not found Q_INVOKABLE FactGroup* getFactGroup(const QString& name); + /// Turning on live updates will allow value changes to flow through as they are received. + Q_INVOKABLE void setLiveUpdates(bool liveUpdates); + QStringList factNames(void) const { return _factNames; } QStringList factGroupNames(void) const { return _nameToFactGroupMap.keys(); } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml index 6a4bcabab00f9858f8f0532a67541551ab8fcfd1..9349789432dbc0295322e670f5070e94ec2a250b 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml +++ b/src/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml @@ -4311,7 +4311,7 @@ default 1.5 turns per second</short_desc> <long_desc>This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.</long_desc> <boolean /> </parameter> - <parameter default="30." name="MC_DTERM_CUTOFF" type="FLOAT"> + <parameter default="0." name="MC_DTERM_CUTOFF" type="FLOAT"> <short_desc>Cutoff frequency for the low pass filter on the D-term in the rate controller</short_desc> <long_desc>The D-term uses the derivative of the rate and thus is the most susceptible to noise. Therefore, using a D-term filter allows to decrease the driver-level filtering, which leads to reduced control latency and permits to increase the P gains. A value of 0 disables the filter.</long_desc> <min>0</min> @@ -8352,7 +8352,7 @@ is less than 50% of this value</short_desc> <unit>Hz</unit> <reboot_required>true</reboot_required> </parameter> - <parameter default="80.0" name="IMU_GYRO_CUTOFF" type="FLOAT"> + <parameter default="30.0" name="IMU_GYRO_CUTOFF" type="FLOAT"> <short_desc>Driver level cutoff frequency for gyro</short_desc> <long_desc>The cutoff frequency for the 2nd order butterworth filter on the gyro driver. This features is currently supported by the mpu6000 and mpu9250. This only affects the signal sent to the controllers, not the estimators. 0 disables the filter.</long_desc> <min>0</min> diff --git a/src/MissionManager/MissionCommandTree.cc b/src/MissionManager/MissionCommandTree.cc index 8d4bce9d4c13f13d055f2ab58e166f2a7d1bf04b..d1e537cca40831d9b92e2d07a6ab8c5f03ef8a74 100644 --- a/src/MissionManager/MissionCommandTree.cc +++ b/src/MissionManager/MissionCommandTree.cc @@ -106,14 +106,6 @@ void MissionCommandTree::_collapseHierarchy(Vehicle* _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); for (MAV_CMD command: cmdList->commandIds()) { - // Only add supported command to tree (MAV_CMD_NAV_LAST is used for planned home position) - if (!qgcApp()->runningUnitTests() - && !vehicle->firmwarePlugin()->supportedMissionCommands().isEmpty() - && !vehicle->firmwarePlugin()->supportedMissionCommands().contains(command) - && command != MAV_CMD_NAV_LAST) { - continue; - } - MissionCommandUIInfo* uiInfo = cmdList->getUIInfo(command); if (uiInfo) { if (collapsedTree.contains(command)) { @@ -125,22 +117,20 @@ void MissionCommandTree::_collapseHierarchy(Vehicle* } } -void MissionCommandTree::_buildAvailableCommands(Vehicle* vehicle) +void MissionCommandTree::_buildAllCommands(Vehicle* vehicle) { MAV_AUTOPILOT baseFirmwareType; MAV_TYPE baseVehicleType; _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - if (_availableCommands.contains(baseFirmwareType) && - _availableCommands[baseFirmwareType].contains(baseVehicleType)) { - // Available commands list already built + if (_allCommands.contains(baseFirmwareType) && + _allCommands[baseFirmwareType].contains(baseVehicleType)) { + // Already built return; } - // Build new available commands list - - QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree = _availableCommands[baseFirmwareType][baseVehicleType]; + QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree = _allCommands[baseFirmwareType][baseVehicleType]; // Any Firmware, Any Vehicle _collapseHierarchy(vehicle, _staticCommandTree[MAV_AUTOPILOT_GENERIC][MAV_TYPE_GENERIC], collapsedTree); @@ -160,16 +150,17 @@ void MissionCommandTree::_buildAvailableCommands(Vehicle* vehicle) } } - // Build category list - QMapIterator<MAV_CMD, MissionCommandUIInfo*> iter(collapsedTree); - while (iter.hasNext()) { - iter.next(); - QString newCategory = iter.value()->category(); - if (!_availableCategories[baseFirmwareType][baseVehicleType].contains(newCategory)) { - _availableCategories[baseFirmwareType][baseVehicleType].append(newCategory); + // Build category list from supported commands + QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands(); + for (MAV_CMD cmd: collapsedTree.keys()) { + if (supportedCommands.contains(cmd)) { + QString newCategory = collapsedTree[cmd]->category(); + if (!_supportedCategories[baseFirmwareType][baseVehicleType].contains(newCategory)) { + _supportedCategories[baseFirmwareType][baseVehicleType].append(newCategory); + } } } - _availableCategories[baseFirmwareType][baseVehicleType].append(_allCommandsCategory); + _supportedCategories[baseFirmwareType][baseVehicleType].append(_allCommandsCategory); } QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle) @@ -178,9 +169,9 @@ QStringList MissionCommandTree::_availableCategoriesForVehicle(Vehicle* vehicle) MAV_TYPE baseVehicleType; _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - _buildAvailableCommands(vehicle); + _buildAllCommands(vehicle); - return _availableCategories[baseFirmwareType][baseVehicleType]; + return _supportedCategories[baseFirmwareType][baseVehicleType]; } QString MissionCommandTree::friendlyName(MAV_CMD command) @@ -191,7 +182,7 @@ QString MissionCommandTree::friendlyName(MAV_CMD command) if (uiInfo) { return uiInfo->friendlyName(); } else { - return QString("MAV_CMD(%1)").arg((int)command); + return QStringLiteral("MAV_CMD(%1)").arg((int)command); } } @@ -203,7 +194,7 @@ QString MissionCommandTree::rawName(MAV_CMD command) if (uiInfo) { return uiInfo->rawName(); } else { - return QString("MAV_CMD(%1)").arg((int)command); + return QStringLiteral("MAV_CMD(%1)").arg((int)command); } } @@ -218,13 +209,13 @@ const MissionCommandUIInfo* MissionCommandTree::getUIInfo(Vehicle* vehicle, MAV_ MAV_TYPE baseVehicleType; _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - _buildAvailableCommands(vehicle); + _buildAllCommands(vehicle); - const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _availableCommands[baseFirmwareType][baseVehicleType]; + const QMap<MAV_CMD, MissionCommandUIInfo*>& infoMap = _allCommands[baseFirmwareType][baseVehicleType]; if (infoMap.contains(command)) { return infoMap[command]; } else { - return NULL; + return nullptr; } } @@ -232,21 +223,19 @@ QVariantList MissionCommandTree::getCommandsForCategory(Vehicle* vehicle, const { MAV_AUTOPILOT baseFirmwareType; MAV_TYPE baseVehicleType; + QList<MAV_CMD> supportedCommands = vehicle->firmwarePlugin()->supportedMissionCommands(); _baseVehicleInfo(vehicle, baseFirmwareType, baseVehicleType); - _buildAvailableCommands(vehicle); + _buildAllCommands(vehicle); QVariantList list; - QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _availableCommands[baseFirmwareType][baseVehicleType]; + QMap<MAV_CMD, MissionCommandUIInfo*> commandMap = _allCommands[baseFirmwareType][baseVehicleType]; for (MAV_CMD command: commandMap.keys()) { - if (command == MAV_CMD_NAV_LAST) { - // MAV_CMD_NAV_LAST is used for Mission Settings item. Although we want to be able to get command info for it. - // The user should not be able to use it as a command. - continue; - } - MissionCommandUIInfo* uiInfo = commandMap[command]; - if (uiInfo->category() == category || category == _allCommandsCategory) { - list.append(QVariant::fromValue(uiInfo)); + if (supportedCommands.contains(command)) { + MissionCommandUIInfo* uiInfo = commandMap[command]; + if (uiInfo->category() == category || category == _allCommandsCategory) { + list.append(QVariant::fromValue(uiInfo)); + } } } diff --git a/src/MissionManager/MissionCommandTree.h b/src/MissionManager/MissionCommandTree.h index 13639b2eec4699193e69105a9b09f85fb13d7d04..13884358604949aa0c1a5a70781dcae0282112fa 100644 --- a/src/MissionManager/MissionCommandTree.h +++ b/src/MissionManager/MissionCommandTree.h @@ -41,7 +41,7 @@ class MissionCommandTreeTest; /// For known firmwares, the override files are requested from the FirmwarePlugin. /// /// When ui info is requested for a specific vehicle the static hierarchy in _staticCommandTree is collapsed into the set of available commands in -/// _availableCommands taking into account the appropriate set of overrides for the MAV_AUTOPILOT/MAV_TYPE combination associated with the vehicle. +/// _allCommands taking into account the appropriate set of overrides for the MAV_AUTOPILOT/MAV_TYPE combination associated with the vehicle. /// class MissionCommandTree : public QGCTool { @@ -68,12 +68,12 @@ public: virtual void setToolbox(QGCToolbox* toolbox); private: - void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree); - MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const; - MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const; - void _buildAvailableCommands(Vehicle* vehicle); - QStringList _availableCategoriesForVehicle(Vehicle* vehicle); - void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const; + void _collapseHierarchy(Vehicle* vehicle, const MissionCommandList* cmdList, QMap<MAV_CMD, MissionCommandUIInfo*>& collapsedTree); + MAV_TYPE _baseVehicleType(MAV_TYPE mavType) const; + MAV_AUTOPILOT _baseFirmwareType(MAV_AUTOPILOT firmwareType) const; + void _buildAllCommands(Vehicle* vehicle); + QStringList _availableCategoriesForVehicle(Vehicle* vehicle); + void _baseVehicleInfo(Vehicle* vehicle, MAV_AUTOPILOT& baseFirmwareType, MAV_TYPE& baseVehicleType) const; private: QString _allCommandsCategory; ///< Category which contains all available commands @@ -85,10 +85,10 @@ private: QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, MissionCommandList*>> _staticCommandTree; /// Collapsed hierarchy for specific vehicle type - QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _availableCommands; + QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QMap<MAV_CMD, MissionCommandUIInfo*>>> _allCommands; /// Collapsed hierarchy for specific vehicle type - QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList>> _availableCategories; + QMap<MAV_AUTOPILOT, QMap<MAV_TYPE, QStringList /* category */>> _supportedCategories; #ifdef UNITTEST_BUILD diff --git a/src/QmlControls/FactSliderPanel.qml b/src/QmlControls/FactSliderPanel.qml index 924c5e6af02031c6c4eefcb9d6fbbac6bee403c8..f46f8086cc0e9789d0a73f0fd9776e80e381e4cb 100644 --- a/src/QmlControls/FactSliderPanel.qml +++ b/src/QmlControls/FactSliderPanel.qml @@ -32,6 +32,8 @@ Column { property real _margins: ScreenTools.defaultFontPixelHeight property bool _loadComplete: false + Component.onCompleted: _loadComplete = true + FactPanelController { id: controller } @@ -68,10 +70,22 @@ Column { font.family: ScreenTools.demiboldFontFamily } - FactValueSlider { - digitCount: fact.maxString.length - incrementSlots: 3 - fact: controller.getParameterFact(-1, param) + Slider { + anchors.left: parent.left + anchors.right: parent.right + minimumValue: min + maximumValue: max + stepSize: step + tickmarksEnabled: true + value: _fact.value + + property Fact _fact: controller.getParameterFact(-1, param) + + onValueChanged: { + if (_loadComplete) { + _fact.value = value + } + } } QGCLabel { diff --git a/src/QmlControls/PIDTuning.qml b/src/QmlControls/PIDTuning.qml index 5de48fb260b2de68aaf6d45861c34b1e460f2581..614af00691c9c3f79a6746dfa327e6718c1e5eb9 100644 --- a/src/QmlControls/PIDTuning.qml +++ b/src/QmlControls/PIDTuning.qml @@ -142,9 +142,12 @@ RowLayout { } Component.onCompleted: { + activeVehicle.setPIDTuningTelemetryMode(true) saveTuningParamValues() } + Component.onDestruction: activeVehicle.setPIDTuningTelemetryMode(false) + on_CurrentTuneTypeChanged: { saveTuningParamValues() resetGraphs() @@ -155,7 +158,8 @@ RowLayout { min: 0 max: 0 labelFormat: "%d" - titleText: "sec" + titleText: "msec" + tickCount: 11 } ValueAxis { @@ -163,7 +167,8 @@ RowLayout { min: 0 max: 0 labelFormat: "%d" - titleText: "sec" + titleText: "msec" + tickCount: 11 } ValueAxis { @@ -189,40 +194,28 @@ RowLayout { repeat: true onTriggered: { - var seconds = _msecs / 1000 - _valueXAxis.max = seconds - _valueRateXAxis.max = seconds + _valueXAxis.max = _msecs + _valueRateXAxis.max = _msecs getValues() - valueSeries.append(seconds, _value) + valueSeries.append(_msecs, _value) adjustYAxisMin(_valueYAxis, _value) adjustYAxisMax(_valueYAxis, _value) - valueSetpointSeries.append(seconds, _valueSetpoint) + valueSetpointSeries.append(_msecs, _valueSetpoint) adjustYAxisMin(_valueYAxis, _valueSetpoint) adjustYAxisMax(_valueYAxis, _valueSetpoint) - valueRateSeries.append(seconds, _valueRate) + valueRateSeries.append(_msecs, _valueRate) adjustYAxisMin(_valueRateYAxis, _valueRate) adjustYAxisMax(_valueRateYAxis, _valueRate) - valueRateSetpointSeries.append(seconds, _valueRateSetpoint) + valueRateSetpointSeries.append(_msecs, _valueRateSetpoint) adjustYAxisMin(_valueRateYAxis, _valueRateSetpoint) adjustYAxisMax(_valueRateYAxis, _valueRateSetpoint) _msecs += interval - /* - Testing with just start/stop for now. No time limit. - if (valueSeries.count > _maxPointCount) { - valueSeries.remove(0) - valueSetpointSeries.remove(0) - valueRateSeries.remove(0) - valueRateSetpointSeries.remove(0) - valueXAxis.min = valueSeries.at(0).x - valueRateXAxis.min = valueSeries.at(0).x - } - */ } property int _maxPointCount: 10000 / interval @@ -232,23 +225,23 @@ RowLayout { spacing: _margins Layout.alignment: Qt.AlignTop - QGCLabel { text: qsTr("Tuning Axis:") } + Column { + QGCLabel { text: qsTr("Tuning Axis:") } - RowLayout { - spacing: _margins + RowLayout { + spacing: _margins - Repeater { - model: tuneList - QGCRadioButton { - text: modelData - checked: _currentTuneType === modelData - onClicked: _currentTuneType = modelData + Repeater { + model: tuneList + QGCRadioButton { + text: modelData + checked: _currentTuneType === modelData + onClicked: _currentTuneType = modelData + } } } } - Item { width: 1; height: 1 } - QGCLabel { text: qsTr("Tuning Values:") } GridLayout { @@ -272,7 +265,10 @@ RowLayout { text: "-" onClicked: { var value = modelData.value - modelData.value -= value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value + var newValue = value - (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value) + if (newValue >= modelData.min) { + modelData.value = newValue + } } } } @@ -294,7 +290,10 @@ RowLayout { text: "+" onClicked: { var value = modelData.value - modelData.value += value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value + var newValue = value + (value * adjustPercentModel.get(adjustPercentCombo.currentIndex).value) + if (newValue <= modelData.max) { + modelData.value = newValue + } } } } @@ -314,26 +313,27 @@ RowLayout { } } } - Item { width: 1; height: 1 } - QGCLabel { text: qsTr("Clipboard Values:") } + Column { + QGCLabel { text: qsTr("Clipboard Values:") } - GridLayout { - rows: savedRepeater.model.length - flow: GridLayout.TopToBottom - rowSpacing: _margins - columnSpacing: _margins + GridLayout { + rows: savedRepeater.model.length + flow: GridLayout.TopToBottom + rowSpacing: 0 + columnSpacing: _margins - Repeater { - model: params[tuneList.indexOf(_currentTuneType)] + Repeater { + model: params[tuneList.indexOf(_currentTuneType)] - QGCLabel { text: modelData.name } - } + QGCLabel { text: modelData.name } + } - Repeater { - id: savedRepeater + Repeater { + id: savedRepeater - QGCLabel { text: modelData } + QGCLabel { text: modelData } + } } } @@ -365,7 +365,30 @@ RowLayout { QGCButton { text: dataTimer.running ? qsTr("Stop") : qsTr("Start") - onClicked: dataTimer.running = !dataTimer.running + onClicked: { + dataTimer.running = !dataTimer.running + if (autoModeChange.checked) { + activeVehicle.flightMode = dataTimer.running ? "Stabilized" : activeVehicle.pauseFlightMode + } + } + } + } + + QGCCheckBox { + id: autoModeChange + text: qsTr("Automatic Flight Mode Switching") + } + + Column { + visible: autoModeChange.checked + QGCLabel { + text: qsTr("Switches to 'Stabilized' when you click Start.") + font.pointSize: ScreenTools.smallFontPointSize + } + + QGCLabel { + text: qsTr("Switches to '%1' when you click Stop.").arg(activeVehicle.pauseFlightMode) + font.pointSize: ScreenTools.smallFontPointSize } } } diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 74ba8a9672d62b011261485e6b27e122c16b4ac1..fab58588246f8f8a0cf98208eea4700079bf5299 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -75,6 +75,7 @@ const char* Vehicle::_distanceToHomeFactName = "distanceToHome"; const char* Vehicle::_headingToHomeFactName = "headingToHome"; const char* Vehicle::_distanceToGCSFactName = "distanceToGCS"; const char* Vehicle::_hobbsFactName = "hobbs"; +const char* Vehicle::_throttlePctFactName = "throttlePct"; const char* Vehicle::_gpsFactGroupName = "gps"; const char* Vehicle::_battery1FactGroupName = "battery"; @@ -185,6 +186,8 @@ Vehicle::Vehicle(LinkInterface* link, , _lastAnnouncedLowBatteryPercent(100) , _priorityLinkCommanded(false) , _orbitActive(false) + , _pidTuningTelemetryMode(false) + , _pidTuningWaitingForRates(false) , _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) , _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) , _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) @@ -202,6 +205,7 @@ Vehicle::Vehicle(LinkInterface* link, , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) + , _throttlePctFact (0, _throttlePctFactName, FactMetaData::valueTypeUint16) , _gpsFactGroup(this) , _battery1FactGroup(this) , _battery2FactGroup(this) @@ -386,6 +390,8 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _uid(0) , _lastAnnouncedLowBatteryPercent(100) , _orbitActive(false) + , _pidTuningTelemetryMode(false) + , _pidTuningWaitingForRates(false) , _rollFact (0, _rollFactName, FactMetaData::valueTypeDouble) , _pitchFact (0, _pitchFactName, FactMetaData::valueTypeDouble) , _headingFact (0, _headingFactName, FactMetaData::valueTypeDouble) @@ -403,6 +409,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _headingToHomeFact (0, _headingToHomeFactName, FactMetaData::valueTypeDouble) , _distanceToGCSFact (0, _distanceToGCSFactName, FactMetaData::valueTypeDouble) , _hobbsFact (0, _hobbsFactName, FactMetaData::valueTypeString) + , _throttlePctFact (0, _throttlePctFactName, FactMetaData::valueTypeUint16) , _gpsFactGroup(this) , _battery1FactGroup(this) , _battery2FactGroup(this) @@ -476,6 +483,7 @@ void Vehicle::_commonInit(void) _addFact(&_distanceToHomeFact, _distanceToHomeFactName); _addFact(&_headingToHomeFact, _headingToHomeFactName); _addFact(&_distanceToGCSFact, _distanceToGCSFactName); + _addFact(&_throttlePctFact, _throttlePctFactName); _hobbsFact.setRawValue(QVariant(QString("0000:00:00"))); _addFact(&_hobbsFact, _hobbsFactName); @@ -518,6 +526,8 @@ void Vehicle::_commonInit(void) } } #endif + + _pidTuningMessages << MAVLINK_MSG_ID_ATTITUDE << MAVLINK_MSG_ID_ATTITUDE_TARGET; } Vehicle::~Vehicle() @@ -793,7 +803,9 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes case MAVLINK_MSG_ID_ORBIT_EXECUTION_STATUS: _handleOrbitExecutionStatus(message); break; - + case MAVLINK_MSG_ID_MESSAGE_INTERVAL: + _handleMessageInterval(message); + break; case MAVLINK_MSG_ID_PING: _handlePing(link, message); break; @@ -894,12 +906,16 @@ void Vehicle::_handleStatusText(mavlink_message_t& message, bool longVersion) if (longVersion) { b.resize(MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN+1); - mavlink_msg_statustext_long_get_text(&message, b.data()); - severity = mavlink_msg_statustext_long_get_severity(&message); + mavlink_statustext_long_t statustextLong; + mavlink_msg_statustext_long_decode(&message, &statustextLong); + strncpy(b.data(), statustextLong.text, MAVLINK_MSG_STATUSTEXT_LONG_FIELD_TEXT_LEN); + severity = statustextLong.severity; } else { b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); - mavlink_msg_statustext_get_text(&message, b.data()); - severity = mavlink_msg_statustext_get_severity(&message); + mavlink_statustext_t statustext; + mavlink_msg_statustext_decode(&message, &statustext); + strncpy(b.data(), statustext.text, MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN); + severity = statustext.severity; } b[b.length()-1] = '\0'; messageText = QString(b); @@ -3400,7 +3416,23 @@ QString Vehicle::firmwareVersionTypeString(void) const void Vehicle::rebootVehicle() { _autoDisconnect = true; - sendMavCommand(_defaultComponentId, MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN, true, 1.0f); + + mavlink_message_t msg; + mavlink_command_long_t cmd; + + memset(&cmd, 0, sizeof(cmd)); + cmd.target_system = _id; + cmd.target_component = _defaultComponentId; + cmd.command = MAV_CMD_PREFLIGHT_REBOOT_SHUTDOWN; + cmd.confirmation = 0; + cmd.param1 = 1; + cmd.param2 = cmd.param3 = cmd.param4 = cmd.param5 = cmd.param6 = cmd.param7 = 0; + mavlink_msg_command_long_encode_chan(_mavlink->getSystemId(), + _mavlink->getComponentId(), + priorityLink()->mavlinkChannel(), + &msg, + &cmd); + sendMessageOnLink(priorityLink(), msg); } void Vehicle::setSoloFirmware(bool soloFirmware) @@ -3858,6 +3890,74 @@ int Vehicle::versionCompare(int major, int minor, int patch) return _firmwarePlugin->versionCompare(this, major, minor, patch); } +void Vehicle::_handleMessageInterval(const mavlink_message_t& message) +{ + if (_pidTuningWaitingForRates) { + mavlink_message_interval_t messageInterval; + + mavlink_msg_message_interval_decode(&message, &messageInterval); + + int msgId = messageInterval.message_id; + if (_pidTuningMessages.contains(msgId)) { + _pidTuningMessageRatesUsecs[msgId] = messageInterval.interval_us; + } + + if (_pidTuningMessageRatesUsecs.count() == _pidTuningMessages.count()) { + // We have back all the rates we requested + _pidTuningWaitingForRates = false; + _pidTuningAdjustRates(true); + } + } +} + +void Vehicle::setPIDTuningTelemetryMode(bool pidTuning) +{ + if (pidTuning) { + if (!_pidTuningTelemetryMode) { + // First step is to get the current message rates before we adjust them + _pidTuningTelemetryMode = true; + _pidTuningWaitingForRates = true; + _pidTuningMessageRatesUsecs.clear(); + for (int telemetry: _pidTuningMessages) { + sendMavCommand(defaultComponentId(), + MAV_CMD_GET_MESSAGE_INTERVAL, + true, // show error + telemetry); + } + } + } else { + if (_pidTuningTelemetryMode) { + _pidTuningTelemetryMode = false; + if (_pidTuningWaitingForRates) { + // We never finished waiting for previous rates + _pidTuningWaitingForRates = false; + } else { + _pidTuningAdjustRates(false); + } + } + } +} + +void Vehicle::_pidTuningAdjustRates(bool setRatesForTuning) +{ + int requestedRate = (int)(1000000.0 / 30.0); // 30 Hz in usecs + + for (int telemetry: _pidTuningMessages) { + + if (requestedRate < _pidTuningMessageRatesUsecs[telemetry]) { + sendMavCommand(defaultComponentId(), + MAV_CMD_SET_MESSAGE_INTERVAL, + true, // show error + telemetry, + setRatesForTuning ? requestedRate : _pidTuningMessageRatesUsecs[telemetry]); + } + } + + setLiveUpdates(setRatesForTuning); + _setpointFactGroup.setLiveUpdates(setRatesForTuning); +} + + #if !defined(NO_ARDUPILOT_DIALECT) void Vehicle::flashBootloader(void) { diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index a71e6a552d8c04110ae33b25e595bd39e95c60a8..eb00e19faad6d1db473dae3854335d1e163ac2b3 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -667,6 +667,7 @@ public: Q_PROPERTY(Fact* headingToHome READ headingToHome CONSTANT) Q_PROPERTY(Fact* distanceToGCS READ distanceToGCS CONSTANT) Q_PROPERTY(Fact* hobbs READ hobbs CONSTANT) + Q_PROPERTY(Fact* throttlePct READ throttlePct CONSTANT) Q_PROPERTY(FactGroup* gps READ gpsFactGroup CONSTANT) Q_PROPERTY(FactGroup* battery READ battery1FactGroup CONSTANT) @@ -758,6 +759,8 @@ public: /// @param percent 0-no power, 100-full power Q_INVOKABLE void motorTest(int motor, int percent); + Q_INVOKABLE void setPIDTuningTelemetryMode(bool pidTuning); + #if !defined(NO_ARDUPILOT_DIALECT) Q_INVOKABLE void flashBootloader(void); #endif @@ -961,6 +964,7 @@ public: Fact* headingToHome (void) { return &_headingToHomeFact; } Fact* distanceToGCS (void) { return &_distanceToGCSFact; } Fact* hobbs (void) { return &_hobbsFact; } + Fact* throttlePct (void) { return &_throttlePctFact; } FactGroup* gpsFactGroup (void) { return &_gpsFactGroup; } FactGroup* battery1FactGroup (void) { return &_battery1FactGroup; } @@ -1265,6 +1269,7 @@ private: void _handleEstimatorStatus(mavlink_message_t& message); void _handleStatusText(mavlink_message_t& message, bool longVersion); void _handleOrbitExecutionStatus(const mavlink_message_t& message); + void _handleMessageInterval(const mavlink_message_t& message); // ArduPilot dialect messages #if !defined(NO_ARDUPILOT_DIALECT) void _handleCameraFeedback(const mavlink_message_t& message); @@ -1291,6 +1296,7 @@ private: void _setCapabilities(uint64_t capabilityBits); void _updateArmed(bool armed); bool _apmArmingNotRequired(void); + void _pidTuningAdjustRates(bool setRatesForTuning); int _id; ///< Mavlink system id int _defaultComponentId; @@ -1473,6 +1479,12 @@ private: QTimer _orbitTelemetryTimer; static const int _orbitTelemetryTimeoutMsecs = 3000; // No telemetry for this amount and orbit will go inactive + // PID Tuning telemetry mode + bool _pidTuningTelemetryMode; + bool _pidTuningWaitingForRates; + QList<int> _pidTuningMessages; + QMap<int, int> _pidTuningMessageRatesUsecs; + // FactGroup facts Fact _rollFact; @@ -1492,6 +1504,7 @@ private: Fact _headingToHomeFact; Fact _distanceToGCSFact; Fact _hobbsFact; + Fact _throttlePctFact; VehicleGPSFactGroup _gpsFactGroup; VehicleBatteryFactGroup _battery1FactGroup; @@ -1521,6 +1534,7 @@ private: static const char* _headingToHomeFactName; static const char* _distanceToGCSFactName; static const char* _hobbsFactName; + static const char* _throttlePctFactName; static const char* _gpsFactGroupName; static const char* _battery1FactGroupName; diff --git a/src/Vehicle/VehicleFact.json b/src/Vehicle/VehicleFact.json index 07233e5e30e43fe51c0bcb46b2037afbeadfde81..ce0b5d391e9f57a6b6b25602a12aced568df0b5c 100644 --- a/src/Vehicle/VehicleFact.json +++ b/src/Vehicle/VehicleFact.json @@ -114,5 +114,11 @@ "name": "hobbs", "shortDescription": "Hobbs Meter", "type": "string" +}, +{ + "name": "throttlePct", + "shortDescription": "Throttle %", + "type": "uint16", + "units": "%" } ] diff --git a/src/VehicleSetup/Bootloader.h b/src/VehicleSetup/Bootloader.h index a7b990bac0a239aa386f5092a36105cc7dd2f442..6132241e08c891905bc57c8712caa4daa6952b4e 100644 --- a/src/VehicleSetup/Bootloader.h +++ b/src/VehicleSetup/Bootloader.h @@ -75,7 +75,7 @@ public: static const int boardIDASCV1 = 65; ///< ASC V1 board, as from USB PID static const int boardIDCrazyflie2 = 12; ///< Crazyflie 2.0 board, as from USB PID static const int boardIDOmnibusF4SD = 42; ///< Omnibus F4 SD, as from USB PID - static const int boardIDNXPHliteV3 = 28; ///< NXPHliteV3 board, as from USB PID + static const int boardIDFMUK66V3 = 28; ///< FMUK66V3 board, as from USB PID /// Simulated board id for V3 which is a V2 board which supports larger flash space /// IMPORTANT: Make sure this id does not conflict with any newly added real board ids diff --git a/src/VehicleSetup/FirmwareUpgradeController.cc b/src/VehicleSetup/FirmwareUpgradeController.cc index e26a57e390da39787bfb3a7c1e1ce4858a8080f9..6d923b8edc723e5ea862e7b7577369e3c339b17f 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.cc +++ b/src/VehicleSetup/FirmwareUpgradeController.cc @@ -526,8 +526,8 @@ QHash<FirmwareUpgradeController::FirmwareIdentifier, QString>* FirmwareUpgradeCo case Bootloader::boardIDOmnibusF4SD: _rgFirmwareDynamic = _rgOmnibusF4SDFirmware; break; - case Bootloader::boardIDNXPHliteV3: - _rgFirmwareDynamic = _rgNXPHliteV3Firmware; + case Bootloader::boardIDFMUK66V3: + _rgFirmwareDynamic = _rgFMUK66V3Firmware; break; case Bootloader::boardID3DRRadio: _rgFirmwareDynamic = _rg3DRRadioFirmware; diff --git a/src/VehicleSetup/FirmwareUpgradeController.h b/src/VehicleSetup/FirmwareUpgradeController.h index 3aaed12733850f1ac4571ef0410a1d6b947a69c6..112117f7575e93012d18d2d72d4fca8f4287b1ac 100644 --- a/src/VehicleSetup/FirmwareUpgradeController.h +++ b/src/VehicleSetup/FirmwareUpgradeController.h @@ -212,7 +212,7 @@ private: QHash<FirmwareIdentifier, QString> _rgASCV1Firmware; QHash<FirmwareIdentifier, QString> _rgCrazyflie2Firmware; QHash<FirmwareIdentifier, QString> _rgOmnibusF4SDFirmware; - QHash<FirmwareIdentifier, QString> _rgNXPHliteV3Firmware; + QHash<FirmwareIdentifier, QString> _rgFMUK66V3Firmware; QHash<FirmwareIdentifier, QString> _rgPX4FLowFirmware; QHash<FirmwareIdentifier, QString> _rg3DRRadioFirmware; diff --git a/src/comm/LogReplayLink.cc b/src/comm/LogReplayLink.cc index a97a84b33b045c408bfba35fc6f895b95dadf921..579b45322e9d84da8ea2816f6d3d607160b06bfc 100644 --- a/src/comm/LogReplayLink.cc +++ b/src/comm/LogReplayLink.cc @@ -14,6 +14,7 @@ #include <QFileInfo> #include <QtEndian> +#include <QSignalSpy> const char* LogReplayLinkConfiguration::_logFilenameKey = "logFilename"; @@ -368,7 +369,7 @@ void LogReplayLink::_readNextLogEntry(void) timeToNextExecutionMSecs = desiredPacedTimeMSecs - currentTimeMSecs; } - emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000); + _signalCurrentLogTimeSecs(); // And schedule the next execution of this function. _readTickTimer.start(timeToNextExecutionMSecs); @@ -450,8 +451,12 @@ void LogReplayLink::_resetPlaybackToBeginning(void) void LogReplayLink::movePlayhead(int percentComplete) { if (isPlaying()) { - qWarning() << "Should not move playhead while playing, pause first"; - return; + _pauseOnThread(); + QSignalSpy waitForPause(this, SIGNAL(playbackPaused)); + waitForPause.wait(); + if (_readTickTimer.isActive()) { + return; + } } if (percentComplete < 0 || percentComplete > 100) { @@ -495,7 +500,8 @@ void LogReplayLink::movePlayhead(int percentComplete) // And scan until we reach the start of a MAVLink message. We make sure to record this timestamp for // smooth jumping around the file. _logCurrentTimeUSecs = _seekToNextMavlinkMessage(&dummy); - + _signalCurrentLogTimeSecs(); + // Now update the UI with our actual final position. newRelativeTimeUSecs = (float)(_logCurrentTimeUSecs - _logStartTimeUSecs); percentComplete = (newRelativeTimeUSecs / _logDurationUSecs) * 100; @@ -561,3 +567,8 @@ void LogReplayLink::_playbackError(void) _logFile.close(); emit playbackError(); } + +void LogReplayLink::_signalCurrentLogTimeSecs(void) +{ + emit currentLogTimeSecs((_logCurrentTimeUSecs - _logStartTimeUSecs) / 1000000); +} diff --git a/src/comm/LogReplayLink.h b/src/comm/LogReplayLink.h index 6f369b35f3ca1a20d6e8be1fce605a902d9b5644..fb5de6ee6abd74edca13dfbaf483cd84b3490c73 100644 --- a/src/comm/LogReplayLink.h +++ b/src/comm/LogReplayLink.h @@ -120,6 +120,7 @@ private: void _finishPlayback(void); void _playbackError(void); void _resetPlaybackToBeginning(void); + void _signalCurrentLogTimeSecs(void); // Virtuals from LinkInterface virtual bool _connect(void); diff --git a/src/comm/USBBoardInfo.json b/src/comm/USBBoardInfo.json index 079d001a55d3501e6220a64f73d435ba75f1c315..dabcef3254413bc92701846db1666b867e082b0b 100644 --- a/src/comm/USBBoardInfo.json +++ b/src/comm/USBBoardInfo.json @@ -19,7 +19,7 @@ { "vendorID": 9900, "productID": 65, "boardClass": "Pixhawk", "name": "ASC V1" }, { "vendorID": 9900, "productID": 22, "boardClass": "Pixhawk", "name": "Crazyflie 2" }, { "vendorID": 9900, "productID": 1, "boardClass": "Pixhawk", "name": "Omnibus F4 SD" }, - { "vendorID": 8137, "productID": 28, "boardClass": "Pixhawk", "name": "PX4 NXPHlite v3.x" }, + { "vendorID": 8137, "productID": 28, "boardClass": "Pixhawk", "name": "PX4 FMUK66 v3.x" }, { "vendorID": 1155, "productID": 22336, "boardClass": "Pixhawk", "name": "ArduPilot ChibiOS" }, { "vendorID": 4617, "productID": 22336, "boardClass": "Pixhawk", "name": "ArduPilot ChibiOS" }, diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc new file mode 100644 index 0000000000000000000000000000000000000000..6dc0e56f9521c91ba66d1e2f54aa96ce59d8a40f --- /dev/null +++ b/src/ui/MainWindow.cc @@ -0,0 +1,518 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + + +/** + * @file + * @brief Implementation of class MainWindow + * @author Lorenz Meier <mail@qgroundcontrol.org> + */ + +#include <QSettings> +#include <QNetworkInterface> +#include <QDebug> +#include <QTimer> +#include <QHostInfo> +#include <QQuickView> +#include <QDesktopWidget> +#include <QScreen> +#include <QDesktopServices> +#include <QDockWidget> +#include <QMenuBar> +#include <QDialog> + +#include "QGC.h" +#include "MAVLinkProtocol.h" +#include "MainWindow.h" +#include "AudioOutput.h" +#ifndef __mobile__ +#include "QGCMAVLinkLogPlayer.h" +#endif +#include "MAVLinkDecoder.h" +#include "QGCApplication.h" +#include "MultiVehicleManager.h" +#include "LogCompressor.h" +#include "UAS.h" +#include "QGCImageProvider.h" +#include "QGCCorePlugin.h" + +#ifndef __mobile__ +#include "Linecharts.h" +#include "QGCUASFileViewMulti.h" +#include "CustomCommandWidget.h" +#include "QGCDockWidget.h" +#include "HILDockWidget.h" +#include "AppMessages.h" +#endif + +#ifndef NO_SERIAL_LINK +#include "SerialLink.h" +#endif + +#ifdef UNITTEST_BUILD +#include "QmlControls/QmlTestWidget.h" +#endif + +/// The key under which the Main Window settings are saved +const char* MAIN_SETTINGS_GROUP = "QGC_MAINWINDOW"; + +#ifndef __mobile__ +enum DockWidgetTypes { + MAVLINK_INSPECTOR, + CUSTOM_COMMAND, + ONBOARD_FILES, + HIL_CONFIG, + ANALYZE +}; + +static const char *rgDockWidgetNames[] = { + "MAVLink Inspector", + "Custom Command", + "Onboard Files", + "HIL Config", + "Analyze" +}; + +#define ARRAY_SIZE(ARRAY) (sizeof(ARRAY) / sizeof(ARRAY[0])) + +static const char* _visibleWidgetsKey = "VisibleWidgets"; +#endif + +static MainWindow* _instance = nullptr; ///< @brief MainWindow singleton + +MainWindow* MainWindow::_create() +{ + new MainWindow(); + return _instance; +} + +MainWindow* MainWindow::instance(void) +{ + return _instance; +} + +void MainWindow::deleteInstance(void) +{ + delete this; +} + +/// @brief Private constructor for MainWindow. MainWindow singleton is only ever created +/// by MainWindow::_create method. Hence no other code should have access to +/// constructor. +MainWindow::MainWindow() + : _mavlinkDecoder (nullptr) + , _lowPowerMode (false) + , _showStatusBar (false) + , _mainQmlWidgetHolder (nullptr) + , _forceClose (false) +{ + _instance = this; + + //-- Load fonts + if(QFontDatabase::addApplicationFont(":/fonts/opensans") < 0) { + qWarning() << "Could not load /fonts/opensans font"; + } + if(QFontDatabase::addApplicationFont(":/fonts/opensans-demibold") < 0) { + qWarning() << "Could not load /fonts/opensans-demibold font"; + } + + // Qt 4/5 on Ubuntu does place the native menubar correctly so on Linux we revert back to in-window menu bar. +#ifdef Q_OS_LINUX + menuBar()->setNativeMenuBar(false); +#endif + // Setup user interface + loadSettings(); + emit initStatusChanged(tr("Setting up user interface"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); + + _ui.setupUi(this); + configureWindowName(); + + // Setup central widget with a layout to hold the views + _centralLayout = new QVBoxLayout(); + _centralLayout->setContentsMargins(0, 0, 0, 0); + centralWidget()->setLayout(_centralLayout); + + //-- Allow plugin to initialize main QML Widget + _mainQmlWidgetHolder = qgcApp()->toolbox()->corePlugin()->createMainQmlWidgetHolder(_centralLayout, this); + + // Image provider + QQuickImageProvider* pImgProvider = dynamic_cast<QQuickImageProvider*>(qgcApp()->toolbox()->imageProvider()); + _mainQmlWidgetHolder->getEngine()->addImageProvider(QStringLiteral("QGCImages"), pImgProvider); + + // Set dock options + setDockOptions(nullptr); + // Setup corners + setCorner(Qt::BottomRightCorner, Qt::BottomDockWidgetArea); + + // On Mobile devices, we don't want any main menus at all. +#ifdef __mobile__ + menuBar()->setNativeMenuBar(false); +#endif + +#ifdef UNITTEST_BUILD + QAction* qmlTestAction = new QAction("Test QML palette and controls", nullptr); + connect(qmlTestAction, &QAction::triggered, this, &MainWindow::_showQmlTestWidget); + _ui.menuWidgets->addAction(qmlTestAction); +#endif + + connect(qgcApp()->toolbox()->corePlugin(), &QGCCorePlugin::showAdvancedUIChanged, this, &MainWindow::_showAdvancedUIChanged); + _showAdvancedUIChanged(qgcApp()->toolbox()->corePlugin()->showAdvancedUI()); + + // Status Bar + setStatusBar(new QStatusBar(this)); + statusBar()->setSizeGripEnabled(true); + +#ifndef __mobile__ + emit initStatusChanged(tr("Building common widgets."), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); + _buildCommonWidgets(); + emit initStatusChanged(tr("Building common actions"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); +#endif + + // Create actions + connectCommonActions(); + + // Set low power mode + enableLowPowerMode(_lowPowerMode); + emit initStatusChanged(tr("Restoring last view state"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); + +#ifndef __mobile__ + + // Restore the window position and size + emit initStatusChanged(tr("Restoring last window size"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); + if (settings.contains(_getWindowGeometryKey())) + { + restoreGeometry(settings.value(_getWindowGeometryKey()).toByteArray()); + } + else + { + // Adjust the size + QScreen* scr = QApplication::primaryScreen(); + QSize scrSize = scr->availableSize(); + if (scrSize.width() <= 1280) + { + resize(scrSize.width(), scrSize.height()); + } + else + { + int w = scrSize.width() > 1600 ? 1600 : scrSize.width(); + int h = scrSize.height() > 800 ? 800 : scrSize.height(); + resize(w, h); + move((scrSize.width() - w) / 2, (scrSize.height() - h) / 2); + } + } +#endif + + connect(_ui.actionStatusBar, &QAction::triggered, this, &MainWindow::showStatusBarCallback); + + connect(&windowNameUpdateTimer, &QTimer::timeout, this, &MainWindow::configureWindowName); + windowNameUpdateTimer.start(15000); + emit initStatusChanged(tr("Done"), Qt::AlignLeft | Qt::AlignBottom, QColor(62, 93, 141)); + + if (!qgcApp()->runningUnitTests()) { + _ui.actionStatusBar->setChecked(_showStatusBar); + showStatusBarCallback(_showStatusBar); +#ifdef __mobile__ + menuBar()->hide(); +#endif + show(); + } + +#ifndef __mobile__ + _loadVisibleWidgetsSettings(); +#endif + //-- Enable message handler display of messages in main window + UASMessageHandler* msgHandler = qgcApp()->toolbox()->uasMessageHandler(); + if(msgHandler) { + msgHandler->showErrorsInToolbar(); + } +} + +MainWindow::~MainWindow() +{ + if (_mavlinkDecoder) { + // Enforce thread-safe shutdown of the mavlink decoder + _mavlinkDecoder->finish(); + _mavlinkDecoder->wait(1000); + _mavlinkDecoder->deleteLater(); + _mavlinkDecoder = nullptr; + } + + // This needs to happen before we get into the QWidget dtor + // otherwise the QML engine reads freed data and tries to + // destroy MainWindow a second time. + delete _mainQmlWidgetHolder; + _instance = nullptr; +} + +QString MainWindow::_getWindowGeometryKey() +{ + return "_geometry"; +} + +#ifndef __mobile__ +MAVLinkDecoder* MainWindow::_mavLinkDecoderInstance(void) +{ + if (!_mavlinkDecoder) { + _mavlinkDecoder = new MAVLinkDecoder(qgcApp()->toolbox()->mavlinkProtocol()); + connect(_mavlinkDecoder, &MAVLinkDecoder::valueChanged, this, &MainWindow::valueChanged); + } + + return _mavlinkDecoder; +} + +void MainWindow::_buildCommonWidgets(void) +{ + // Log player + // TODO: Make this optional with a preferences setting or under a "View" menu + logPlayer = new QGCMAVLinkLogPlayer(statusBar()); + statusBar()->addPermanentWidget(logPlayer, 1); + + // Populate widget menu + for (int i = 0, end = ARRAY_SIZE(rgDockWidgetNames); i < end; i++) { + + const char* pDockWidgetName = rgDockWidgetNames[i]; + + // Add to menu + QAction* action = new QAction(pDockWidgetName, this); + action->setCheckable(true); + action->setData(i); + connect(action, &QAction::triggered, this, &MainWindow::_showDockWidgetAction); + _ui.menuWidgets->addAction(action); + _mapName2Action[pDockWidgetName] = action; + } +} + +/// Shows or hides the specified dock widget, creating if necessary +void MainWindow::_showDockWidget(const QString& name, bool show) +{ + // Create the inner widget if we need to + if (!_mapName2DockWidget.contains(name)) { + if(!_createInnerDockWidget(name)) { + qWarning() << "Trying to load non existent widget:" << name; + return; + } + } + Q_ASSERT(_mapName2DockWidget.contains(name)); + QGCDockWidget* dockWidget = _mapName2DockWidget[name]; + Q_ASSERT(dockWidget); + dockWidget->setVisible(show); + Q_ASSERT(_mapName2Action.contains(name)); + _mapName2Action[name]->setChecked(show); +} + +/// Creates the specified inner dock widget and adds to the QDockWidget +bool MainWindow::_createInnerDockWidget(const QString& widgetName) +{ + QGCDockWidget* widget = nullptr; + QAction *action = _mapName2Action[widgetName]; + if(action) { + switch(action->data().toInt()) { + case MAVLINK_INSPECTOR: + widget = new QGCMAVLinkInspector(widgetName, action, qgcApp()->toolbox()->mavlinkProtocol(),this); + break; + case CUSTOM_COMMAND: + widget = new CustomCommandWidget(widgetName, action, this); + break; + case ONBOARD_FILES: + widget = new QGCUASFileViewMulti(widgetName, action, this); + break; + case HIL_CONFIG: + widget = new HILDockWidget(widgetName, action, this); + break; + case ANALYZE: + widget = new Linecharts(widgetName, action, _mavLinkDecoderInstance(), this); + break; + } + if(widget) { + _mapName2DockWidget[widgetName] = widget; + } + } + return widget != nullptr; +} + +void MainWindow::_hideAllDockWidgets(void) +{ + for(QGCDockWidget* dockWidget: _mapName2DockWidget) { + dockWidget->setVisible(false); + } +} + +void MainWindow::_showDockWidgetAction(bool show) +{ + QAction* action = qobject_cast<QAction*>(QObject::sender()); + Q_ASSERT(action); + _showDockWidget(rgDockWidgetNames[action->data().toInt()], show); +} +#endif + +void MainWindow::showStatusBarCallback(bool checked) +{ + _showStatusBar = checked; + checked ? statusBar()->show() : statusBar()->hide(); +} + +void MainWindow::_reallyClose(void) +{ + _forceClose = true; + close(); +} + +void MainWindow::closeEvent(QCloseEvent *event) +{ + if (!_forceClose) { + // Attempt close from within the root Qml item + qgcApp()->qmlAttemptWindowClose(); + event->ignore(); + return; + } + + // Should not be any active connections + if (qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()) { + qWarning() << "All links should be disconnected by now"; + } + + _storeCurrentViewState(); + storeSettings(); + + emit mainWindowClosed(); +} + +void MainWindow::loadSettings() +{ + // Why the screaming? + QSettings settings; + settings.beginGroup(MAIN_SETTINGS_GROUP); + _lowPowerMode = settings.value("LOW_POWER_MODE", _lowPowerMode).toBool(); + _showStatusBar = settings.value("SHOW_STATUSBAR", _showStatusBar).toBool(); + settings.endGroup(); +} + +void MainWindow::storeSettings() +{ + QSettings settings; + settings.beginGroup(MAIN_SETTINGS_GROUP); + settings.setValue("LOW_POWER_MODE", _lowPowerMode); + settings.setValue("SHOW_STATUSBAR", _showStatusBar); + settings.endGroup(); + settings.setValue(_getWindowGeometryKey(), saveGeometry()); + +#ifndef __mobile__ + _storeVisibleWidgetsSettings(); +#endif +} + +void MainWindow::configureWindowName() +{ + setWindowTitle(qApp->applicationName() + " " + qApp->applicationVersion()); +} + +/** +* @brief Create all actions associated to the main window +* +**/ +void MainWindow::connectCommonActions() +{ + // Connect internal actions + connect(qgcApp()->toolbox()->multiVehicleManager(), &MultiVehicleManager::vehicleAdded, this, &MainWindow::_vehicleAdded); + connect(this, &MainWindow::reallyClose, this, &MainWindow::_reallyClose, Qt::QueuedConnection); // Queued to allow closeEvent to fully unwind before _reallyClose is called +} + +void MainWindow::_openUrl(const QString& url, const QString& errorMessage) +{ + if(!QDesktopServices::openUrl(QUrl(url))) { + qgcApp()->showMessage(QString("Could not open information in browser: %1").arg(errorMessage)); + } +} + +void MainWindow::_vehicleAdded(Vehicle* vehicle) +{ + connect(vehicle->uas(), &UAS::valueChanged, this, &MainWindow::valueChanged); +} + +/// Stores the state of the toolbar, status bar and widgets associated with the current view +void MainWindow::_storeCurrentViewState(void) +{ +#ifndef __mobile__ + for(QGCDockWidget* dockWidget: _mapName2DockWidget) { + dockWidget->saveSettings(); + } +#endif + + settings.setValue(_getWindowGeometryKey(), saveGeometry()); +} + +/// @brief Saves the last used connection +void MainWindow::saveLastUsedConnection(const QString connection) +{ + QSettings settings; + QString key(MAIN_SETTINGS_GROUP); + key += "/LAST_CONNECTION"; + settings.setValue(key, connection); +} + +#ifdef UNITTEST_BUILD +void MainWindow::_showQmlTestWidget(void) +{ + new QmlTestWidget(); +} +#endif + +#ifndef __mobile__ +void MainWindow::_loadVisibleWidgetsSettings(void) +{ + QSettings settings; + + QString widgets = settings.value(_visibleWidgetsKey).toString(); + + if (!widgets.isEmpty()) { + QStringList nameList = widgets.split(","); + + for (const QString &name: nameList) { + _showDockWidget(name, true); + } + } +} + +void MainWindow::_storeVisibleWidgetsSettings(void) +{ + QString widgetNames; + bool firstWidget = true; + + for (const QString &name: _mapName2DockWidget.keys()) { + if (_mapName2DockWidget[name]->isVisible()) { + if (!firstWidget) { + widgetNames += ","; + } else { + firstWidget = false; + } + + widgetNames += name; + } + } + + QSettings settings; + + settings.setValue(_visibleWidgetsKey, widgetNames); +} +#endif + +QObject* MainWindow::rootQmlObject(void) +{ + return _mainQmlWidgetHolder ? _mainQmlWidgetHolder->getRootObject() : nullptr; +} + +void MainWindow::_showAdvancedUIChanged(bool advanced) +{ + if (advanced) { + menuBar()->addMenu(_ui.menuFile); + menuBar()->addMenu(_ui.menuWidgets); + } else { + menuBar()->clear(); + } +} diff --git a/src/ui/QGCMAVLinkLogPlayer.cc b/src/ui/QGCMAVLinkLogPlayer.cc index 6a7d83b6eefe3cb054a0463bdff7d206823a0cc7..e28824f361dd0d6d2ee9a7331383829e2bda27c2 100644 --- a/src/ui/QGCMAVLinkLogPlayer.cc +++ b/src/ui/QGCMAVLinkLogPlayer.cc @@ -142,7 +142,6 @@ void QGCMAVLinkLogPlayer::_playbackStarted(void) _enablePlaybackControls(true); _ui->playButton->setChecked(true); _ui->playButton->setIcon(QIcon(":/res/Pause")); - _ui->positionSlider->setEnabled(false); } /// Signalled from LogReplayLink when replay is paused @@ -150,7 +149,6 @@ void QGCMAVLinkLogPlayer::_playbackPaused(void) { _ui->playButton->setIcon(QIcon(":/res/Play")); _ui->playButton->setChecked(false); - _ui->positionSlider->setEnabled(true); } void QGCMAVLinkLogPlayer::_playbackPercentCompleteChanged(int percentComplete) diff --git a/src/ui/QGCMAVLinkLogPlayer.ui b/src/ui/QGCMAVLinkLogPlayer.ui index f80f6ac95533a8a71b45360e7c7eedfea3560d73..2253c908d1b3f10ecfbfdbf914d1a8bffb812650 100644 --- a/src/ui/QGCMAVLinkLogPlayer.ui +++ b/src/ui/QGCMAVLinkLogPlayer.ui @@ -75,7 +75,7 @@ <number>100</number> </property> <property name="tracking"> - <bool>false</bool> + <bool>true</bool> </property> <property name="orientation"> <enum>Qt::Horizontal</enum>