diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml index ab7efbf3f904d4f50c548d6a269d5ddd58fc2dc3..2f715482269ebe17d6edca4dcbd8647b6f7e0a10 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml @@ -106,8 +106,15 @@ SetupPage { readonly property real innerMargin: ScreenTools.defaultFontPixelWidth MouseArea { - anchors.fill: parent - onClicked: airframeCheckBox.checked = true + anchors.fill: parent + onClicked: { + if (!airframeCheckBox.checked || !combo.valid) { + if (_frameTypeAvailable && object.defaultFrameType != -1) { + _frameType.rawValue = object.defaultFrameType + } + airframeCheckBox.checked = true + } + } } QGCLabel { @@ -116,12 +123,14 @@ SetupPage { } Rectangle { + id: imageComboRect anchors.topMargin: ScreenTools.defaultFontPixelHeight / 2 anchors.top: title.bottom anchors.bottom: parent.bottom anchors.left: parent.left anchors.right: parent.right color: airframeCheckBox.checked ? qgcPal.buttonHighlight : qgcPal.windowShade + opacity: combo.valid ? 1.0 : 0.5 ColumnLayout { anchors.margins: innerMargin @@ -136,7 +145,7 @@ SetupPage { smooth: true antialiasing: true sourceSize.width: width - source: object.imageResource + source: airframeCheckBox.checked ? object.imageResource : object.imageResourceDefault } QGCCheckBox { @@ -160,15 +169,43 @@ SetupPage { visible: airframeCheckBox.checked && object.frameTypeSupported } - FactComboBox { + QGCComboBox { id: combo Layout.fillWidth: true - fact: _frameType - indexModel: false + model: object.frameTypeEnumStrings visible: airframeCheckBox.checked && object.frameTypeSupported + onActivated: _frameType.rawValue = object.frameTypeEnumValues[index] + + property bool valid: true + + function selectFrameType(frameType) { + var index = object.frameTypeEnumValues.findIndex(v => v==frameType) + if (index == -1 && combo.visible) { + // Frame Class/Type is set to an invalid combination + combo.valid = false + } else { + combo.currentIndex = index + combo.valid = true + } + } + + Component.onCompleted: selectFrameType(_frameType.rawValue) + + Connections { + target: _frameTypeAvailable ? _frameType : null + ignoreUnknownSignals: true + onRawValueChanged: combo.selectFrameType(value) + } } } } + + QGCLabel { + anchors.fill: imageComboRect + text: qsTr("Invalid setting for FRAME_TYPE. Click to Reset.") + wrapMode: Text.WordWrap + visible: !combo.valid + } } } // Repeater - summary boxes } // Flow - summary boxes diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc index f89d8557d474fadfb79d1f95fad44492ffba0989..b20bbdff4829547c835af2075d234d31b20cbeb4 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc @@ -70,23 +70,35 @@ typedef struct { } FrameToImageInfo_t; static const FrameToImageInfo_t s_rgFrameToImageCopter[] = { - { FRAME_CLASS_QUAD, FRAME_TYPE_PLUS, "QuadRotorPlus" }, - { FRAME_CLASS_QUAD, FRAME_TYPE_X, "QuadRotorX" }, - { FRAME_CLASS_QUAD, FRAME_TYPE_V, "QuadRotorWide" }, - { FRAME_CLASS_QUAD, FRAME_TYPE_H, "QuadRotorH" }, - { FRAME_CLASS_QUAD, FRAME_TYPE_V_TAIL, "QuadRotorVTail" }, - { FRAME_CLASS_QUAD, FRAME_TYPE_A_TAIL, "QuadRotorATail" }, - { FRAME_CLASS_HEX, FRAME_TYPE_PLUS, "HexaRotorPlus" }, - { FRAME_CLASS_HEX, FRAME_TYPE_X, "HexaRotorX" }, - { FRAME_CLASS_OCTA, FRAME_TYPE_PLUS, "OctoRotorPlus" }, - { FRAME_CLASS_OCTA, FRAME_TYPE_X, "OctoRotorX" }, - { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_PLUS, "OctoRotorPlusCoaxial" }, - { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_X, "OctoRotorXCoaxial" }, - { FRAME_CLASS_Y6, FRAME_TYPE_Y6B, "Y6B" }, - { FRAME_CLASS_Y6, FRAME_TYPE_Y6F, "AirframeUnknown" }, - { FRAME_CLASS_Y6, -1, "Y6A" }, - { FRAME_CLASS_HELI, -1, "Helicopter" }, - { FRAME_CLASS_TRI, -1, "YPlus" }, + { FRAME_CLASS_QUAD, FRAME_TYPE_X, "QuadRotorX" }, // Default + { FRAME_CLASS_QUAD, FRAME_TYPE_PLUS, "QuadRotorPlus" }, + { FRAME_CLASS_QUAD, FRAME_TYPE_V, "QuadRotorWide" }, + { FRAME_CLASS_QUAD, FRAME_TYPE_H, "QuadRotorH" }, + { FRAME_CLASS_QUAD, FRAME_TYPE_V_TAIL, "QuadRotorVTail" }, + { FRAME_CLASS_QUAD, FRAME_TYPE_A_TAIL, "QuadRotorATail" }, + + { FRAME_CLASS_HEX, FRAME_TYPE_X, "HexaRotorX" }, // Default + { FRAME_CLASS_HEX, FRAME_TYPE_PLUS, "HexaRotorPlus" }, + + { FRAME_CLASS_OCTA, FRAME_TYPE_X, "OctoRotorX" }, // Default + { FRAME_CLASS_OCTA, FRAME_TYPE_PLUS, "OctoRotorPlus" }, + { FRAME_CLASS_OCTA, FRAME_TYPE_V, "AirframeUnknown" }, + { FRAME_CLASS_OCTA, FRAME_TYPE_H, "AirframeUnknown" }, + + { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_X, "OctoRotorXCoaxial" }, // Default + { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_PLUS, "OctoRotorPlusCoaxial" }, + { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_V, "AirframeUnknown" }, + { FRAME_CLASS_OCTAQUAD, FRAME_TYPE_H, "AirframeUnknown" }, + + { FRAME_CLASS_Y6, FRAME_TYPE_Y6B, "Y6B" }, // Default + { FRAME_CLASS_Y6, FRAME_TYPE_Y6F, "AirframeUnknown" }, + { FRAME_CLASS_Y6, -1, "Y6A" }, + + { FRAME_CLASS_DODECAHEXA, FRAME_TYPE_X, "AirframeUnknown" }, // Default + { FRAME_CLASS_DODECAHEXA, FRAME_TYPE_PLUS, "AirframeUnknown" }, + + { FRAME_CLASS_HELI, -1, "Helicopter" }, + { FRAME_CLASS_TRI, -1, "YPlus" }, }; static const FrameToImageInfo_t s_rgFrameToImageRover[] = { @@ -94,14 +106,16 @@ static const FrameToImageInfo_t s_rgFrameToImageRover[] = { { FRAME_CLASS_BOAT, -1, "Boat" }, }; -static QString s_findImageResourceCopter(int frameClass, int frameType) +/// Returns the image resource for the frameClass, frameType pair +/// @param[in,out] frameType Specified frame type, or -1 to match first item in list (frameType found will be returned) +static QString s_findImageResourceCopter(int frameClass, int& frameType) { for (size_t i=0; iframeClass == frameClass && pFrameToImageInfo->frameType == frameType) { - return pFrameToImageInfo->imageResource; - } else if (pFrameToImageInfo->frameClass == frameClass && pFrameToImageInfo->frameType == -1) { + if ((pFrameToImageInfo->frameClass == frameClass && frameType == -1) || + (pFrameToImageInfo->frameClass == frameClass && pFrameToImageInfo->frameType == frameType)) { + frameType = pFrameToImageInfo->frameType; return pFrameToImageInfo->imageResource; } } @@ -154,32 +168,19 @@ void APMAirframeComponentController::_fillFrameClasses() for (int i=1; i<_frameClassFact->enumStrings().count(); i++) { QString frameClassName = _frameClassFact->enumStrings()[i]; int frameClass = _frameClassFact->enumValues()[i].toInt(); - int defaultFrameType; if (frameClass == FRAME_CLASS_HELI) { // Heli requires it's own firmware variant. You can't switch to Heli from a Copter variant firmware. continue; } - if (frameTypeNotSupported.contains(frameClass)) { - defaultFrameType = -1; - } else { - defaultFrameType = FRAME_TYPE_X; - } - _frameClassModel->append(new APMFrameClass(frameClassName, true /* copter */, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel)); + _frameClassModel->append(new APMFrameClass(frameClassName, true /* copter */, frameClass, _frameTypeFact, _frameClassModel)); } } else if (qobject_cast(fwPlugin)) { for (int i=1; i<_frameClassFact->enumStrings().count(); i++) { QString frameClassName = _frameClassFact->enumStrings()[i]; int frameClass = _frameClassFact->enumValues()[i].toInt(); - int defaultFrameType; - - if (_frameTypeFact) { - defaultFrameType = FRAME_TYPE_UNDEFINED; - } else { - defaultFrameType = -1; - } - _frameClassModel->append(new APMFrameClass(frameClassName, false /* copter */, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel)); + _frameClassModel->append(new APMFrameClass(frameClassName, false /* copter */, frameClass, _frameTypeFact, _frameClassModel)); } } } @@ -270,19 +271,55 @@ void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg) qgcApp()->restoreOverrideCursor(); } -APMFrameClass::APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent) +APMFrameClass::APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, QObject* parent) : QObject (parent) , _name (name) , _copter (copter) , _frameClass (frameClass) - , _defaultFrameType (defaultFrameType) - , _frameTypeSupported (defaultFrameType != -1) + , _defaultFrameType (-1) + , _frameTypeSupported (false) , _frameTypeFact (frameTypeFact) { if (frameTypeFact) { connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::imageResourceChanged); connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::frameTypeChanged); } + + if (copter) { + QList rgSupportedFrameTypes; + + for (size_t i=0; iframeClass == frameClass) { + if (_defaultFrameType == -1) { + // Default frame type/icon is the first item found to match frameClass + _defaultFrameType = pFrameToImageInfo->frameType; + _imageResourceDefault = QStringLiteral("/qmlimages/Airframe/%1").arg(pFrameToImageInfo->imageResource); + } + + if (pFrameToImageInfo->frameType != -1) { + // The list includes the supported frame types for the class + rgSupportedFrameTypes.append(pFrameToImageInfo->frameType); + } + } + } + if (_imageResourceDefault.isEmpty()) { + _imageResourceDefault = QStringLiteral("/qmlimages/Airframe/AirframeUnknown"); + } + + // Filter the enums + for (const int frameType: rgSupportedFrameTypes) { + int index = frameTypeFact->enumValues().indexOf(frameType); + if (index != -1) { + _frameTypeEnumValues.append(frameType); + _frameTypeEnumStrings.append(frameTypeFact->enumStrings()[index]); + } + } + } + + // If the frameClass is not in the list then frame type is not supported + _frameTypeSupported = _defaultFrameType != -1; } APMFrameClass::~APMFrameClass() diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h index 16bb24bc1d859c377354d23964c79004e005f9f1..7a6dfbadb775366453d6c217756e8406cb8e4e2e 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h @@ -54,25 +54,31 @@ class APMFrameClass : public QObject Q_OBJECT public: - APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent = nullptr); + APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, QObject* parent = nullptr); ~APMFrameClass(); - Q_PROPERTY(QString name MEMBER _name CONSTANT) - Q_PROPERTY(int frameClass MEMBER _frameClass CONSTANT) - Q_PROPERTY(int frameType READ frameType NOTIFY frameTypeChanged) - Q_PROPERTY(int defaultFrameType MEMBER _defaultFrameType CONSTANT) - Q_PROPERTY(QString imageResource READ imageResource NOTIFY imageResourceChanged) - Q_PROPERTY(bool frameTypeSupported MEMBER _frameTypeSupported CONSTANT) + Q_PROPERTY(QString name MEMBER _name CONSTANT) + Q_PROPERTY(int frameClass MEMBER _frameClass CONSTANT) + Q_PROPERTY(int frameType READ frameType NOTIFY frameTypeChanged) + Q_PROPERTY(QStringList frameTypeEnumStrings MEMBER _frameTypeEnumStrings CONSTANT) + Q_PROPERTY(QVariantList frameTypeEnumValues MEMBER _frameTypeEnumValues CONSTANT) + Q_PROPERTY(int defaultFrameType MEMBER _defaultFrameType CONSTANT) + Q_PROPERTY(QString imageResource READ imageResource NOTIFY imageResourceChanged) + Q_PROPERTY(QString imageResourceDefault MEMBER _imageResourceDefault CONSTANT) + Q_PROPERTY(bool frameTypeSupported MEMBER _frameTypeSupported CONSTANT) - int frameType (void) { return _frameTypeFact->rawValue().toInt(); }; + int frameType (void) { return _frameTypeFact->rawValue().toInt(); } QString imageResource (void); - QString _name; - bool _copter; - QString _imageResource; - int _frameClass; - int _defaultFrameType; - bool _frameTypeSupported; + QString _name; + bool _copter; + QString _imageResource; + QString _imageResourceDefault; + int _frameClass; + QStringList _frameTypeEnumStrings; + QVariantList _frameTypeEnumValues; + int _defaultFrameType; + bool _frameTypeSupported; signals: void imageResourceChanged(void);