diff --git a/QGCSetup.pri b/QGCSetup.pri index c6bb37f6a1c3861f5f066cc0954d0bd254f0ac70..3afde80424ea4c0dcaa831df8aa46e0f900f33c7 100644 --- a/QGCSetup.pri +++ b/QGCSetup.pri @@ -99,6 +99,47 @@ WindowsBuild { } LinuxBuild { + QMAKE_POST_LINK += && mkdir -p $$DESTDIR/libs + + # QT_INSTALL_LIBS + QT_LIB_LIST = \ + libicudata.so.54 \ + libicui18n.so.54 \ + libicuuc.so.54 \ + libQt5Core.so.5 \ + libQt5DBus.so.5 \ + libQt5Gui.so.5 \ + libQt5Location.so.5 \ + libQt5Network.so.5 \ + libQt5OpenGL.so.5 \ + libQt5Positioning.so.5 \ + libQt5PrintSupport.so.5 \ + libQt5Qml.so.5 \ + libQt5Quick.so.5 \ + libQt5QuickWidgets.so.5 \ + libQt5SerialPort.so.5 \ + libQt5Svg.so.5 \ + libQt5Test.so.5 \ + libQt5Widgets.so.5 \ + libQt5XcbQpa.so.5 + + for(QT_LIB, QT_LIB_LIST) { + QMAKE_POST_LINK += && $$QMAKE_COPY --dereference $$[QT_INSTALL_LIBS]/$$QT_LIB $$DESTDIR/libs + } + + # QT_INSTALL_PLUGINS + QT_PLUGIN_LIST = \ + platforms \ + xcbglintegrations + + for(QT_PLUGIN, QT_PLUGIN_LIST) { + QMAKE_POST_LINK += && $$QMAKE_COPY --dereference --recursive $$[QT_INSTALL_PLUGINS]/$$QT_PLUGIN $$DESTDIR/libs + } + + # QT_INSTALL_QML + QMAKE_POST_LINK += && $$QMAKE_COPY --dereference --recursive $$[QT_INSTALL_QML] $$DESTDIR/libs + + # QGroundControl start script QMAKE_POST_LINK += && $$QMAKE_COPY $$BASEDIR/deploy/qgroundcontrol-start.sh $$DESTDIR } diff --git a/README.md b/README.md index 47b61adb4a7e2e0ccc69d713650d014efb285767..0601358b4ad0ecaf1e2a0fbd6d6f623bd19ab65d 100644 --- a/README.md +++ b/README.md @@ -22,7 +22,7 @@ Source code for QGroundControl is kept on GitHub: https://github.com/mavlink/qgr ``` git clone --recursive https://github.com/mavlink/qgroundcontrol.git ``` -Each time you pull new source to your repository you should run `git submodule update` to get the latest submodules as well. +Each time you pull new source to your repository you should run `git submodule update` to get the latest submodules as well. Since QGroundControl uses submodules, using the zip file for source download will not work. You must use git. ### Supported Builds QGroundControl builds are supported for OSX, Linux, Windows and Android. QGroundControl uses [Qt](http://www.qt.io) as it's cross-platform support library and uses [QtCreator](http://doc.qt.io/qtcreator/index.html) as it's default build environment. diff --git a/deploy/qgroundcontrol-start.sh b/deploy/qgroundcontrol-start.sh index 859626dc884319d359ddcb6dae4cb26a43ad7467..6cd22d28e582651681298189a433e008f89ddc85 100755 --- a/deploy/qgroundcontrol-start.sh +++ b/deploy/qgroundcontrol-start.sh @@ -1,6 +1,6 @@ #!/bin/sh -export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$HOME/Qt/5.5/gcc_64/lib -export QML_IMPORT_PATH=$HOME/Qt/5.5/gcc_64/qml/ -export QML2_IMPORT_PATH=$HOME/Qt/5.5/gcc_64/qml/ -export QT_QPA_PLATFORM_PLUGIN_PATH=$HOME/Qt/5.5/gcc_64/plugins/platforms/ +export LD_LIBRARY_PATH=`pwd`/libs:$LD_LIBRARY_PATH +export QML_IMPORT_PATH=`pwd`/libs/qml +export QML2_IMPORT_PATH=`pwd`/libs/qml +export QT_QPA_PLATFORM_PLUGIN_PATH=`pwd`/libs/platforms ./qgroundcontrol "$@" diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml index 1a6551e51caca5f8a8358407a8fda8b5827c5094..30529cc563c980020d89262d21fd60322e870c2a 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml @@ -21,17 +21,16 @@ ======================================================================*/ -import QtQuick 2.5 +import QtQuick 2.5 import QtQuick.Controls 1.2 -import QtQuick.Controls.Styles 1.2 -import QtQuick.Dialogs 1.2 +import QtQuick.Dialogs 1.2 -import QGroundControl.FactSystem 1.0 -import QGroundControl.FactControls 1.0 -import QGroundControl.Palette 1.0 -import QGroundControl.Controls 1.0 -import QGroundControl.Controllers 1.0 -import QGroundControl.ScreenTools 1.0 +import QGroundControl.FactSystem 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.Controllers 1.0 +import QGroundControl.ScreenTools 1.0 QGCView { id: qgcView @@ -39,34 +38,18 @@ QGCView { QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } - property real _minW: ScreenTools.defaultFontPixelWidth * 30 - property real _boxWidth: _minW - property real _boxSpace: ScreenTools.defaultFontPixelWidth - property Fact sysIdFact: controller.getParameterFact(-1, "FRAME") - - function computeDimensions() { - var sw = 0 - var rw = 0 - var idx = Math.floor(scroll.width / (_minW + ScreenTools.defaultFontPixelWidth)) - if(idx < 1) { - _boxWidth = scroll.width - _boxSpace = 0 - } else { - _boxSpace = 0 - if(idx > 1) { - _boxSpace = ScreenTools.defaultFontPixelWidth - sw = _boxSpace * (idx - 1) - } - rw = scroll.width - sw - _boxWidth = rw / idx - } - } + property real _margins: ScreenTools.defaultFontPixelWidth + property Fact _frame: controller.getParameterFact(-1, "FRAME") APMAirframeComponentController { id: controller factPanel: panel } + ExclusiveGroup { + id: airframeTypeExclusive + } + Component { id: applyRestartDialogComponent @@ -84,36 +67,35 @@ QGCView { } QGCLabel { - id: applyParamsText - anchors.top: parent.top - anchors.left: parent.left - anchors.right: parent.right - anchors.margins: _boxSpace - wrapMode: Text.WordWrap - text: "Select you drone to load the default parameters for it. " + id: applyParamsText + anchors.top: parent.top + anchors.left: parent.left + anchors.right: parent.right + anchors.margins: _margins + wrapMode: Text.WordWrap + text: "Select you drone to load the default parameters for it. " } Flow { - anchors.top : applyParamsText.bottom - anchors.left: parent.left - anchors.right: parent.right - anchors.bottom: parent.bottom - spacing : _boxSpace - layoutDirection: Qt.Vertical; - anchors.margins : _boxSpace + anchors.margins: _margins + anchors.top: applyParamsText.bottom + anchors.left: parent.left + anchors.right: parent.right + anchors.bottom: parent.bottom + spacing : _margins + layoutDirection: Qt.Vertical; + Repeater { - id : airframePicker - model : controller.currentAirframeType.airframes; + id: airframePicker + model: controller.currentAirframeType.airframes; delegate: QGCButton { - id: btnParams + id: btnParams width: parent.width / 2.1 height: (ScreenTools.defaultFontPixelHeight * 14) / 5 - text: controller.currentAirframeType.airframes[index].name; + text: controller.currentAirframeType.airframes[index].name; - onClicked : { - controller.currentAirframe = controller.currentAirframeType.airframes[index] - } + onClicked : controller.currentAirframe = controller.currentAirframeType.airframes[index] } } } @@ -124,12 +106,6 @@ QGCView { id: panel anchors.fill: parent - readonly property real spacerHeight: ScreenTools.defaultFontPixelHeight - - onWidthChanged: { - computeDimensions() - } - Item { id: helpApplyRow anchors.top: parent.top @@ -138,24 +114,25 @@ QGCView { height: Math.max(helpText.contentHeight, applyButton.height) QGCLabel { - id: helpText - width: parent.width - applyButton.width - 5 - text: qsTr("Please select your airframe type") - font.pixelSize: ScreenTools.mediumFontPixelSize - wrapMode: Text.WordWrap + id: helpText + anchors.rightMargin: _margins + anchors.left: parent.left + anchors.right: applyButton.right + text: "Please select your airframe type" + font.pixelSize: ScreenTools.mediumFontPixelSize + wrapMode: Text.WordWrap } QGCButton { id: applyButton anchors.right: parent.right - text: qsTr("Load common parameters") - - onClicked: showDialog(applyRestartDialogComponent, qsTr("Load common parameters"), 50, StandardButton.Close) + text: "Load common parameters" + onClicked: showDialog(applyRestartDialogComponent, "Load common parameters", qgcView.showDialogDefaultWidth, StandardButton.Close) } } Item { - id: lastSpacer + id: helpSpacer anchors.top: helpApplyRow.bottom height: parent.spacerHeight width: 10 @@ -163,90 +140,35 @@ QGCView { Flickable { id: scroll - anchors.top: lastSpacer.bottom - width: parent.width; - height: parent.height; - clip: true - boundsBehavior: Flickable.StopAtBounds - flickableDirection: Flickable.VerticalFlick - - onWidthChanged: { - computeDimensions() - } + anchors.top: helpSpacer.bottom + anchors.bottom: parent.bottom + anchors.left: parent.left + anchors.right: parent.right + contentHeight: frameColumn.height + contentWidth: frameColumn.width - Flow { - id: flowView - width: scroll.width - spacing: _boxSpace - ExclusiveGroup { - id: airframeTypeExclusive - } + + Column { + id: frameColumn + spacing: _margins Repeater { model: controller.airframeTypesModel - // Outer summary item rectangle - delegate : Rectangle { - id: airframeBackground - width: _boxWidth - height: ScreenTools.defaultFontPixelHeight * 14 - color: qgcPal.windowShade; - - readonly property real titleHeight: ScreenTools.defaultFontPixelHeight * 1.75 - readonly property real innerMargin: ScreenTools.defaultFontPixelWidth - - MouseArea { - anchors.fill: parent - onClicked: airframeCheckBox.checked = true; - } + QGCRadioButton { + text: object.name + checked: controller.currentAirframeType == object + exclusiveGroup: airframeTypeExclusive - Rectangle { - id: nameRect; - width: parent.width - height: parent.titleHeight - color: qgcPal.windowShadeDark - - QGCLabel { - anchors.fill: parent - color: qgcPal.buttonText - verticalAlignment: TextEdit.AlignVCenter - horizontalAlignment: TextEdit.AlignHCenter - text: object.name - } - } - - Image { - id: imageRect - anchors.topMargin: innerMargin - anchors.top: nameRect.bottom - width: parent.width * 0.75 - height: parent.height - nameRect.height - (innerMargin * 3) - fillMode: Image.PreserveAspectFit - smooth: true - mipmap: true - source: object.imageResource - anchors.horizontalCenter: parent.horizontalCenter - } - - QGCCheckBox { - id: airframeCheckBox - checked: object.type == sysIdFact.value - exclusiveGroup: airframeTypeExclusive - anchors.bottom: imageRect.bottom - anchors.right: parent.right - anchors.rightMargin: innerMargin - - onCheckedChanged: { - if (checked) { - controller.currentAirframeType = object - } - airframeBackground.color = checked ? qgcPal.buttonHighlight : qgcPal.windowShade; + onCheckedChanged: { + if (checked) { + controller.currentAirframeType = object } } } } } - } // Scroll View - summary boxes + } } // QGCViewPanel } // QGCView diff --git a/src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml b/src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml index bfa1fed7fbe67079ebb50ab9411a1b17a7e37385..8552c064342f92fc5ef7af127ae9b822ac67a5ae 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml +++ b/src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml @@ -1,7 +1,7 @@ 1 - + @@ -9,26 +9,26 @@ - + - + - + - + - + - + diff --git a/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml b/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml index 34c76beca06af5ad19b131fa9a801da52e661bd6..e6ad1414edc6f748baa48149a43787aac1d67020 100644 --- a/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml +++ b/src/AutoPilotPlugins/APM/APMFlightModesComponent.qml @@ -91,7 +91,7 @@ QGCView { QGCLabel { anchors.baseline: modeCombo.baseline text: "Flight Mode " + index + ":" - color: controller.activeFlightMode == index ? qgcPal.buttonHighlight : qgcPal.text + color: controller.activeFlightMode == index ? "yellow" : qgcPal.text } FactComboBox { @@ -149,7 +149,7 @@ QGCView { QGCLabel { anchors.baseline: optCombo.baseline text: "Channel option " + index + ":" - color: controller.channelOptionEnabled[modelData] ? qgcPal.buttonHighlight : qgcPal.text + color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text } FactComboBox { diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml index 4efc35791068205f9b45b53c1e3861b72c58e12f..37e33f39a1d3d0907fa9039e81204c7d31f6cf00 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.qml @@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.Controllers 1.0 QGCView { - id: rootQGCView + id: qgcView viewPanel: panel // Help text which is shown both in the status text area prior to pressing a cal button and in the @@ -157,7 +157,7 @@ QGCView { _postCalibrationDialogParams.push("COMPASS_OFS3_Z") } } - showDialog(postCalibrationDialogComponent, "Calibration complete", 50, StandardButton.Ok) + showDialog(postCalibrationDialogComponent, "Calibration complete", qgcView.showDialogDefaultWidth, StandardButton.Ok) } } @@ -362,7 +362,7 @@ QGCView { } else { preCalibrationDialogType = "compass" preCalibrationDialogHelp = compassHelp - showDialog(preCalibrationDialogComponent, "Calibrate Compass", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Compass", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } } @@ -376,7 +376,7 @@ QGCView { onClicked: { preCalibrationDialogType = "accel" preCalibrationDialogHelp = accelHelp - showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } QGCButton { diff --git a/src/AutoPilotPlugins/Common/RadioComponent.qml b/src/AutoPilotPlugins/Common/RadioComponent.qml index fe5a030afd3ec7ad27f71eba0d5517e055be275f..68eb9e5d1890d140245c93961b39ce939bc2e288 100644 --- a/src/AutoPilotPlugins/Common/RadioComponent.qml +++ b/src/AutoPilotPlugins/Common/RadioComponent.qml @@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.Controllers 1.0 QGCView { - id: rootQGCView + id: qgcView viewPanel: panel QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } @@ -51,7 +51,7 @@ QGCView { FIXME: Turned off for now, since it prevents binding. Need to restructure to allow binding and still check channel count if (controller.channelCount < controller.minChannelCount) { - showDialog(channelCountDialogComponent, dialogTitle, 50, 0) + showDialog(channelCountDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, 0) } else { hideDialog() } @@ -68,7 +68,7 @@ QGCView { Component.onCompleted: { controllerCompleted = true - if (rootQGCView.completedSignalled) { + if (qgcView.completedSignalled) { controllerAndViewReady = true controller.start() updateChannelCount() @@ -283,11 +283,11 @@ QGCView { id: rollLoader anchors.left: rollLabel.right anchors.right: parent.right - height: rootQGCView.defaultTextHeight + height: qgcView.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: rootQGCView.defaultTextWidth + property real defaultTextWidth: qgcView.defaultTextWidth property bool mapped: controller.rollChannelMapped property bool reversed: controller.rollChannelReversed } @@ -313,11 +313,11 @@ QGCView { id: pitchLoader anchors.left: pitchLabel.right anchors.right: parent.right - height: rootQGCView.defaultTextHeight + height: qgcView.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: rootQGCView.defaultTextWidth + property real defaultTextWidth: qgcView.defaultTextWidth property bool mapped: controller.pitchChannelMapped property bool reversed: controller.pitchChannelReversed } @@ -343,11 +343,11 @@ QGCView { id: yawLoader anchors.left: yawLabel.right anchors.right: parent.right - height: rootQGCView.defaultTextHeight + height: qgcView.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: rootQGCView.defaultTextWidth + property real defaultTextWidth: qgcView.defaultTextWidth property bool mapped: controller.yawChannelMapped property bool reversed: controller.yawChannelReversed } @@ -373,11 +373,11 @@ QGCView { id: throttleLoader anchors.left: throttleLabel.right anchors.right: parent.right - height: rootQGCView.defaultTextHeight + height: qgcView.defaultTextHeight width: 100 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: rootQGCView.defaultTextWidth + property real defaultTextWidth: qgcView.defaultTextWidth property bool mapped: controller.throttleChannelMapped property bool reversed: controller.throttleChannelReversed } @@ -418,7 +418,7 @@ QGCView { onClicked: { if (text == "Calibrate") { - showDialog(zeroTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel) + showDialog(zeroTrimsDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel) } else { controller.nextButtonClicked() } @@ -460,7 +460,7 @@ QGCView { showBorder: true text: "Spektrum Bind" - onClicked: showDialog(spektrumBindDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel) + onClicked: showDialog(spektrumBindDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel) } } @@ -468,7 +468,7 @@ QGCView { showBorder: true text: "Copy Trims" visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware - onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel) + onClicked: showDialog(copyTrimsDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel) } } // Column - Left Column @@ -552,11 +552,11 @@ QGCView { Loader { id: theLoader anchors.verticalCenter: channelLabel.verticalCenter - height: rootQGCView.defaultTextHeight + height: qgcView.defaultTextHeight width: 200 sourceComponent: channelMonitorDisplayComponent - property real defaultTextWidth: rootQGCView.defaultTextWidth + property real defaultTextWidth: qgcView.defaultTextWidth property bool mapped: true readonly property bool reversed: false } diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.cc b/src/AutoPilotPlugins/Common/RadioComponentController.cc index abf2e726b5e03fb8f4319e32f560ee24f5181acb..234abbc5ce9138fc312f6a7de25451f4e5216543 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.cc +++ b/src/AutoPilotPlugins/Common/RadioComponentController.cc @@ -120,6 +120,10 @@ RadioComponentController::RadioComponentController(void) : connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged); _loadSettings(); + + // APM Stack has a bug where some RC params are missing. We need to know what these are so we can skip them if missing + // instead of popping missing param warnings. + _apmPossibleMissingRCChannelParams << 9 << 11 << 12 << 13 << 14; _resetInternalCalibrationValues(); } @@ -704,17 +708,20 @@ void RadioComponentController::_resetInternalCalibrationValues(void) QVariant value; enum rcCalFunctions curFunction = rgFlightModeFunctions[i]; - bool ok; - int switchChannel = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[curFunction].parameterName)->rawValue().toInt(&ok); - Q_ASSERT(ok); + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[curFunction].parameterName); + if (paramFact) { + bool ok; + int switchChannel = paramFact->rawValue().toInt(&ok); + Q_ASSERT(ok); - // Parameter: 1-based channel, 0=not mapped - // _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped + // Parameter: 1-based channel, 0=not mapped + // _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped - if (switchChannel != 0) { - qCDebug(RadioComponentControllerLog) << "Reserving 0-based switch channel" << switchChannel - 1; - _rgFunctionChannelMapping[curFunction] = switchChannel - 1; - _rgChannelInfo[switchChannel - 1].function = curFunction; + if (switchChannel != 0) { + qCDebug(RadioComponentControllerLog) << "Reserving 0-based switch channel" << switchChannel - 1; + _rgFunctionChannelMapping[curFunction] = switchChannel - 1; + _rgChannelInfo[switchChannel - 1].function = curFunction; + } } } } @@ -747,20 +754,43 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) for (int i = 0; i < _chanMax(); ++i) { struct ChannelInfo* info = &_rgChannelInfo[i]; + + if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(i+1)) { + if (!parameterExists(FactSystem::defaultComponentId, minTpl.arg(i+1))) { + // Parameter is missing from this version of APM + info->rcTrim = 1500; + info->rcMin = 1100; + info->rcMax = 1900; + info->reversed = false; + continue; + } + } - info->rcTrim = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1)); + if (paramFact) { + info->rcTrim = paramFact->rawValue().toInt(&convertOk); + Q_ASSERT(convertOk); + } - info->rcMin = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1)); + if (paramFact) { + info->rcMin = paramFact->rawValue().toInt(&convertOk); + Q_ASSERT(convertOk); + } - info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1)); + if (paramFact) { + info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(&convertOk); + Q_ASSERT(convertOk); + } - float floatReversed = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->rawValue().toFloat(&convertOk); - Q_ASSERT(convertOk); - Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); - info->reversed = floatReversed == -1.0f; + paramFact = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1)); + if (paramFact) { + float floatReversed = paramFact->rawValue().toFloat(&convertOk); + Q_ASSERT(convertOk); + Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); + info->reversed = floatReversed == -1.0f; + } } for (int i=0; irawValue().toInt(&convertOk); - Q_ASSERT(convertOk); - - if (paramChannel != 0) { - _rgFunctionChannelMapping[i] = paramChannel - 1; - _rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i; + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName); + if (paramFact) { + paramChannel = paramFact->rawValue().toInt(&convertOk); + Q_ASSERT(convertOk); + + if (paramChannel != 0) { + _rgFunctionChannelMapping[i] = paramChannel - 1; + _rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i; + } } } } @@ -837,7 +870,9 @@ void RadioComponentController::_writeCalibration(void) { if (!_uas) return; - _uas->stopCalibration(); + if (_px4Vehicle()) { + _uas->stopCalibration(); + } _validateCalibration(); @@ -851,9 +886,23 @@ void RadioComponentController::_writeCalibration(void) struct ChannelInfo* info = &_rgChannelInfo[chan]; int oneBasedChannel = chan + 1; - getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setRawValue((float)info->rcTrim); - getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMin); - getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMax); + if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(chan+1) && !parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) { + // RC parameters for this channel are missing from this version of APM + continue; + } + + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel)); + if (paramFact) { + paramFact->setRawValue((float)info->rcTrim); + } + paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel)); + if (paramFact) { + paramFact->setRawValue((float)info->rcMin); + } + paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel)); + if (paramFact) { + paramFact->setRawValue((float)info->rcMax); + } // APM has a backwards interpretation of "reversed" on the Pitch control. So be careful. float reversedParamValue; @@ -862,7 +911,10 @@ void RadioComponentController::_writeCalibration(void) } else { reversedParamValue = info->reversed ? 1.0f : -1.0f; } - getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setRawValue(reversedParamValue); + paramFact = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel)); + if (paramFact) { + paramFact->setRawValue(reversedParamValue); + } } // Write function mapping parameters @@ -880,9 +932,12 @@ void RadioComponentController::_writeCalibration(void) if (paramName) { Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName); - if (paramFact->rawValue().toInt() != paramChannel) { + if (paramFact && paramFact->rawValue().toInt() != paramChannel) { functionMappingChanged = true; - getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName)->setRawValue(paramChannel); + paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName); + if (paramFact) { + paramFact->setRawValue(paramChannel); + } } } } @@ -911,7 +966,9 @@ void RadioComponentController::_startCalibration(void) _resetInternalCalibrationValues(); // Let the mav known we are starting calibration. This should turn off motors and so forth. - _uas->startCalibration(UASInterface::StartCalibrationRadio); + if (_px4Vehicle()) { + _uas->startCalibration(UASInterface::StartCalibrationRadio); + } _nextButton->setProperty("text", "Next"); _cancelButton->setEnabled(true); @@ -926,7 +983,9 @@ void RadioComponentController::_stopCalibration(void) _currentStep = -1; if (_uas) { - _uas->stopCalibration(); + if (_px4Vehicle()) { + _uas->stopCalibration(); + } _setInternalCalibrationValuesFromParameters(); } else { _resetInternalCalibrationValues(); diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.h b/src/AutoPilotPlugins/Common/RadioComponentController.h index 20a1f3ef6fe271a6c891f24906930fcd9b9519f5..21fdd0e7eaa3a92412f9dbc2a6e4dd15e3be1e9e 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.h +++ b/src/AutoPilotPlugins/Common/RadioComponentController.h @@ -300,6 +300,8 @@ private: static const int _chanMinimum = 5; ///< Minimum numner of channels required to run struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel + + QList _apmPossibleMissingRCChannelParams; ///< List of possible missing RC*_* params for APM stack enum rcCalStates _rcCalState; ///< Current calibration state int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.qml b/src/AutoPilotPlugins/PX4/AirframeComponent.qml index 0bff1ddd8bf4162db9b6cd7feb1ed1eabfa27cae..69c63f69944bd4306bd78ca9a0ead8a000147075 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.qml +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.qml @@ -67,7 +67,7 @@ QGCView { Component.onCompleted: { if (controller.showCustomConfigPanel) { - showDialog(customConfigDialogComponent, "Custom Airframe Config", 50, StandardButton.Reset) + showDialog(customConfigDialogComponent, "Custom Airframe Config", qgcView.showDialogDefaultWidth, StandardButton.Reset) } } } @@ -138,7 +138,7 @@ QGCView { anchors.right: parent.right text: "Apply and Restart" - onClicked: showDialog(applyRestartDialogComponent, "Apply and Restart", 50, StandardButton.Apply | StandardButton.Cancel) + onClicked: showDialog(applyRestartDialogComponent, "Apply and Restart", qgcView.showDialogDefaultWidth, StandardButton.Apply | StandardButton.Cancel) } } diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml index a4b643cbeade0f8948ebda85faa2145031e30bb0..d63a3edcfca7c7a0ad4e59df8d180d1287b3e96f 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml @@ -35,7 +35,7 @@ import QGroundControl.Controllers 1.0 import QGroundControl.ScreenTools 1.0 QGCView { - id: rootQGCView + id: qgcView viewPanel: panel readonly property int monitorThresholdCharWidth: 8 // Character width of Monitor and Threshold labels @@ -138,7 +138,7 @@ QGCView { onTriggered: { recalcModePositions() if (rcInMode.value == 1) { - showDialog(joystickEnabledDialogComponent, title, 50, 0) + showDialog(joystickEnabledDialogComponent, title, qgcView.showDialogDefaultWidth, 0) } } } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.qml b/src/AutoPilotPlugins/PX4/SensorsComponent.qml index 7fc5ac494828688857534ed7b7f6321f3efbc9e4..c6f74b77009d9e13c557b4cab6f64797b7649bc6 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.qml @@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0 import QGroundControl.Controllers 1.0 QGCView { - id: rootQGCView + id: qgcView viewPanel: panel // Help text which is shown both in the status text area prior to pressing a cal button and in the @@ -130,7 +130,7 @@ QGCView { onSetCompassRotations: { if (showCompass0Rot || showCompass1Rot || showCompass2Rot) { - showDialog(compassRotationDialogComponent, "Set Compass Rotation(s)", 50, StandardButton.Ok) + showDialog(compassRotationDialogComponent, "Set Compass Rotation(s)", qgcView.showDialogDefaultWidth, StandardButton.Ok) } } @@ -295,7 +295,7 @@ QGCView { onClicked: { preCalibrationDialogType = "compass" preCalibrationDialogHelp = compassHelp - showDialog(preCalibrationDialogComponent, "Calibrate Compass", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Compass", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } @@ -308,7 +308,7 @@ QGCView { onClicked: { preCalibrationDialogType = "gyro" preCalibrationDialogHelp = gyroHelp - showDialog(preCalibrationDialogComponent, "Calibrate Gyro", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Gyro", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } @@ -321,7 +321,7 @@ QGCView { onClicked: { preCalibrationDialogType = "accel" preCalibrationDialogHelp = accelHelp - showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } @@ -335,7 +335,7 @@ QGCView { onClicked: { preCalibrationDialogType = "level" preCalibrationDialogHelp = levelHelp - showDialog(preCalibrationDialogComponent, "Level Horizon", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Level Horizon", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } @@ -349,7 +349,7 @@ QGCView { onClicked: { preCalibrationDialogType = "airspeed" preCalibrationDialogHelp = airspeedHelp - showDialog(preCalibrationDialogComponent, "Calibrate Airspeed", 50, StandardButton.Cancel | StandardButton.Ok) + showDialog(preCalibrationDialogComponent, "Calibrate Airspeed", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok) } } diff --git a/src/FactSystem/FactControls/FactTextField.qml b/src/FactSystem/FactControls/FactTextField.qml index aa7050a0e2dda8868b29ee78a09e0d31b72150ba..e22416945ad26116f547c98c20f010b3d1a55d58 100644 --- a/src/FactSystem/FactControls/FactTextField.qml +++ b/src/FactSystem/FactControls/FactTextField.qml @@ -29,7 +29,7 @@ QGCTextField { fact.value = text } else { _validateString = text - qgcView.showDialog(editorDialogComponent, "Invalid Parameter Value", 50, StandardButton.Save) + qgcView.showDialog(editorDialogComponent, "Invalid Parameter Value", qgcView.showDialogDefaultWidth, StandardButton.Save) } } else { fact.value = text diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index e9be6b724f97c21ecd2510b08c5e56607962071f..3025b70399e2b3164d4f23b209ddb3a2b08c4e84 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -335,12 +335,18 @@ void ParameterLoader::_determineDefaultComponentId(void) // the set of parameters. Better than nothing! _defaultComponentId = -1; + int largestCompParamCount = 0; foreach(int componentId, _mapParameterName2Variant.keys()) { - if (_mapParameterName2Variant[componentId].count() > _defaultComponentId) { + int compParamCount = _mapParameterName2Variant[componentId].count(); + if (compParamCount > largestCompParamCount) { + largestCompParamCount = compParamCount; _defaultComponentId = componentId; } } - Q_ASSERT(_defaultComponentId != -1); + + if (_defaultComponentId == -1) { + qWarning() << "All parameters missing, unable to determine default componet id"; + } } } diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 37184ecb453f7b332e0aa5a7a74e32586da81b42..3471a773545bc3596b20d0e4adbf13f0ef93938a 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -28,6 +28,7 @@ #include "Generic/GenericFirmwarePlugin.h" #include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack #include "QGCMAVLink.h" +#include "QGCApplication.h" QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog") @@ -211,7 +212,7 @@ int APMFirmwarePlugin::manualControlReservedButtonCount(void) return -1; } -void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +void APMFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) { if (message->msgid == MAVLINK_MSG_ID_PARAM_VALUE) { mavlink_param_value_t paramValue; @@ -296,9 +297,6 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) mavlink_statustext_t statusText; mavlink_msg_statustext_decode(message, &statusText); - // APM user facing calibration messages come through as high severity, we need to parse them out - // and lower the severity on them so that they don't pop in the users face. - if (!_firmwareVersion.isValid() || statusText.severity < MAV_SEVERITY_NOTICE) { QByteArray b; b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); @@ -314,9 +312,42 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) // found version string _firmwareVersion = APMFirmwareVersion(messageText); _textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(_firmwareVersion); + + if (!_firmwareVersion.isBeta() && !_firmwareVersion.isDev()) { + int supportedMajorNumber = -1; + int supportedMinorNumber = -1; + + switch (vehicle->vehicleType()) { + case MAV_TYPE_FIXED_WING: + supportedMajorNumber = 3; + supportedMinorNumber = 4; + break; + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_SUBMARINE: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + supportedMajorNumber = 3; + supportedMinorNumber = 3; + break; + default: + break; + } + + if (supportedMajorNumber != -1) { + if (_firmwareVersion.majorNumber() < supportedMajorNumber || _firmwareVersion.minorNumber() < supportedMinorNumber) { + qgcApp()->showMessage(QString("QGroundControl fully supports Version %1.%2 and above. You are using a version prior to that. This combination is untested, you may run into unpredictable results.").arg(supportedMajorNumber).arg(supportedMinorNumber)); + } + } + } } } + // APM user facing calibration messages come through as high severity, we need to parse them out + // and lower the severity on them so that they don't pop in the users face. + if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) { _adjustCalibrationMessageSeverity(message); return; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 2e0ce6be125e038c614ab0af403d1720b7f30e04..775949927d4842c938bc2a688869bfb34da42fbb 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -86,7 +86,7 @@ public: virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual int manualControlReservedButtonCount(void); - virtual void adjustMavlinkMessage(mavlink_message_t* message); + virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index e6edfbc6853d656d1e4ab45012273a234508039c..7838dbdb991fc79102c65e27220062fdcf74f0ca 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -90,8 +90,9 @@ public: /// Called before any mavlink message is processed by Vehicle such taht the firmwre plugin /// can adjust any message characteristics. This is handy to adjust or differences in mavlink /// spec implementations such that the base code can remain mavlink generic. + /// @param vehicle Vehicle message came from /// @param message[in,out] Mavlink message to adjust if needed. - virtual void adjustMavlinkMessage(mavlink_message_t* message) = 0; + virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) = 0; /// Called when Vehicle is first created to send any necessary mavlink messages to the firmware. virtual void initializeVehicle(Vehicle* vehicle) = 0; diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index 7a6b17c5c4d3fb3dfdfbaf68c2f331cde7ae6491..b35fddc31734f24a2442449786fecec559d14c7c 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -90,8 +90,9 @@ int GenericFirmwarePlugin::manualControlReservedButtonCount(void) return -1; } -void GenericFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) { + Q_UNUSED(vehicle); Q_UNUSED(message); // Generic plugin does no message adjustment diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index bd17140beb9699019024365e9d22a2c7e7f7cd7f..d1b828459c4af34e5fab60b14fafac1d9a1cb10f 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -42,7 +42,7 @@ public: virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual int manualControlReservedButtonCount(void); - virtual void adjustMavlinkMessage(mavlink_message_t* message); + virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 7808b3c045471e944fa3af1430822d2dcd7fd613..b9b55570a6be242b2900d760f0bc657a957e3a0e 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -177,8 +177,9 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void) return 0; // 0 buttons reserved for rc switch simulation } -void PX4FirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) +void PX4FirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message) { + Q_UNUSED(vehicle); Q_UNUSED(message); // PX4 Flight Stack plugin does no message adjustment @@ -217,6 +218,8 @@ QList PX4FirmwarePlugin::supportedMissionCommands(void) << MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_NAV_ROI << MAV_CMD_DO_JUMP - << MAV_CMD_CONDITION_DELAY; + << MAV_CMD_CONDITION_DELAY + << MAV_CMD_DO_VTOL_TRANSITION + << MAV_CMD_DO_DIGICAM_CONTROL; return list; } diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 07825896d290dade8356dd351a6938ccaea2d6e2..4af5a1c01ffb175aeeb416334607a1051142b8e4 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -42,7 +42,7 @@ public: virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode); virtual int manualControlReservedButtonCount(void); - virtual void adjustMavlinkMessage(mavlink_message_t* message); + virtual void adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); diff --git a/src/MissionManager/MavCmdInfo.json b/src/MissionManager/MavCmdInfo.json index 8110e09171b9ce05304dbf9b4e1c3c0c93ab405b..c2c28512c562b388a6aa8c8de5f8bfef803b5845 100644 --- a/src/MissionManager/MavCmdInfo.json +++ b/src/MissionManager/MavCmdInfo.json @@ -553,7 +553,7 @@ { "id": 222, "rawName": "MAV_CMD_DO_GUIDED_LIMITS", - "friendlyName": "Exetrnal control limits", + "friendlyName": "External control limits", "description": "Set limits for external control", "param1": { "label": "Timeout:", @@ -588,7 +588,20 @@ { "id": 2500, "rawName": "MAV_CMD_VIDEO_START_CAPTURE", "friendlyName": "MAV_CMD_VIDEO_START_CAPTURE" }, { "id": 2501, "rawName": "MAV_CMD_VIDEO_STOP_CAPTURE", "friendlyName": "MAV_CMD_VIDEO_STOP_CAPTURE" }, { "id": 2800, "rawName": "MAV_CMD_PANORAMA_CREATE", "friendlyName": "MAV_CMD_PANORAMA_CREATE" }, - { "id": 3000, "rawName": "MAV_CMD_DO_VTOL_TRANSITION", "friendlyName": "MAV_CMD_DO_VTOL_TRANSITION" }, + { + "id": 3000, + "rawName": "MAV_CMD_DO_VTOL_TRANSITION", + "friendlyName": "VTOL Transition", + "description": "Perform flight mode transition", + "category": "Basic", + "param7": { + "label": "Mode:", + "default": 3, + "decimalPlaces": 0, + "enumStrings": "Hover Mode,Plane Mode", + "enumValues": "3,4" + } + }, { "id": 30001, "rawName": "MAV_CMD_PAYLOAD_PREPARE_DEPLOY", "friendlyName": "MAV_CMD_PAYLOAD_PREPARE_DEPLOY" }, { "id": 30002, "rawName": "MAV_CMD_PAYLOAD_CONTROL_DEPLOY", "friendlyName": "MAV_CMD_PAYLOAD_CONTROL_DEPLOY" } ] diff --git a/src/QGCDockWidget.cc b/src/QGCDockWidget.cc index b17cbc943399f010de9d401cf5ce8dea7d5468df..0adb405e62e11b847ea01efbf6946fce143e7191 100644 --- a/src/QGCDockWidget.cc +++ b/src/QGCDockWidget.cc @@ -36,7 +36,6 @@ QGCDockWidget::QGCDockWidget(const QString& title, QAction* action, QWidget* par if (action) { setWindowTitle(title); setWindowFlags(Qt::Tool); - loadSettings(); } } @@ -55,11 +54,11 @@ void QGCDockWidget::loadSettings(void) { if (_action) { QSettings settings; - settings.beginGroup(_settingsGroup); if (settings.contains(_title)) { restoreGeometry(settings.value(_title).toByteArray()); } + settings.endGroup(); } } @@ -67,8 +66,8 @@ void QGCDockWidget::saveSettings(void) { if (_action) { QSettings settings; - settings.beginGroup(_settingsGroup); settings.setValue(_title, saveGeometry()); + settings.endGroup(); } } diff --git a/src/QGCPalette.cc b/src/QGCPalette.cc index a01c916a7e74dd70946eb9da55c986605de316a9..73289a12bc455e38efa05f00070ef7ffc00ab685 100644 --- a/src/QGCPalette.cc +++ b/src/QGCPalette.cc @@ -49,7 +49,7 @@ QColor QGCPalette::_windowShadeDark[QGCPalette::_cThemes][QGCPalette::_cColorGro }; QColor QGCPalette::_text[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { - { QColor("#cccccc"), QColor("#000000") }, + { QColor("#9d9d9d"), QColor("#000000") }, { QColor(0x58, 0x58, 0x58), QColor(0xFF, 0xFF, 0xFF) } }; @@ -64,12 +64,12 @@ QColor QGCPalette::_button[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { }; QColor QGCPalette::_buttonText[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { - { QColor("#dedede"), QColor("#000000") }, + { QColor("#9d9d9d"), QColor("#000000") }, { QColor(0x2c, 0x2c, 0x2c), QColor(0xFF, 0xFF, 0xFF) }, }; QColor QGCPalette::_buttonHighlight[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { - { QColor("#e4e4e4"), QColor("#e4e4e4") }, + { QColor("#e4e4e4"), QColor("#91d1e4") }, { QColor(0x58, 0x58, 0x58), QColor(237, 235, 51) }, }; diff --git a/src/QmlControls/MissionItemEditor.qml b/src/QmlControls/MissionItemEditor.qml index 5fc35af6920c9806c8abd82296da5646ed400842..d4eb9c4bdeca49fe2304d8f8862ab9361719721b 100644 --- a/src/QmlControls/MissionItemEditor.qml +++ b/src/QmlControls/MissionItemEditor.qml @@ -95,7 +95,7 @@ Rectangle { MenuItem { text: "Delete all" - onTriggered: qgcView.showDialog(deleteAllPromptDialog, "Delete all", 40, StandardButton.Yes | StandardButton.No) + onTriggered: qgcView.showDialog(deleteAllPromptDialog, "Delete all", qgcView.showDialogDefaultWidth, StandardButton.Yes | StandardButton.No) } MenuSeparator { } @@ -139,7 +139,7 @@ Rectangle { } } - onClicked: qgcView.showDialog(commandDialog, "Select Mission Command", 40, StandardButton.Cancel) + onClicked: qgcView.showDialog(commandDialog, "Select Mission Command", qgcView.showDialogDefaultWidth, StandardButton.Cancel) } QGCLabel { diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index 0b0bb79dabab85f82e1393f83a69535cd1cb888a..25b3d8ba7698f9084ca16b0b1c643196c90782ac 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -119,7 +119,7 @@ QGCView { } MenuItem { text: "Search..." - onTriggered: showDialog(searchDialogComponent, "Parameter Search", 50, StandardButton.Reset | StandardButton.Apply) + onTriggered: showDialog(searchDialogComponent, "Parameter Search", panel.showDialogDefaultWidth, StandardButton.Reset | StandardButton.Apply) } MenuSeparator { visible: !ScreenTools.isMobile } MenuItem { @@ -290,7 +290,7 @@ QGCView { id: valueLabel width: ScreenTools.defaultFontPixelWidth * 20 color: factRow.modelFact.defaultValueAvailable ? (factRow.modelFact.valueEqualsDefault ? __qgcPal.text : __qgcPal.warningText) : __qgcPal.text - text: factRow.modelFact.valueString + " " + factRow.modelFact.units + text: factRow.modelFact.enumStrings.length == 0 ? factRow.modelFact.valueString + " " + factRow.modelFact.units : factRow.modelFact.enumStringValue } QGCLabel { text: factRow.modelFact.shortDescription @@ -314,7 +314,7 @@ QGCView { acceptedButtons: Qt.LeftButton onClicked: { __editorDialogFact = factRow.modelFact - showDialog(editorDialogComponent, "Parameter Editor", 50, StandardButton.Cancel | StandardButton.Save) + showDialog(editorDialogComponent, "Parameter Editor", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Save) } } } diff --git a/src/QmlControls/ParameterEditorDialog.qml b/src/QmlControls/ParameterEditorDialog.qml index c6622eeae23754ac046f1328a31da5478aa4efaf..56d95ebd6eed4b744f88c685351635a1403e52de 100644 --- a/src/QmlControls/ParameterEditorDialog.qml +++ b/src/QmlControls/ParameterEditorDialog.qml @@ -35,6 +35,8 @@ import QGroundControl.FactControls 1.0 import QGroundControl.ScreenTools 1.0 QGCViewDialog { + id: root + property Fact fact property bool validate: false property string validateValue @@ -42,14 +44,19 @@ QGCViewDialog { ParameterEditorController { id: controller; factPanel: parent } function accept() { - var errorString = fact.validate(valueField.text, forceSave.checked) - if (errorString == "") { - fact.value = valueField.text - fact.valueChanged(fact.value) + if (factCombo.visible) { + fact.enumIndex = factCombo.currentIndex hideDialog() } else { - validationError.text = errorString - forceSave.visible = true + var errorString = fact.validate(valueField.text, forceSave.checked) + if (errorString == "") { + fact.value = valueField.text + fact.valueChanged(fact.value) + hideDialog() + } else { + validationError.text = errorString + forceSave.visible = true + } } } @@ -80,14 +87,30 @@ QGCViewDialog { } QGCTextField { - id: valueField - text: validate ? validateValue : fact.valueString + id: valueField + text: validate ? validateValue : fact.valueString + visible: fact.enumStrings.length == 0 || validate //focus: true // At this point all Facts are numeric inputMethodHints: Qt.ImhFormattedNumbersOnly } + QGCComboBox { + id: factCombo + width: valueField.width + visible: fact.enumStrings.length != 0 && !validate + model: fact.enumStrings + + Component.onCompleted: { + // We can't bind directly to fact.enumIndex since that would add an unknown value + // if there are no enum strings. + if (visible) { + currentIndex = fact.enumIndex + } + } + } + QGCLabel { text: fact.name } Row { diff --git a/src/QmlControls/QGCView.qml b/src/QmlControls/QGCView.qml index 199456e991b6d3975956dfc36d86abe7e12058d6..432a629fbcfbc311414ff1c768e7bee2284d8f7d 100644 --- a/src/QmlControls/QGCView.qml +++ b/src/QmlControls/QGCView.qml @@ -128,8 +128,12 @@ FactPanel { /// Shows a QGCViewDialog component /// @param compoent QGCViewDialog component /// @param title Title for dialog - /// @param charWidth Width of dialog in characters (-1 for full parent width) + /// @param charWidth Width of dialog in characters /// @param buttons Buttons to show in dialog using StandardButton enum + + readonly property int showDialogFullWidth: -1 ///< Use for full width dialog + readonly property int showDialogDefaultWidth: 40 ///< Use for default dialog width + function showDialog(component, title, charWidth, buttons) { if (__checkForEarlyDialog(title)) { return @@ -158,7 +162,7 @@ FactPanel { __stopAllAnimations() - __dialogCharWidth = 50 + __dialogCharWidth = showDialogDefaultWidth __dialogTitle = title __messageDialogText = message @@ -285,7 +289,7 @@ FactPanel { // This is the main dialog panel which is anchored to the right edge Rectangle { id: __dialogPanel - width: __dialogCharWidth == -1 ? parent.width : defaultTextWidth * __dialogCharWidth + width: __dialogCharWidth == showDialogFullWidth ? parent.width : defaultTextWidth * __dialogCharWidth anchors.topMargin: topDialogMargin anchors.top: parent.top anchors.bottom: parent.bottom diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 9aa7a11012789c939f1e1b5d96c1d497301f4e73..caedb6bf7bda7d7c52383c4261a7f4cb93573f42 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -221,7 +221,7 @@ void Vehicle::_mavlinkMessageReceived(LinkInterface* link, mavlink_message_t mes } // Give the plugin a change to adjust the message contents - _firmwarePlugin->adjustMavlinkMessage(&message); + _firmwarePlugin->adjustMavlinkMessage(this, &message); switch (message.msgid) { case MAVLINK_MSG_ID_HOME_POSITION: @@ -442,7 +442,7 @@ void Vehicle::_sendMessage(mavlink_message_t message) MAVLinkProtocol* mavlink = _mavlink; // Give the plugin a chance to adjust - _firmwarePlugin->adjustMavlinkMessage(&message); + _firmwarePlugin->adjustMavlinkMessage(this, &message); static const uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]); diff --git a/src/VehicleSetup/FirmwareUpgrade.qml b/src/VehicleSetup/FirmwareUpgrade.qml index 11dc82a934db0d17aa22df095907c1f96a838c89..78f8bdff337bc30c41bdeac1451a7dc6e08393fa 100644 --- a/src/VehicleSetup/FirmwareUpgrade.qml +++ b/src/VehicleSetup/FirmwareUpgrade.qml @@ -109,7 +109,7 @@ QGCView { // We end up here when we detect a board plugged in after we've started upgrade statusTextArea.append(highlightPrefix + "Found device" + highlightSuffix + ": " + controller.boardType) if (controller.boardType == "Pixhawk" || controller.boardType == "AeroCore" || controller.boardType == "PX4 Flow" || controller.boardType == "PX4 FMU V1") { - showDialog(pixhawkFirmwareSelectDialog, title, 50, StandardButton.Ok | StandardButton.Cancel) + showDialog(pixhawkFirmwareSelectDialog, title, qgcView.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel) } } } diff --git a/src/ViewWidgets/LogDownload.cc b/src/ViewWidgets/LogDownload.cc index 8cce36288c57c0b3d3e1c052abb1ba638b249132..f30eee3dca92a6966dfbe918e40da60384e2dcb3 100644 --- a/src/ViewWidgets/LogDownload.cc +++ b/src/ViewWidgets/LogDownload.cc @@ -29,6 +29,5 @@ LogDownload::LogDownload(const QString& title, QAction* action, QWidget *parent) Q_UNUSED(title); Q_UNUSED(action); setSource(QUrl::fromUserInput("qrc:/qml/LogDownload.qml")); - loadSettings(); } diff --git a/src/ViewWidgets/LogDownloadController.cc b/src/ViewWidgets/LogDownloadController.cc index 127fab99e7e6c9a5833de8ee783d67ab7006c9d5..32af69413a8709357476251fdfad31a9b24a2198 100644 --- a/src/ViewWidgets/LogDownloadController.cc +++ b/src/ViewWidgets/LogDownloadController.cc @@ -113,21 +113,26 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t return; } //-- If this is the first, pre-fill it - if(!_logEntriesModel.count()) { + if(!_logEntriesModel.count() && num_logs > 0) { for(int i = 0; i < num_logs; i++) { QGCLogEntry *entry = new QGCLogEntry(i); _logEntriesModel.append(entry); } } //-- Update this log record - if(id < _logEntriesModel.count()) { - QGCLogEntry* entry = _logEntriesModel[id]; - entry->setSize(size); - entry->setTime(QDateTime::fromTime_t(time_utc)); - entry->setReceived(true); - entry->setStatus(QString("Available")); + if(num_logs > 0) { + if(id < _logEntriesModel.count()) { + QGCLogEntry* entry = _logEntriesModel[id]; + entry->setSize(size); + entry->setTime(QDateTime::fromTime_t(time_utc)); + entry->setReceived(true); + entry->setStatus(QString("Available")); + } else { + qWarning() << "Received log entry for out-of-bound index:" << id; + } } else { - qWarning() << "Received log entry for out-of-bound index:" << id; + //-- No logs to list + _receivedAllEntries(); } //-- Reset retry count _retries = 0; @@ -515,6 +520,7 @@ LogDownloadController::eraseAll(void) &msg, qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL); _vehicle->sendMessage(msg); + refresh(); } } diff --git a/src/ViewWidgets/LogDownloadController.h b/src/ViewWidgets/LogDownloadController.h index befd5bcb27ba0593f13cfdfb42706cedcd9f3d20..3c29836f6ac311c0458f42ddb510db14ee917f9a 100644 --- a/src/ViewWidgets/LogDownloadController.h +++ b/src/ViewWidgets/LogDownloadController.h @@ -34,10 +34,10 @@ #include "AutoPilotPlugin.h" #include "FactPanelController.h" -class MultiVehicleManager; -class UASInterface; -class Vehicle; -class QGCLogEntry; +class MultiVehicleManager; +class UASInterface; +class Vehicle; +class QGCLogEntry; class LogDownloadData; Q_DECLARE_LOGGING_CATEGORY(LogDownloadLog) diff --git a/src/comm/LinkInterface.h b/src/comm/LinkInterface.h index 0d093cfa6642335c01bf9afced6ef0f10581c180..b2b18d2e91f68b02f294b8effa0e55b8fa3bf160 100644 --- a/src/comm/LinkInterface.h +++ b/src/comm/LinkInterface.h @@ -131,10 +131,6 @@ public: /// set into the link when it is added to LinkManager uint8_t getMavlinkChannel(void) const { Q_ASSERT(_mavlinkChannelSet); return _mavlinkChannel; } - /// @return true: "sh /etc/init.d/rc.usb" must be sent on link to start mavlink - virtual bool requiresUSBMavlinkStart(void) const { return false; } - - // These are left unimplemented in order to cause linker errors which indicate incorrect usage of // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. bool connect(void); diff --git a/src/comm/LinkManager.cc b/src/comm/LinkManager.cc index 5f8bc4a291a2643bb570946a93aed866f2fbb414..a3a5b5d14e9101d5446c7529b1ab1e9d0443c481 100644 --- a/src/comm/LinkManager.cc +++ b/src/comm/LinkManager.cc @@ -189,8 +189,6 @@ void LinkManager::_addLink(LinkInterface* link) connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); - connect(link, &LinkInterface::connected, _mavlinkProtocol, &MAVLinkProtocol::linkConnected); - connect(link, &LinkInterface::disconnected, _mavlinkProtocol, &MAVLinkProtocol::linkDisconnected); _mavlinkProtocol->resetMetadataForLink(link); diff --git a/src/comm/MAVLinkProtocol.cc b/src/comm/MAVLinkProtocol.cc index 0ece393fa4a7bfba8e36a93b9dd9a960941df088..18f8602013dcb63e05ee44bd4aa6590870f44841 100644 --- a/src/comm/MAVLinkProtocol.cc +++ b/src/comm/MAVLinkProtocol.cc @@ -173,41 +173,6 @@ void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link) currLossCounter[channel] = 0; } -void MAVLinkProtocol::linkConnected(void) -{ - LinkInterface* link = qobject_cast(QObject::sender()); - Q_ASSERT(link); - - _linkStatusChanged(link, true); -} - -void MAVLinkProtocol::linkDisconnected(void) -{ - LinkInterface* link = qobject_cast(QObject::sender()); - Q_ASSERT(link); - - _linkStatusChanged(link, false); -} - -void MAVLinkProtocol::_linkStatusChanged(LinkInterface* link, bool connected) -{ - qCDebug(MAVLinkProtocolLog) << "_linkStatusChanged" << QString("%1").arg((long)link, 0, 16) << connected; - Q_ASSERT(link); - - if (connected) { - if (link->requiresUSBMavlinkStart()) { - // Send command to start MAVLink - // XXX hacky but safe - // Start NSH - const char init[] = {0x0d, 0x0d, 0x0d, 0x0d}; - link->writeBytes(init, sizeof(init)); - const char* cmd = "sh /etc/init.d/rc.usb\n"; - link->writeBytes(cmd, strlen(cmd)); - link->writeBytes(init, 4); - } - } -} - /** * This method parses all incoming bytes and constructs a MAVLink packet. * It can handle multiple links in parallel, as each link has it's own buffer/ diff --git a/src/comm/MAVLinkProtocol.h b/src/comm/MAVLinkProtocol.h index b24491ee6f5c47063fe8c43d608edf4ea4d72d89..c3de7bc1c4b7d235c629e4a65187c1f064ed6b33 100644 --- a/src/comm/MAVLinkProtocol.h +++ b/src/comm/MAVLinkProtocol.h @@ -155,9 +155,6 @@ public slots: /** @brief Receive bytes from a communication interface */ void receiveBytes(LinkInterface* link, QByteArray b); - void linkConnected(void); - void linkDisconnected(void); - /** @brief Set the rate at which heartbeats are emitted */ void setHeartbeatRate(int rate); /** @brief Set the system id of this application */ @@ -285,7 +282,6 @@ private slots: void _vehicleCountChanged(int count); private: - void _linkStatusChanged(LinkInterface* link, bool connected); void _sendMessage(mavlink_message_t message); void _sendMessage(LinkInterface* link, mavlink_message_t message); void _sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid); diff --git a/src/comm/SerialLink.cc b/src/comm/SerialLink.cc index 4f1b250874f3b9bee310137aa4d467c5d58e6cb4..b64be4932c7456d1ac6b8ea7c921685d6b964ec5 100644 --- a/src/comm/SerialLink.cc +++ b/src/comm/SerialLink.cc @@ -377,15 +377,6 @@ LinkConfiguration* SerialLink::getLinkConfiguration() return _config; } -bool SerialLink::requiresUSBMavlinkStart(void) const -{ - if (_port) { - return QGCSerialPortInfo(*_port).boardTypePixhawk(); - } else { - return false; - } -} - //-------------------------------------------------------------------------- //-- SerialConfiguration diff --git a/src/comm/SerialLink.h b/src/comm/SerialLink.h index 12b360103768058aa0a32a660fdc8cbbf403ba11..7f43d62aa28431cd2ed79dc28e2f046636c5c254 100644 --- a/src/comm/SerialLink.h +++ b/src/comm/SerialLink.h @@ -146,7 +146,6 @@ public: void requestReset(); bool isConnected() const; qint64 getConnectionSpeed() const; - bool requiresUSBMavlinkStart(void) const; // These are left unimplemented in order to cause linker errors which indicate incorrect usage of // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager. diff --git a/src/uas/UAS.cc b/src/uas/UAS.cc index 907ed64b18e537a82b7b0c92b8bf59259ecdc845..0dbfbb1469c86073f05bf324e75a815d0ce428b8 100644 --- a/src/uas/UAS.cc +++ b/src/uas/UAS.cc @@ -810,7 +810,8 @@ void UAS::receiveMessage(mavlink_message_t message) { case MAV_RESULT_ACCEPTED: { - emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_INFO, tr("SUCCESS: Executed CMD: %1").arg(ack.command)); + // Do not confirm each command positively, as it spams the console. + // emit textMessageReceived(uasId, message.compid, MAV_SEVERITY_INFO, tr("SUCCESS: Executed CMD: %1").arg(ack.command)); } break; case MAV_RESULT_TEMPORARILY_REJECTED: diff --git a/src/ui/MainWindow.cc b/src/ui/MainWindow.cc index 42080bd464914623292990de9ba054d654fbd679..df8b7bc2729f34ef859a5d2d31b134b720cf9711 100644 --- a/src/ui/MainWindow.cc +++ b/src/ui/MainWindow.cc @@ -332,56 +332,59 @@ void MainWindow::_showDockWidget(const QString& name, bool show) { // Create the inner widget if we need to if (!_mapName2DockWidget.contains(name)) { - _createInnerDockWidget(name); + if(!_createInnerDockWidget(name)) { + qWarning() << "Trying to load non existing 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 -void MainWindow::_createInnerDockWidget(const QString& widgetName) +bool MainWindow::_createInnerDockWidget(const QString& widgetName) { QGCDockWidget* widget = NULL; QAction *action = _mapName2Action[widgetName]; - - 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 LOG_DOWNLOAD: - widget = new LogDownload(widgetName, action, this); - break; - case STATUS_DETAILS: - widget = new UASInfoWidget(widgetName, action, this); - break; - case HIL_CONFIG: - widget = new HILDockWidget(widgetName, action, this); - break; - case ANALYZE: - widget = new Linecharts(widgetName, action, mavlinkDecoder, this); - break; - case INFO_VIEW: - widget= new QGCTabbedInfoView(widgetName, action, this); - break; - } - - if(action->data().toInt() == INFO_VIEW) { - qobject_cast(widget)->addSource(mavlinkDecoder); + 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 LOG_DOWNLOAD: + widget = new LogDownload(widgetName, action, this); + break; + case STATUS_DETAILS: + widget = new UASInfoWidget(widgetName, action, this); + break; + case HIL_CONFIG: + widget = new HILDockWidget(widgetName, action, this); + break; + case ANALYZE: + widget = new Linecharts(widgetName, action, mavlinkDecoder, this); + break; + case INFO_VIEW: + widget= new QGCTabbedInfoView(widgetName, action, this); + break; + } + if(action->data().toInt() == INFO_VIEW) { + qobject_cast(widget)->addSource(mavlinkDecoder); + } + if(widget) { + _mapName2DockWidget[widgetName] = widget; + } } - _mapName2DockWidget[widgetName] = widget; + return widget != NULL; } void MainWindow::_hideAllDockWidgets(void) diff --git a/src/ui/MainWindow.h b/src/ui/MainWindow.h index a6e02b72b66131748d345b29ca1554f6e95ee7ff..ca0d4ef2fcd83416019703ac6f266a59d849a245 100644 --- a/src/ui/MainWindow.h +++ b/src/ui/MainWindow.h @@ -221,7 +221,7 @@ private: void _loadCurrentViewState(void); #ifndef __mobile__ - void _createInnerDockWidget(const QString& widgetName); + bool _createInnerDockWidget(const QString& widgetName); void _buildCommonWidgets(void); void _hideAllDockWidgets(void); void _showDockWidget(const QString &name, bool show);