Commit d18a6b85 authored by dogmaphobic's avatar dogmaphobic

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
parents 939ee6f4 d8c45c77
......@@ -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
}
......@@ -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.
......
#!/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 "$@"
<?xml version='1.0' encoding='UTF-8'?>
<airframes>
<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 RTF" file="3DR_Aero_RTF.param"/>
<airframe name="3DR Rover" file="3DR_Rover.param"/>
......@@ -9,26 +9,26 @@
<airframe name="Parrot Bebop" file="Parrot_Bebop.param"/>
<airframe name="Storm32" file="SToRM32-MAVLink.param"/>
</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 Y6A" file="3DR_Y6A_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 X8" file="3DR_X8_RTF.param"/>
</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 Tarot" file="Iris with Tarot Gimbal.param"/>
<airframe name="3DR Iris+" file="3DR_Iris+.param"/>
<airframe name="Iris" file="Iris.param"/>
</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 image="AirframeQuadRotorH.png" name="A Tail Frame" id="5">
<airframe_group image="AirframeQuadRotorH.png" name="A Tail" id="5">
</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 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_group>
<airframes>
......@@ -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 {
......
......@@ -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 {
......
......@@ -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
}
......
......@@ -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; i<rcCalFunctionMax; i++) {
......@@ -768,12 +798,15 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void)
const char* paramName = _functionInfo()[i].parameterName;
if (paramName) {
paramChannel = getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().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();
......
......@@ -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<int> _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
......
......@@ -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)
}
}
......
......@@ -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)
}
}
}
......
......@@ -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)
}
}
......
......@@ -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
......
......@@ -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";
}
}
}
......
......@@ -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));
}
}
}
}
}