Browse Source

Merge remote-tracking branch 'MavLink/master' into logHandling

* MavLink/master:
  Warn on unsupported APM version
  APM stack does not support RC cal start/stop
  Harden code for missing params, handle APM special case
  Fix default comp id detection
  PX4 Firmware no longer requires mavlink USB start
  Standard sizing for QGCView::showDialog
  Standard sizing for QGCView::showDialog
  UAS Object: Avoid spamming the console on successful commands
  linux include required libraries
  Show enumStringValue if available
  Use combo box if enums available
  Set proper default mode for VTOL
  Teach mission manager about transition command
  Support camera and VTOL transition commands
  Better light disabled text color
  Add better button highlight color for light theme
  Change selected flight mode color
  Update README.md
  Simplifying Airframe config
  Fixing crash bug.

Conflicts:
	src/ui/MainWindow.cc
QGC4.4
dogmaphobic 9 years ago
parent
commit
d18a6b85f4
  1. 41
      QGCSetup.pri
  2. 2
      README.md
  3. 8
      deploy/qgroundcontrol-start.sh
  4. 202
      src/AutoPilotPlugins/APM/APMAirframeComponent.qml
  5. 14
      src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml
  6. 4
      src/AutoPilotPlugins/APM/APMFlightModesComponent.qml
  7. 8
      src/AutoPilotPlugins/APM/APMSensorsComponent.qml
  8. 32
      src/AutoPilotPlugins/Common/RadioComponent.qml
  9. 127
      src/AutoPilotPlugins/Common/RadioComponentController.cc
  10. 2
      src/AutoPilotPlugins/Common/RadioComponentController.h
  11. 4
      src/AutoPilotPlugins/PX4/AirframeComponent.qml
  12. 4
      src/AutoPilotPlugins/PX4/FlightModesComponent.qml
  13. 14
      src/AutoPilotPlugins/PX4/SensorsComponent.qml
  14. 2
      src/FactSystem/FactControls/FactTextField.qml
  15. 10
      src/FactSystem/ParameterLoader.cc
  16. 39
      src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
  17. 2
      src/FirmwarePlugin/APM/APMFirmwarePlugin.h
  18. 3
      src/FirmwarePlugin/FirmwarePlugin.h
  19. 3
      src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc
  20. 2
      src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h
  21. 7
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc
  22. 2
      src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h
  23. 17
      src/MissionManager/MavCmdInfo.json
  24. 5
      src/QGCDockWidget.cc
  25. 6
      src/QGCPalette.cc
  26. 4
      src/QmlControls/MissionItemEditor.qml
  27. 6
      src/QmlControls/ParameterEditor.qml
  28. 39
      src/QmlControls/ParameterEditorDialog.qml
  29. 10
      src/QmlControls/QGCView.qml
  30. 4
      src/Vehicle/Vehicle.cc
  31. 2
      src/VehicleSetup/FirmwareUpgrade.qml
  32. 1
      src/ViewWidgets/LogDownload.cc
  33. 22
      src/ViewWidgets/LogDownloadController.cc
  34. 8
      src/ViewWidgets/LogDownloadController.h
  35. 4
      src/comm/LinkInterface.h
  36. 2
      src/comm/LinkManager.cc
  37. 35
      src/comm/MAVLinkProtocol.cc
  38. 4
      src/comm/MAVLinkProtocol.h
  39. 9
      src/comm/SerialLink.cc
  40. 1
      src/comm/SerialLink.h
  41. 3
      src/uas/UAS.cc
  42. 75
      src/ui/MainWindow.cc
  43. 2
      src/ui/MainWindow.h

41
QGCSetup.pri

@ -99,6 +99,47 @@ WindowsBuild {
} }
LinuxBuild { 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 QMAKE_POST_LINK += && $$QMAKE_COPY $$BASEDIR/deploy/qgroundcontrol-start.sh $$DESTDIR
} }

2
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 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 ### 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. 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.

8
deploy/qgroundcontrol-start.sh

@ -1,6 +1,6 @@
#!/bin/sh #!/bin/sh
export LD_LIBRARY_PATH=$LD_LIBRARY_PATH:$HOME/Qt/5.5/gcc_64/lib export LD_LIBRARY_PATH=`pwd`/libs:$LD_LIBRARY_PATH
export QML_IMPORT_PATH=$HOME/Qt/5.5/gcc_64/qml/ export QML_IMPORT_PATH=`pwd`/libs/qml
export QML2_IMPORT_PATH=$HOME/Qt/5.5/gcc_64/qml/ export QML2_IMPORT_PATH=`pwd`/libs/qml
export QT_QPA_PLATFORM_PLUGIN_PATH=$HOME/Qt/5.5/gcc_64/plugins/platforms/ export QT_QPA_PLATFORM_PLUGIN_PATH=`pwd`/libs/platforms
./qgroundcontrol "$@" ./qgroundcontrol "$@"

202
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 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.FactSystem 1.0
import QGroundControl.FactControls 1.0 import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
QGCView { QGCView {
id: qgcView id: qgcView
@ -39,34 +38,18 @@ QGCView {
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
property real _minW: ScreenTools.defaultFontPixelWidth * 30 property real _margins: ScreenTools.defaultFontPixelWidth
property real _boxWidth: _minW property Fact _frame: controller.getParameterFact(-1, "FRAME")
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
}
}
APMAirframeComponentController { APMAirframeComponentController {
id: controller id: controller
factPanel: panel factPanel: panel
} }
ExclusiveGroup {
id: airframeTypeExclusive
}
Component { Component {
id: applyRestartDialogComponent id: applyRestartDialogComponent
@ -84,36 +67,35 @@ QGCView {
} }
QGCLabel { QGCLabel {
id: applyParamsText id: applyParamsText
anchors.top: parent.top anchors.top: parent.top
anchors.left: parent.left anchors.left: parent.left
anchors.right: parent.right anchors.right: parent.right
anchors.margins: _boxSpace anchors.margins: _margins
wrapMode: Text.WordWrap wrapMode: Text.WordWrap
text: "Select you drone to load the default parameters for it. " text: "Select you drone to load the default parameters for it. "
} }
Flow { Flow {
anchors.top : applyParamsText.bottom anchors.margins: _margins
anchors.left: parent.left anchors.top: applyParamsText.bottom
anchors.right: parent.right anchors.left: parent.left
anchors.bottom: parent.bottom anchors.right: parent.right
spacing : _boxSpace anchors.bottom: parent.bottom
layoutDirection: Qt.Vertical; spacing : _margins
anchors.margins : _boxSpace layoutDirection: Qt.Vertical;
Repeater { Repeater {
id : airframePicker id: airframePicker
model : controller.currentAirframeType.airframes; model: controller.currentAirframeType.airframes;
delegate: QGCButton { delegate: QGCButton {
id: btnParams id: btnParams
width: parent.width / 2.1 width: parent.width / 2.1
height: (ScreenTools.defaultFontPixelHeight * 14) / 5 height: (ScreenTools.defaultFontPixelHeight * 14) / 5
text: controller.currentAirframeType.airframes[index].name; text: controller.currentAirframeType.airframes[index].name;
onClicked : { onClicked : controller.currentAirframe = controller.currentAirframeType.airframes[index]
controller.currentAirframe = controller.currentAirframeType.airframes[index]
}
} }
} }
} }
@ -124,12 +106,6 @@ QGCView {
id: panel id: panel
anchors.fill: parent anchors.fill: parent
readonly property real spacerHeight: ScreenTools.defaultFontPixelHeight
onWidthChanged: {
computeDimensions()
}
Item { Item {
id: helpApplyRow id: helpApplyRow
anchors.top: parent.top anchors.top: parent.top
@ -138,24 +114,25 @@ QGCView {
height: Math.max(helpText.contentHeight, applyButton.height) height: Math.max(helpText.contentHeight, applyButton.height)
QGCLabel { QGCLabel {
id: helpText id: helpText
width: parent.width - applyButton.width - 5 anchors.rightMargin: _margins
text: qsTr("Please select your airframe type") anchors.left: parent.left
font.pixelSize: ScreenTools.mediumFontPixelSize anchors.right: applyButton.right
wrapMode: Text.WordWrap text: "Please select your airframe type"
font.pixelSize: ScreenTools.mediumFontPixelSize
wrapMode: Text.WordWrap
} }
QGCButton { QGCButton {
id: applyButton id: applyButton
anchors.right: parent.right anchors.right: parent.right
text: qsTr("Load common parameters") text: "Load common parameters"
onClicked: showDialog(applyRestartDialogComponent, "Load common parameters", qgcView.showDialogDefaultWidth, StandardButton.Close)
onClicked: showDialog(applyRestartDialogComponent, qsTr("Load common parameters"), 50, StandardButton.Close)
} }
} }
Item { Item {
id: lastSpacer id: helpSpacer
anchors.top: helpApplyRow.bottom anchors.top: helpApplyRow.bottom
height: parent.spacerHeight height: parent.spacerHeight
width: 10 width: 10
@ -163,90 +140,35 @@ QGCView {
Flickable { Flickable {
id: scroll id: scroll
anchors.top: lastSpacer.bottom anchors.top: helpSpacer.bottom
width: parent.width; anchors.bottom: parent.bottom
height: parent.height; anchors.left: parent.left
clip: true anchors.right: parent.right
boundsBehavior: Flickable.StopAtBounds contentHeight: frameColumn.height
flickableDirection: Flickable.VerticalFlick contentWidth: frameColumn.width
onWidthChanged: {
computeDimensions()
}
Flow {
id: flowView
width: scroll.width
spacing: _boxSpace
ExclusiveGroup {
id: airframeTypeExclusive Column {
} id: frameColumn
spacing: _margins
Repeater { Repeater {
model: controller.airframeTypesModel model: controller.airframeTypesModel
// Outer summary item rectangle QGCRadioButton {
delegate : Rectangle { text: object.name
id: airframeBackground checked: controller.currentAirframeType == object
width: _boxWidth exclusiveGroup: airframeTypeExclusive
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;
}
Rectangle { onCheckedChanged: {
id: nameRect; if (checked) {
width: parent.width controller.currentAirframeType = object
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;
} }
} }
} }
} }
} }
} // Scroll View - summary boxes }
} // QGCViewPanel } // QGCViewPanel
} // QGCView } // QGCView

14
src/AutoPilotPlugins/APM/APMAirframeFactMetaData.xml

@ -1,7 +1,7 @@
<?xml version='1.0' encoding='UTF-8'?> <?xml version='1.0' encoding='UTF-8'?>
<airframes> <airframes>
<version>1</version> <version>1</version>
<airframe_group image="AirframeQuadRotorPlus.png" name="Plus Frame" id="0"> <airframe_group image="AirframeQuadRotorPlus.png" name="Plus Style: Quad, Hexa, Octo, Heli" id="0">
<airframe name="3DR Aero M" file="3DR_AERO_M.param"/> <airframe name="3DR Aero M" file="3DR_AERO_M.param"/>
<airframe name="3DR Aero RTF" file="3DR_Aero_RTF.param"/> <airframe name="3DR Aero RTF" file="3DR_Aero_RTF.param"/>
<airframe name="3DR Rover" file="3DR_Rover.param"/> <airframe name="3DR Rover" file="3DR_Rover.param"/>
@ -9,26 +9,26 @@
<airframe name="Parrot Bebop" file="Parrot_Bebop.param"/> <airframe name="Parrot Bebop" file="Parrot_Bebop.param"/>
<airframe name="Storm32" file="SToRM32-MAVLink.param"/> <airframe name="Storm32" file="SToRM32-MAVLink.param"/>
</airframe_group> </airframe_group>
<airframe_group image="AirframeQuadRotorX.png" name="X Frame, Y6A Frame" id="1"> <airframe_group image="AirframeQuadRotorX.png" name="X Style, Y6A Style: Quad, Hexa, Octo, X8, Tri, Y6A" id="1">
<airframe name="3DR X8-M RTF" file="3DR_X8-M_RTF.param"/> <airframe name="3DR X8-M RTF" file="3DR_X8-M_RTF.param"/>
<airframe name="3DR Y6A" file="3DR_Y6A_RTF.param"/> <airframe name="3DR Y6A" file="3DR_Y6A_RTF.param"/>
<airframe name="3DR X8+ RTF" file="3DR_X8+_RTF.param"/> <airframe name="3DR X8+ RTF" file="3DR_X8+_RTF.param"/>
<airframe name="3DR QUAD X4 RTF" file="3DR_QUAD_X4_RTF.param"/> <airframe name="3DR QUAD X4 RTF" file="3DR_QUAD_X4_RTF.param"/>
<airframe name="3DR X8" file="3DR_X8_RTF.param"/> <airframe name="3DR X8" file="3DR_X8_RTF.param"/>
</airframe_group> </airframe_group>
<airframe_group image="AirframeQuadRotorH.png" name="V Frame (3DR Iris)" id="2"> <airframe_group image="AirframeQuadRotorH.png" name="V (3DR Iris)" id="2">
<airframe name="Iris with GoPro" file="Iris with Front Mount Go Pro.param"/> <airframe name="Iris with GoPro" file="Iris with Front Mount Go Pro.param"/>
<airframe name="Iris with Tarot" file="Iris with Tarot Gimbal.param"/> <airframe name="Iris with Tarot" file="Iris with Tarot Gimbal.param"/>
<airframe name="3DR Iris+" file="3DR_Iris+.param"/> <airframe name="3DR Iris+" file="3DR_Iris+.param"/>
<airframe name="Iris" file="Iris.param"/> <airframe name="Iris" file="Iris.param"/>
</airframe_group> </airframe_group>
<airframe_group image="AirframeQuadRotorH.png" name="V Tail Frame" id="4"> <airframe_group image="AirframeQuadRotorH.png" name="V Tail" id="4">
</airframe_group> </airframe_group>
<airframe_group image="AirframeQuadRotorH.png" name="A Tail Frame" id="5"> <airframe_group image="AirframeQuadRotorH.png" name="A Tail" id="5">
</airframe_group> </airframe_group>
<airframe_group name="H Frame" id="3"> <airframe_group name="H: X and H differ in prop rotation" id="3">
</airframe_group> </airframe_group>
<airframe_group name="Y6B Frame (3DR TriCopter)" id="10"> <airframe_group name="Y6B Frame (3DR TriCopter): Y6B and Y6A differ in prop rotation" id="10">
<airframe name="3DR Y6B" file="3DR_Y6B_RTF.param"/> <airframe name="3DR Y6B" file="3DR_Y6B_RTF.param"/>
</airframe_group> </airframe_group>
<airframes> <airframes>

4
src/AutoPilotPlugins/APM/APMFlightModesComponent.qml

@ -91,7 +91,7 @@ QGCView {
QGCLabel { QGCLabel {
anchors.baseline: modeCombo.baseline anchors.baseline: modeCombo.baseline
text: "Flight Mode " + index + ":" text: "Flight Mode " + index + ":"
color: controller.activeFlightMode == index ? qgcPal.buttonHighlight : qgcPal.text color: controller.activeFlightMode == index ? "yellow" : qgcPal.text
} }
FactComboBox { FactComboBox {
@ -149,7 +149,7 @@ QGCView {
QGCLabel { QGCLabel {
anchors.baseline: optCombo.baseline anchors.baseline: optCombo.baseline
text: "Channel option " + index + ":" text: "Channel option " + index + ":"
color: controller.channelOptionEnabled[modelData] ? qgcPal.buttonHighlight : qgcPal.text color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text
} }
FactComboBox { FactComboBox {

8
src/AutoPilotPlugins/APM/APMSensorsComponent.qml

@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: rootQGCView id: qgcView
viewPanel: panel viewPanel: panel
// Help text which is shown both in the status text area prior to pressing a cal button and in the // 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") _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 { } else {
preCalibrationDialogType = "compass" preCalibrationDialogType = "compass"
preCalibrationDialogHelp = compassHelp 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: { onClicked: {
preCalibrationDialogType = "accel" preCalibrationDialogType = "accel"
preCalibrationDialogHelp = accelHelp preCalibrationDialogHelp = accelHelp
showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", 50, StandardButton.Cancel | StandardButton.Ok) showDialog(preCalibrationDialogComponent, "Calibrate Accelerometer", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
} }
} }
QGCButton { QGCButton {

32
src/AutoPilotPlugins/Common/RadioComponent.qml

@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: rootQGCView id: qgcView
viewPanel: panel viewPanel: panel
QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled } QGCPalette { id: qgcPal; colorGroupEnabled: panel.enabled }
@ -51,7 +51,7 @@ QGCView {
FIXME: Turned off for now, since it prevents binding. Need to restructure to FIXME: Turned off for now, since it prevents binding. Need to restructure to
allow binding and still check channel count allow binding and still check channel count
if (controller.channelCount < controller.minChannelCount) { if (controller.channelCount < controller.minChannelCount) {
showDialog(channelCountDialogComponent, dialogTitle, 50, 0) showDialog(channelCountDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, 0)
} else { } else {
hideDialog() hideDialog()
} }
@ -68,7 +68,7 @@ QGCView {
Component.onCompleted: { Component.onCompleted: {
controllerCompleted = true controllerCompleted = true
if (rootQGCView.completedSignalled) { if (qgcView.completedSignalled) {
controllerAndViewReady = true controllerAndViewReady = true
controller.start() controller.start()
updateChannelCount() updateChannelCount()
@ -283,11 +283,11 @@ QGCView {
id: rollLoader id: rollLoader
anchors.left: rollLabel.right anchors.left: rollLabel.right
anchors.right: parent.right anchors.right: parent.right
height: rootQGCView.defaultTextHeight height: qgcView.defaultTextHeight
width: 100 width: 100
sourceComponent: channelMonitorDisplayComponent sourceComponent: channelMonitorDisplayComponent
property real defaultTextWidth: rootQGCView.defaultTextWidth property real defaultTextWidth: qgcView.defaultTextWidth
property bool mapped: controller.rollChannelMapped property bool mapped: controller.rollChannelMapped
property bool reversed: controller.rollChannelReversed property bool reversed: controller.rollChannelReversed
} }
@ -313,11 +313,11 @@ QGCView {
id: pitchLoader id: pitchLoader
anchors.left: pitchLabel.right anchors.left: pitchLabel.right
anchors.right: parent.right anchors.right: parent.right
height: rootQGCView.defaultTextHeight height: qgcView.defaultTextHeight
width: 100 width: 100
sourceComponent: channelMonitorDisplayComponent sourceComponent: channelMonitorDisplayComponent
property real defaultTextWidth: rootQGCView.defaultTextWidth property real defaultTextWidth: qgcView.defaultTextWidth
property bool mapped: controller.pitchChannelMapped property bool mapped: controller.pitchChannelMapped
property bool reversed: controller.pitchChannelReversed property bool reversed: controller.pitchChannelReversed
} }
@ -343,11 +343,11 @@ QGCView {
id: yawLoader id: yawLoader
anchors.left: yawLabel.right anchors.left: yawLabel.right
anchors.right: parent.right anchors.right: parent.right
height: rootQGCView.defaultTextHeight height: qgcView.defaultTextHeight
width: 100 width: 100
sourceComponent: channelMonitorDisplayComponent sourceComponent: channelMonitorDisplayComponent
property real defaultTextWidth: rootQGCView.defaultTextWidth property real defaultTextWidth: qgcView.defaultTextWidth
property bool mapped: controller.yawChannelMapped property bool mapped: controller.yawChannelMapped
property bool reversed: controller.yawChannelReversed property bool reversed: controller.yawChannelReversed
} }
@ -373,11 +373,11 @@ QGCView {
id: throttleLoader id: throttleLoader
anchors.left: throttleLabel.right anchors.left: throttleLabel.right
anchors.right: parent.right anchors.right: parent.right
height: rootQGCView.defaultTextHeight height: qgcView.defaultTextHeight
width: 100 width: 100
sourceComponent: channelMonitorDisplayComponent sourceComponent: channelMonitorDisplayComponent
property real defaultTextWidth: rootQGCView.defaultTextWidth property real defaultTextWidth: qgcView.defaultTextWidth
property bool mapped: controller.throttleChannelMapped property bool mapped: controller.throttleChannelMapped
property bool reversed: controller.throttleChannelReversed property bool reversed: controller.throttleChannelReversed
} }
@ -418,7 +418,7 @@ QGCView {
onClicked: { onClicked: {
if (text == "Calibrate") { if (text == "Calibrate") {
showDialog(zeroTrimsDialogComponent, dialogTitle, 50, StandardButton.Ok | StandardButton.Cancel) showDialog(zeroTrimsDialogComponent, dialogTitle, qgcView.showDialogDefaultWidth, StandardButton.Ok | StandardButton.Cancel)
} else { } else {
controller.nextButtonClicked() controller.nextButtonClicked()
} }
@ -460,7 +460,7 @@ QGCView {
showBorder: true showBorder: true
text: "Spektrum Bind" 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 showBorder: true
text: "Copy Trims" text: "Copy Trims"
visible: QGroundControl.multiVehicleManager.activeVehicle.px4Firmware 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 } // Column - Left Column
@ -552,11 +552,11 @@ QGCView {
Loader { Loader {
id: theLoader id: theLoader
anchors.verticalCenter: channelLabel.verticalCenter anchors.verticalCenter: channelLabel.verticalCenter
height: rootQGCView.defaultTextHeight height: qgcView.defaultTextHeight
width: 200 width: 200
sourceComponent: channelMonitorDisplayComponent sourceComponent: channelMonitorDisplayComponent
property real defaultTextWidth: rootQGCView.defaultTextWidth property real defaultTextWidth: qgcView.defaultTextWidth
property bool mapped: true property bool mapped: true
readonly property bool reversed: false readonly property bool reversed: false
} }

127
src/AutoPilotPlugins/Common/RadioComponentController.cc

@ -120,6 +120,10 @@ RadioComponentController::RadioComponentController(void) :
connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged); connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged);
_loadSettings(); _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(); _resetInternalCalibrationValues();
} }
@ -704,17 +708,20 @@ void RadioComponentController::_resetInternalCalibrationValues(void)
QVariant value; QVariant value;
enum rcCalFunctions curFunction = rgFlightModeFunctions[i]; enum rcCalFunctions curFunction = rgFlightModeFunctions[i];
bool ok; Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[curFunction].parameterName);
int switchChannel = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[curFunction].parameterName)->rawValue().toInt(&ok); if (paramFact) {
Q_ASSERT(ok); bool ok;
int switchChannel = paramFact->rawValue().toInt(&ok);
Q_ASSERT(ok);
// Parameter: 1-based channel, 0=not mapped // Parameter: 1-based channel, 0=not mapped
// _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped // _rgFunctionChannelMapping: 0-based channel, _chanMax=not mapped
if (switchChannel != 0) { if (switchChannel != 0) {
qCDebug(RadioComponentControllerLog) << "Reserving 0-based switch channel" << switchChannel - 1; qCDebug(RadioComponentControllerLog) << "Reserving 0-based switch channel" << switchChannel - 1;
_rgFunctionChannelMapping[curFunction] = switchChannel - 1; _rgFunctionChannelMapping[curFunction] = switchChannel - 1;
_rgChannelInfo[switchChannel - 1].function = curFunction; _rgChannelInfo[switchChannel - 1].function = curFunction;
}
} }
} }
} }
@ -747,20 +754,43 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
for (int i = 0; i < _chanMax(); ++i) { for (int i = 0; i < _chanMax(); ++i) {
struct ChannelInfo* info = &_rgChannelInfo[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); Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1));
Q_ASSERT(convertOk); if (paramFact) {
info->rcTrim = paramFact->rawValue().toInt(&convertOk);
Q_ASSERT(convertOk);
}
info->rcMin = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->rawValue().toInt(&convertOk); paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1));
Q_ASSERT(convertOk); if (paramFact) {
info->rcMin = paramFact->rawValue().toInt(&convertOk);
Q_ASSERT(convertOk);
}
info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(&convertOk); paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1));
Q_ASSERT(convertOk); 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); paramFact = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1));
Q_ASSERT(convertOk); if (paramFact) {
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); float floatReversed = paramFact->rawValue().toFloat(&convertOk);
info->reversed = floatReversed == -1.0f; Q_ASSERT(convertOk);
Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f);
info->reversed = floatReversed == -1.0f;
}
} }
for (int i=0; i<rcCalFunctionMax; i++) { for (int i=0; i<rcCalFunctionMax; i++) {
@ -768,12 +798,15 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
const char* paramName = _functionInfo()[i].parameterName; const char* paramName = _functionInfo()[i].parameterName;
if (paramName) { if (paramName) {
paramChannel = getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(&convertOk); Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, paramName);
Q_ASSERT(convertOk); if (paramFact) {
paramChannel = paramFact->rawValue().toInt(&convertOk);
if (paramChannel != 0) { Q_ASSERT(convertOk);
_rgFunctionChannelMapping[i] = paramChannel - 1;
_rgChannelInfo[paramChannel - 1].function = (enum rcCalFunctions)i; 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; if (!_uas) return;
_uas->stopCalibration(); if (_px4Vehicle()) {
_uas->stopCalibration();
}
_validateCalibration(); _validateCalibration();
@ -851,9 +886,23 @@ void RadioComponentController::_writeCalibration(void)
struct ChannelInfo* info = &_rgChannelInfo[chan]; struct ChannelInfo* info = &_rgChannelInfo[chan];
int oneBasedChannel = chan + 1; int oneBasedChannel = chan + 1;
getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setRawValue((float)info->rcTrim); if (_px4Vehicle() && _apmPossibleMissingRCChannelParams.contains(chan+1) && !parameterExists(FactSystem::defaultComponentId, minTpl.arg(chan+1))) {
getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMin); // RC parameters for this channel are missing from this version of APM
getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setRawValue((float)info->rcMax); 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. // APM has a backwards interpretation of "reversed" on the Pitch control. So be careful.
float reversedParamValue; float reversedParamValue;
@ -862,7 +911,10 @@ void RadioComponentController::_writeCalibration(void)
} else { } else {
reversedParamValue = info->reversed ? 1.0f : -1.0f; 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 // Write function mapping parameters
@ -880,9 +932,12 @@ void RadioComponentController::_writeCalibration(void)
if (paramName) { if (paramName) {
Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName); Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _functionInfo()[i].parameterName);
if (paramFact->rawValue().toInt() != paramChannel) { if (paramFact && paramFact->rawValue().toInt() != paramChannel) {
functionMappingChanged = true; 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(); _resetInternalCalibrationValues();
// Let the mav known we are starting calibration. This should turn off motors and so forth. // 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"); _nextButton->setProperty("text", "Next");
_cancelButton->setEnabled(true); _cancelButton->setEnabled(true);
@ -926,7 +983,9 @@ void RadioComponentController::_stopCalibration(void)
_currentStep = -1; _currentStep = -1;
if (_uas) { if (_uas) {
_uas->stopCalibration(); if (_px4Vehicle()) {
_uas->stopCalibration();
}
_setInternalCalibrationValuesFromParameters(); _setInternalCalibrationValuesFromParameters();
} else { } else {
_resetInternalCalibrationValues(); _resetInternalCalibrationValues();

2
src/AutoPilotPlugins/Common/RadioComponentController.h

@ -300,6 +300,8 @@ private:
static const int _chanMinimum = 5; ///< Minimum numner of channels required to run static const int _chanMinimum = 5; ///< Minimum numner of channels required to run
struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel
QList<int> _apmPossibleMissingRCChannelParams; ///< List of possible missing RC*_* params for APM stack
enum rcCalStates _rcCalState; ///< Current calibration state enum rcCalStates _rcCalState; ///< Current calibration state
int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion int _rcCalStateCurrentChannel; ///< Current channel being worked on in rcCalStateIdentify and rcCalStateDetectInversion

4
src/AutoPilotPlugins/PX4/AirframeComponent.qml

@ -67,7 +67,7 @@ QGCView {
Component.onCompleted: { Component.onCompleted: {
if (controller.showCustomConfigPanel) { 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 anchors.right: parent.right
text: "Apply and Restart" 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)
} }
} }

4
src/AutoPilotPlugins/PX4/FlightModesComponent.qml

@ -35,7 +35,7 @@ import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
QGCView { QGCView {
id: rootQGCView id: qgcView
viewPanel: panel viewPanel: panel
readonly property int monitorThresholdCharWidth: 8 // Character width of Monitor and Threshold labels readonly property int monitorThresholdCharWidth: 8 // Character width of Monitor and Threshold labels
@ -138,7 +138,7 @@ QGCView {
onTriggered: { onTriggered: {
recalcModePositions() recalcModePositions()
if (rcInMode.value == 1) { if (rcInMode.value == 1) {
showDialog(joystickEnabledDialogComponent, title, 50, 0) showDialog(joystickEnabledDialogComponent, title, qgcView.showDialogDefaultWidth, 0)
} }
} }
} }

14
src/AutoPilotPlugins/PX4/SensorsComponent.qml

@ -34,7 +34,7 @@ import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0 import QGroundControl.Controllers 1.0
QGCView { QGCView {
id: rootQGCView id: qgcView
viewPanel: panel viewPanel: panel
// Help text which is shown both in the status text area prior to pressing a cal button and in the // 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: { onSetCompassRotations: {
if (showCompass0Rot || showCompass1Rot || showCompass2Rot) { 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: { onClicked: {
preCalibrationDialogType = "compass" preCalibrationDialogType = "compass"
preCalibrationDialogHelp = compassHelp 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: { onClicked: {
preCalibrationDialogType = "gyro" preCalibrationDialogType = "gyro"
preCalibrationDialogHelp = gyroHelp 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: { onClicked: {
preCalibrationDialogType = "accel" preCalibrationDialogType = "accel"
preCalibrationDialogHelp = accelHelp 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: { onClicked: {
preCalibrationDialogType = "level" preCalibrationDialogType = "level"
preCalibrationDialogHelp = levelHelp 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: { onClicked: {
preCalibrationDialogType = "airspeed" preCalibrationDialogType = "airspeed"
preCalibrationDialogHelp = airspeedHelp preCalibrationDialogHelp = airspeedHelp
showDialog(preCalibrationDialogComponent, "Calibrate Airspeed", 50, StandardButton.Cancel | StandardButton.Ok) showDialog(preCalibrationDialogComponent, "Calibrate Airspeed", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Ok)
} }
} }

2
src/FactSystem/FactControls/FactTextField.qml

@ -29,7 +29,7 @@ QGCTextField {
fact.value = text fact.value = text
} else { } else {
_validateString = text _validateString = text
qgcView.showDialog(editorDialogComponent, "Invalid Parameter Value", 50, StandardButton.Save) qgcView.showDialog(editorDialogComponent, "Invalid Parameter Value", qgcView.showDialogDefaultWidth, StandardButton.Save)
} }
} else { } else {
fact.value = text fact.value = text

10
src/FactSystem/ParameterLoader.cc

@ -335,12 +335,18 @@ void ParameterLoader::_determineDefaultComponentId(void)
// the set of parameters. Better than nothing! // the set of parameters. Better than nothing!
_defaultComponentId = -1; _defaultComponentId = -1;
int largestCompParamCount = 0;
foreach(int componentId, _mapParameterName2Variant.keys()) { foreach(int componentId, _mapParameterName2Variant.keys()) {
if (_mapParameterName2Variant[componentId].count() > _defaultComponentId) { int compParamCount = _mapParameterName2Variant[componentId].count();
if (compParamCount > largestCompParamCount) {
largestCompParamCount = compParamCount;
_defaultComponentId = componentId; _defaultComponentId = componentId;
} }
} }
Q_ASSERT(_defaultComponentId != -1);
if (_defaultComponentId == -1) {
qWarning() << "All parameters missing, unable to determine default componet id";
}
} }
} }

39
src/FirmwarePlugin/APM/APMFirmwarePlugin.cc

@ -28,6 +28,7 @@
#include "Generic/GenericFirmwarePlugin.h" #include "Generic/GenericFirmwarePlugin.h"
#include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack #include "AutoPilotPlugins/APM/APMAutoPilotPlugin.h" // FIXME: Hack
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "QGCApplication.h"
QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog") QGC_LOGGING_CATEGORY(APMFirmwarePluginLog, "APMFirmwarePluginLog")
@ -211,7 +212,7 @@ int APMFirmwarePlugin::manualControlReservedButtonCount(void)
return -1; 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) { if (message->msgid == MAVLINK_MSG_ID_PARAM_VALUE) {
mavlink_param_value_t paramValue; mavlink_param_value_t paramValue;
@ -296,9 +297,6 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
mavlink_statustext_t statusText; mavlink_statustext_t statusText;
mavlink_msg_statustext_decode(message, &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) { if (!_firmwareVersion.isValid() || statusText.severity < MAV_SEVERITY_NOTICE) {
QByteArray b; QByteArray b;
b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1); b.resize(MAVLINK_MSG_STATUSTEXT_FIELD_TEXT_LEN+1);
@ -314,9 +312,42 @@ void APMFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message)
// found version string // found version string
_firmwareVersion = APMFirmwareVersion(messageText); _firmwareVersion = APMFirmwareVersion(messageText);
_textSeverityAdjustmentNeeded = _isTextSeverityAdjustmentNeeded(_firmwareVersion); _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")) { if (messageText.contains("Place vehicle") || messageText.contains("Calibration successful")) {
_adjustCalibrationMessageSeverity(message); _adjustCalibrationMessageSeverity(message);
return; return;

2
src/FirmwarePlugin/APM/APMFirmwarePlugin.h

@ -86,7 +86,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); 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 bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void); 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 void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);

3
src/FirmwarePlugin/FirmwarePlugin.h

@ -90,8 +90,9 @@ public:
/// Called before any mavlink message is processed by Vehicle such taht the firmwre plugin /// 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 /// 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. /// 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. /// @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. /// Called when Vehicle is first created to send any necessary mavlink messages to the firmware.
virtual void initializeVehicle(Vehicle* vehicle) = 0; virtual void initializeVehicle(Vehicle* vehicle) = 0;

3
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc

@ -90,8 +90,9 @@ int GenericFirmwarePlugin::manualControlReservedButtonCount(void)
return -1; return -1;
} }
void GenericFirmwarePlugin::adjustMavlinkMessage(mavlink_message_t* message) void GenericFirmwarePlugin::adjustMavlinkMessage(Vehicle* vehicle, mavlink_message_t* message)
{ {
Q_UNUSED(vehicle);
Q_UNUSED(message); Q_UNUSED(message);
// Generic plugin does no message adjustment // Generic plugin does no message adjustment

2
src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h

@ -42,7 +42,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); 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 bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void); 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 void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);

7
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc

@ -177,8 +177,9 @@ int PX4FirmwarePlugin::manualControlReservedButtonCount(void)
return 0; // 0 buttons reserved for rc switch simulation 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); Q_UNUSED(message);
// PX4 Flight Stack plugin does no message adjustment // PX4 Flight Stack plugin does no message adjustment
@ -217,6 +218,8 @@ QList<MAV_CMD> PX4FirmwarePlugin::supportedMissionCommands(void)
<< MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF << MAV_CMD_NAV_RETURN_TO_LAUNCH << MAV_CMD_NAV_LAND << MAV_CMD_NAV_TAKEOFF
<< MAV_CMD_NAV_ROI << MAV_CMD_NAV_ROI
<< MAV_CMD_DO_JUMP << MAV_CMD_DO_JUMP
<< MAV_CMD_CONDITION_DELAY; << MAV_CMD_CONDITION_DELAY
<< MAV_CMD_DO_VTOL_TRANSITION
<< MAV_CMD_DO_DIGICAM_CONTROL;
return list; return list;
} }

2
src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h

@ -42,7 +42,7 @@ public:
virtual QString flightMode(uint8_t base_mode, uint32_t custom_mode); 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 bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode);
virtual int manualControlReservedButtonCount(void); 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 void initializeVehicle(Vehicle* vehicle);
virtual bool sendHomePositionToVehicle(void); virtual bool sendHomePositionToVehicle(void);
virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType);

17
src/MissionManager/MavCmdInfo.json

@ -553,7 +553,7 @@
{ {
"id": 222, "id": 222,
"rawName": "MAV_CMD_DO_GUIDED_LIMITS", "rawName": "MAV_CMD_DO_GUIDED_LIMITS",
"friendlyName": "Exetrnal control limits", "friendlyName": "External control limits",
"description": "Set limits for external control", "description": "Set limits for external control",
"param1": { "param1": {
"label": "Timeout:", "label": "Timeout:",
@ -588,7 +588,20 @@
{ "id": 2500, "rawName": "MAV_CMD_VIDEO_START_CAPTURE", "friendlyName": "MAV_CMD_VIDEO_START_CAPTURE" }, { "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": 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": 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": 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" } { "id": 30002, "rawName": "MAV_CMD_PAYLOAD_CONTROL_DEPLOY", "friendlyName": "MAV_CMD_PAYLOAD_CONTROL_DEPLOY" }
] ]

5
src/QGCDockWidget.cc

@ -36,7 +36,6 @@ QGCDockWidget::QGCDockWidget(const QString& title, QAction* action, QWidget* par
if (action) { if (action) {
setWindowTitle(title); setWindowTitle(title);
setWindowFlags(Qt::Tool); setWindowFlags(Qt::Tool);
loadSettings(); loadSettings();
} }
} }
@ -55,11 +54,11 @@ void QGCDockWidget::loadSettings(void)
{ {
if (_action) { if (_action) {
QSettings settings; QSettings settings;
settings.beginGroup(_settingsGroup); settings.beginGroup(_settingsGroup);
if (settings.contains(_title)) { if (settings.contains(_title)) {
restoreGeometry(settings.value(_title).toByteArray()); restoreGeometry(settings.value(_title).toByteArray());
} }
settings.endGroup();
} }
} }
@ -67,8 +66,8 @@ void QGCDockWidget::saveSettings(void)
{ {
if (_action) { if (_action) {
QSettings settings; QSettings settings;
settings.beginGroup(_settingsGroup); settings.beginGroup(_settingsGroup);
settings.setValue(_title, saveGeometry()); settings.setValue(_title, saveGeometry());
settings.endGroup();
} }
} }

6
src/QGCPalette.cc

@ -49,7 +49,7 @@ QColor QGCPalette::_windowShadeDark[QGCPalette::_cThemes][QGCPalette::_cColorGro
}; };
QColor QGCPalette::_text[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { QColor QGCPalette::_text[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
{ QColor("#cccccc"), QColor("#000000") }, { QColor("#9d9d9d"), QColor("#000000") },
{ QColor(0x58, 0x58, 0x58), QColor(0xFF, 0xFF, 0xFF) } { 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 QGCPalette::_buttonText[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
{ QColor("#dedede"), QColor("#000000") }, { QColor("#9d9d9d"), QColor("#000000") },
{ QColor(0x2c, 0x2c, 0x2c), QColor(0xFF, 0xFF, 0xFF) }, { QColor(0x2c, 0x2c, 0x2c), QColor(0xFF, 0xFF, 0xFF) },
}; };
QColor QGCPalette::_buttonHighlight[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = { QColor QGCPalette::_buttonHighlight[QGCPalette::_cThemes][QGCPalette::_cColorGroups] = {
{ QColor("#e4e4e4"), QColor("#e4e4e4") }, { QColor("#e4e4e4"), QColor("#91d1e4") },
{ QColor(0x58, 0x58, 0x58), QColor(237, 235, 51) }, { QColor(0x58, 0x58, 0x58), QColor(237, 235, 51) },
}; };

4
src/QmlControls/MissionItemEditor.qml

@ -95,7 +95,7 @@ Rectangle {
MenuItem { MenuItem {
text: "Delete all" 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 { } 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 { QGCLabel {

6
src/QmlControls/ParameterEditor.qml

@ -119,7 +119,7 @@ QGCView {
} }
MenuItem { MenuItem {
text: "Search..." 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 } MenuSeparator { visible: !ScreenTools.isMobile }
MenuItem { MenuItem {
@ -290,7 +290,7 @@ QGCView {
id: valueLabel id: valueLabel
width: ScreenTools.defaultFontPixelWidth * 20 width: ScreenTools.defaultFontPixelWidth * 20
color: factRow.modelFact.defaultValueAvailable ? (factRow.modelFact.valueEqualsDefault ? __qgcPal.text : __qgcPal.warningText) : __qgcPal.text 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 { QGCLabel {
text: factRow.modelFact.shortDescription text: factRow.modelFact.shortDescription
@ -314,7 +314,7 @@ QGCView {
acceptedButtons: Qt.LeftButton acceptedButtons: Qt.LeftButton
onClicked: { onClicked: {
__editorDialogFact = factRow.modelFact __editorDialogFact = factRow.modelFact
showDialog(editorDialogComponent, "Parameter Editor", 50, StandardButton.Cancel | StandardButton.Save) showDialog(editorDialogComponent, "Parameter Editor", qgcView.showDialogDefaultWidth, StandardButton.Cancel | StandardButton.Save)
} }
} }
} }

39
src/QmlControls/ParameterEditorDialog.qml

@ -35,6 +35,8 @@ import QGroundControl.FactControls 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
QGCViewDialog { QGCViewDialog {
id: root
property Fact fact property Fact fact
property bool validate: false property bool validate: false
property string validateValue property string validateValue
@ -42,14 +44,19 @@ QGCViewDialog {
ParameterEditorController { id: controller; factPanel: parent } ParameterEditorController { id: controller; factPanel: parent }
function accept() { function accept() {
var errorString = fact.validate(valueField.text, forceSave.checked) if (factCombo.visible) {
if (errorString == "") { fact.enumIndex = factCombo.currentIndex
fact.value = valueField.text
fact.valueChanged(fact.value)
hideDialog() hideDialog()
} else { } else {
validationError.text = errorString var errorString = fact.validate(valueField.text, forceSave.checked)
forceSave.visible = true if (errorString == "") {
fact.value = valueField.text
fact.valueChanged(fact.value)
hideDialog()
} else {
validationError.text = errorString
forceSave.visible = true
}
} }
} }
@ -80,14 +87,30 @@ QGCViewDialog {
} }
QGCTextField { QGCTextField {
id: valueField id: valueField
text: validate ? validateValue : fact.valueString text: validate ? validateValue : fact.valueString
visible: fact.enumStrings.length == 0 || validate
//focus: true //focus: true
// At this point all Facts are numeric // At this point all Facts are numeric
inputMethodHints: Qt.ImhFormattedNumbersOnly 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 } QGCLabel { text: fact.name }
Row { Row {

10
src/QmlControls/QGCView.qml

@ -128,8 +128,12 @@ FactPanel {
/// Shows a QGCViewDialog component /// Shows a QGCViewDialog component
/// @param compoent QGCViewDialog component /// @param compoent QGCViewDialog component
/// @param title Title for dialog /// @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 /// @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) { function showDialog(component, title, charWidth, buttons) {
if (__checkForEarlyDialog(title)) { if (__checkForEarlyDialog(title)) {
return return
@ -158,7 +162,7 @@ FactPanel {
__stopAllAnimations() __stopAllAnimations()
__dialogCharWidth = 50 __dialogCharWidth = showDialogDefaultWidth
__dialogTitle = title __dialogTitle = title
__messageDialogText = message __messageDialogText = message
@ -285,7 +289,7 @@ FactPanel {
// This is the main dialog panel which is anchored to the right edge // This is the main dialog panel which is anchored to the right edge
Rectangle { Rectangle {
id: __dialogPanel id: __dialogPanel
width: __dialogCharWidth == -1 ? parent.width : defaultTextWidth * __dialogCharWidth width: __dialogCharWidth == showDialogFullWidth ? parent.width : defaultTextWidth * __dialogCharWidth
anchors.topMargin: topDialogMargin anchors.topMargin: topDialogMargin
anchors.top: parent.top anchors.top: parent.top
anchors.bottom: parent.bottom anchors.bottom: parent.bottom

4
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 // Give the plugin a change to adjust the message contents
_firmwarePlugin->adjustMavlinkMessage(&message); _firmwarePlugin->adjustMavlinkMessage(this, &message);
switch (message.msgid) { switch (message.msgid) {
case MAVLINK_MSG_ID_HOME_POSITION: case MAVLINK_MSG_ID_HOME_POSITION:
@ -442,7 +442,7 @@ void Vehicle::_sendMessage(mavlink_message_t message)
MAVLinkProtocol* mavlink = _mavlink; MAVLinkProtocol* mavlink = _mavlink;
// Give the plugin a chance to adjust // Give the plugin a chance to adjust
_firmwarePlugin->adjustMavlinkMessage(&message); _firmwarePlugin->adjustMavlinkMessage(this, &message);
static const uint8_t messageKeys[256] = MAVLINK_MESSAGE_CRCS; 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]); mavlink_finalize_message_chan(&message, mavlink->getSystemId(), mavlink->getComponentId(), link->getMavlinkChannel(), message.len, messageKeys[message.msgid]);

2
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 // We end up here when we detect a board plugged in after we've started upgrade
statusTextArea.append(highlightPrefix + "Found device" + highlightSuffix + ": " + controller.boardType) statusTextArea.append(highlightPrefix + "Found device" + highlightSuffix + ": " + controller.boardType)
if (controller.boardType == "Pixhawk" || controller.boardType == "AeroCore" || controller.boardType == "PX4 Flow" || controller.boardType == "PX4 FMU V1") { 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)
} }
} }
} }

1
src/ViewWidgets/LogDownload.cc

@ -29,6 +29,5 @@ LogDownload::LogDownload(const QString& title, QAction* action, QWidget *parent)
Q_UNUSED(title); Q_UNUSED(title);
Q_UNUSED(action); Q_UNUSED(action);
setSource(QUrl::fromUserInput("qrc:/qml/LogDownload.qml")); setSource(QUrl::fromUserInput("qrc:/qml/LogDownload.qml"));
loadSettings(); loadSettings();
} }

22
src/ViewWidgets/LogDownloadController.cc

@ -113,21 +113,26 @@ LogDownloadController::_logEntry(UASInterface* uas, uint32_t time_utc, uint32_t
return; return;
} }
//-- If this is the first, pre-fill it //-- 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++) { for(int i = 0; i < num_logs; i++) {
QGCLogEntry *entry = new QGCLogEntry(i); QGCLogEntry *entry = new QGCLogEntry(i);
_logEntriesModel.append(entry); _logEntriesModel.append(entry);
} }
} }
//-- Update this log record //-- Update this log record
if(id < _logEntriesModel.count()) { if(num_logs > 0) {
QGCLogEntry* entry = _logEntriesModel[id]; if(id < _logEntriesModel.count()) {
entry->setSize(size); QGCLogEntry* entry = _logEntriesModel[id];
entry->setTime(QDateTime::fromTime_t(time_utc)); entry->setSize(size);
entry->setReceived(true); entry->setTime(QDateTime::fromTime_t(time_utc));
entry->setStatus(QString("Available")); entry->setReceived(true);
entry->setStatus(QString("Available"));
} else {
qWarning() << "Received log entry for out-of-bound index:" << id;
}
} else { } else {
qWarning() << "Received log entry for out-of-bound index:" << id; //-- No logs to list
_receivedAllEntries();
} }
//-- Reset retry count //-- Reset retry count
_retries = 0; _retries = 0;
@ -515,6 +520,7 @@ LogDownloadController::eraseAll(void)
&msg, &msg,
qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL); qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->id(), MAV_COMP_ID_ALL);
_vehicle->sendMessage(msg); _vehicle->sendMessage(msg);
refresh();
} }
} }

8
src/ViewWidgets/LogDownloadController.h

@ -34,10 +34,10 @@
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "FactPanelController.h" #include "FactPanelController.h"
class MultiVehicleManager; class MultiVehicleManager;
class UASInterface; class UASInterface;
class Vehicle; class Vehicle;
class QGCLogEntry; class QGCLogEntry;
class LogDownloadData; class LogDownloadData;
Q_DECLARE_LOGGING_CATEGORY(LogDownloadLog) Q_DECLARE_LOGGING_CATEGORY(LogDownloadLog)

4
src/comm/LinkInterface.h

@ -131,10 +131,6 @@ public:
/// set into the link when it is added to LinkManager /// set into the link when it is added to LinkManager
uint8_t getMavlinkChannel(void) const { Q_ASSERT(_mavlinkChannelSet); return _mavlinkChannel; } 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 // 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. // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.
bool connect(void); bool connect(void);

2
src/comm/LinkManager.cc

@ -189,8 +189,6 @@ void LinkManager::_addLink(LinkInterface* link)
connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread); connect(link, &LinkInterface::communicationError, _app, &QGCApplication::criticalMessageBoxOnMainThread);
connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes); connect(link, &LinkInterface::bytesReceived, _mavlinkProtocol, &MAVLinkProtocol::receiveBytes);
connect(link, &LinkInterface::connected, _mavlinkProtocol, &MAVLinkProtocol::linkConnected);
connect(link, &LinkInterface::disconnected, _mavlinkProtocol, &MAVLinkProtocol::linkDisconnected);
_mavlinkProtocol->resetMetadataForLink(link); _mavlinkProtocol->resetMetadataForLink(link);

35
src/comm/MAVLinkProtocol.cc

@ -173,41 +173,6 @@ void MAVLinkProtocol::resetMetadataForLink(const LinkInterface *link)
currLossCounter[channel] = 0; currLossCounter[channel] = 0;
} }
void MAVLinkProtocol::linkConnected(void)
{
LinkInterface* link = qobject_cast<LinkInterface*>(QObject::sender());
Q_ASSERT(link);
_linkStatusChanged(link, true);
}
void MAVLinkProtocol::linkDisconnected(void)
{
LinkInterface* link = qobject_cast<LinkInterface*>(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. * 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/ * It can handle multiple links in parallel, as each link has it's own buffer/

4
src/comm/MAVLinkProtocol.h

@ -155,9 +155,6 @@ public slots:
/** @brief Receive bytes from a communication interface */ /** @brief Receive bytes from a communication interface */
void receiveBytes(LinkInterface* link, QByteArray b); void receiveBytes(LinkInterface* link, QByteArray b);
void linkConnected(void);
void linkDisconnected(void);
/** @brief Set the rate at which heartbeats are emitted */ /** @brief Set the rate at which heartbeats are emitted */
void setHeartbeatRate(int rate); void setHeartbeatRate(int rate);
/** @brief Set the system id of this application */ /** @brief Set the system id of this application */
@ -285,7 +282,6 @@ private slots:
void _vehicleCountChanged(int count); void _vehicleCountChanged(int count);
private: private:
void _linkStatusChanged(LinkInterface* link, bool connected);
void _sendMessage(mavlink_message_t message); void _sendMessage(mavlink_message_t message);
void _sendMessage(LinkInterface* link, mavlink_message_t message); void _sendMessage(LinkInterface* link, mavlink_message_t message);
void _sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid); void _sendMessage(LinkInterface* link, mavlink_message_t message, quint8 systemid, quint8 componentid);

9
src/comm/SerialLink.cc

@ -377,15 +377,6 @@ LinkConfiguration* SerialLink::getLinkConfiguration()
return _config; return _config;
} }
bool SerialLink::requiresUSBMavlinkStart(void) const
{
if (_port) {
return QGCSerialPortInfo(*_port).boardTypePixhawk();
} else {
return false;
}
}
//-------------------------------------------------------------------------- //--------------------------------------------------------------------------
//-- SerialConfiguration //-- SerialConfiguration

1
src/comm/SerialLink.h

@ -146,7 +146,6 @@ public:
void requestReset(); void requestReset();
bool isConnected() const; bool isConnected() const;
qint64 getConnectionSpeed() const; qint64 getConnectionSpeed() const;
bool requiresUSBMavlinkStart(void) const;
// These are left unimplemented in order to cause linker errors which indicate incorrect usage of // 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. // connect/disconnect on link directly. All connect/disconnect calls should be made through LinkManager.

3
src/uas/UAS.cc

@ -810,7 +810,8 @@ void UAS::receiveMessage(mavlink_message_t message)
{ {
case MAV_RESULT_ACCEPTED: 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; break;
case MAV_RESULT_TEMPORARILY_REJECTED: case MAV_RESULT_TEMPORARILY_REJECTED:

75
src/ui/MainWindow.cc

@ -332,56 +332,59 @@ void MainWindow::_showDockWidget(const QString& name, bool show)
{ {
// Create the inner widget if we need to // Create the inner widget if we need to
if (!_mapName2DockWidget.contains(name)) { if (!_mapName2DockWidget.contains(name)) {
_createInnerDockWidget(name); if(!_createInnerDockWidget(name)) {
qWarning() << "Trying to load non existing widget:" << name;
return;
}
} }
Q_ASSERT(_mapName2DockWidget.contains(name)); Q_ASSERT(_mapName2DockWidget.contains(name));
QGCDockWidget* dockWidget = _mapName2DockWidget[name]; QGCDockWidget* dockWidget = _mapName2DockWidget[name];
Q_ASSERT(dockWidget); Q_ASSERT(dockWidget);
dockWidget->setVisible(show); dockWidget->setVisible(show);
Q_ASSERT(_mapName2Action.contains(name)); Q_ASSERT(_mapName2Action.contains(name));
_mapName2Action[name]->setChecked(show); _mapName2Action[name]->setChecked(show);
} }
/// Creates the specified inner dock widget and adds to the QDockWidget /// 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; QGCDockWidget* widget = NULL;
QAction *action = _mapName2Action[widgetName]; QAction *action = _mapName2Action[widgetName];
if(action) {
switch(action->data().toInt()) { switch(action->data().toInt()) {
case MAVLINK_INSPECTOR: case MAVLINK_INSPECTOR:
widget = new QGCMAVLinkInspector(widgetName, action, qgcApp()->toolbox()->mavlinkProtocol(),this); widget = new QGCMAVLinkInspector(widgetName, action, qgcApp()->toolbox()->mavlinkProtocol(),this);
break; break;
case CUSTOM_COMMAND: case CUSTOM_COMMAND:
widget = new CustomCommandWidget(widgetName, action, this); widget = new CustomCommandWidget(widgetName, action, this);
break; break;
case ONBOARD_FILES: case ONBOARD_FILES:
widget = new QGCUASFileViewMulti(widgetName, action, this); widget = new QGCUASFileViewMulti(widgetName, action, this);
break; break;
case LOG_DOWNLOAD: case LOG_DOWNLOAD:
widget = new LogDownload(widgetName, action, this); widget = new LogDownload(widgetName, action, this);
break; break;
case STATUS_DETAILS: case STATUS_DETAILS:
widget = new UASInfoWidget(widgetName, action, this); widget = new UASInfoWidget(widgetName, action, this);
break; break;
case HIL_CONFIG: case HIL_CONFIG:
widget = new HILDockWidget(widgetName, action, this); widget = new HILDockWidget(widgetName, action, this);
break; break;
case ANALYZE: case ANALYZE:
widget = new Linecharts(widgetName, action, mavlinkDecoder, this); widget = new Linecharts(widgetName, action, mavlinkDecoder, this);
break; break;
case INFO_VIEW: case INFO_VIEW:
widget= new QGCTabbedInfoView(widgetName, action, this); widget= new QGCTabbedInfoView(widgetName, action, this);
break; break;
} }
if(action->data().toInt() == INFO_VIEW) {
if(action->data().toInt() == INFO_VIEW) { qobject_cast<QGCTabbedInfoView*>(widget)->addSource(mavlinkDecoder);
qobject_cast<QGCTabbedInfoView*>(widget)->addSource(mavlinkDecoder); }
if(widget) {
_mapName2DockWidget[widgetName] = widget;
}
} }
_mapName2DockWidget[widgetName] = widget; return widget != NULL;
} }
void MainWindow::_hideAllDockWidgets(void) void MainWindow::_hideAllDockWidgets(void)

2
src/ui/MainWindow.h

@ -221,7 +221,7 @@ private:
void _loadCurrentViewState(void); void _loadCurrentViewState(void);
#ifndef __mobile__ #ifndef __mobile__
void _createInnerDockWidget(const QString& widgetName); bool _createInnerDockWidget(const QString& widgetName);
void _buildCommonWidgets(void); void _buildCommonWidgets(void);
void _hideAllDockWidgets(void); void _hideAllDockWidgets(void);
void _showDockWidget(const QString &name, bool show); void _showDockWidget(const QString &name, bool show);

Loading…
Cancel
Save