diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc index b2c4785e1db0a0508bcd92ebf1d1ef9244f3ee97..8f6dcd2f1aaef02b3c4df2a41061fbc3ba334efa 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc @@ -11,28 +11,22 @@ #include "ArduCopterFirmwarePlugin.h" #include "ParameterManager.h" -const char* APMAirframeComponent::_oldFrameParam = "FRAME"; -const char* APMAirframeComponent::_newFrameParam = "FRAME_CLASS"; +const char* APMAirframeComponent::_frameClassParam = "FRAME_CLASS"; APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) - : VehicleComponent(vehicle, autopilot, parent) - , _requiresFrameSetup(false) - , _name(tr("Airframe")) + : VehicleComponent (vehicle, autopilot, parent) + , _name (tr("Frame")) + , _requiresFrameSetup (false) { - if (qobject_cast(_vehicle->firmwarePlugin()) != NULL) { - ParameterManager* paramMgr = _vehicle->parameterManager(); - _requiresFrameSetup = true; - if (paramMgr->parameterExists(FactSystem::defaultComponentId, _oldFrameParam)) { - _useNewFrameParam = false; - _frameParamFact = paramMgr->getParameter(FactSystem::defaultComponentId, _oldFrameParam); - MAV_TYPE vehicleType = vehicle->vehicleType(); - if (vehicleType == MAV_TYPE_TRICOPTER || vehicleType == MAV_TYPE_HELICOPTER) { - _requiresFrameSetup = false; - } - } else { - _useNewFrameParam = true; - _frameParamFact = paramMgr->getParameter(FactSystem::defaultComponentId, _newFrameParam); + ParameterManager* paramMgr = vehicle->parameterManager(); + + if (paramMgr->parameterExists(FactSystem::defaultComponentId, _frameClassParam)) { + _frameClassFact = paramMgr->getParameter(FactSystem::defaultComponentId, _frameClassParam); + if (vehicle->vehicleType() != MAV_TYPE_HELICOPTER) { + _requiresFrameSetup = true; } + } else { + _frameClassFact = nullptr; } } @@ -43,7 +37,7 @@ QString APMAirframeComponent::name(void) const QString APMAirframeComponent::description(void) const { - return tr("Airframe Setup is used to select the airframe which matches your vehicle."); + return tr("Frame Setup is used to select the airframe which matches your vehicle."); } QString APMAirframeComponent::iconResource(void) const @@ -59,11 +53,7 @@ bool APMAirframeComponent::requiresSetup(void) const bool APMAirframeComponent::setupComplete(void) const { if (_requiresFrameSetup) { - if (_useNewFrameParam) { - return _frameParamFact->rawValue().toInt() > 0; - } else { - return _frameParamFact->rawValue().toInt() >= 0; - } + return _frameClassFact->rawValue().toInt() != 0; } else { return true; } @@ -74,7 +64,7 @@ QStringList APMAirframeComponent::setupCompleteChangedTriggerList(void) const QStringList list; if (_requiresFrameSetup) { - list << (_useNewFrameParam ? _newFrameParam : _oldFrameParam); + list << _frameClassParam; } return list; diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.h b/src/AutoPilotPlugins/APM/APMAirframeComponent.h index 8b95b471d7f58200cd1303d96208fa1c411e7ffa..1f24bd5ffc935047bcf307311d2b3c99a28d1df4 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.h +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.h @@ -35,11 +35,9 @@ public: private: bool _requiresFrameSetup; ///< true: FRAME parameter must be set const QString _name; - Fact* _frameParamFact; - bool _useNewFrameParam; + Fact* _frameClassFact; - static const char* _oldFrameParam; - static const char* _newFrameParam; + static const char* _frameClassParam; }; #endif diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml index 6547c190df18ef7527c94f7a734324401edc6eca..e7dbb7e9d60aede3f5f5a5a0dc71c66be1d3f4b6 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.qml @@ -31,12 +31,13 @@ SetupPage { id: mainColumn width: availableWidth - property real _minW: ScreenTools.defaultFontPixelWidth * 20 - property real _boxWidth: _minW - property real _boxSpace: ScreenTools.defaultFontPixelWidth - property real _margins: ScreenTools.defaultFontPixelWidth - property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS") - property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE") + property real _minW: ScreenTools.defaultFontPixelWidth * 20 + property real _boxWidth: _minW + property real _boxSpace: ScreenTools.defaultFontPixelWidth + property real _margins: ScreenTools.defaultFontPixelWidth + property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS") + property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE", false) // FRAME_TYPE is not available on all Rover versions + property bool _frameTypeAvailable: controller.parameterExists(-1, "FRAME_TYPE") readonly property real spacerHeight: ScreenTools.defaultFontPixelHeight @@ -71,7 +72,9 @@ SetupPage { Layout.fillWidth: true text: (_frameClass.rawValue === 0 ? qsTr("Airframe is currently not set.") : - qsTr("Currently set to frame class '%1' and frame type '%2'.").arg(_frameClass.enumStringValue).arg(_frameType.enumStringValue)) + + qsTr("Currently set to frame class '%1'").arg(_frameClass.enumStringValue) + + (_frameTypeAvailable ? qsTr(" and frame type '%2'").arg(_frameType.enumStringValue) : "") + + qsTr(".", "period for end of sentence")) + qsTr(" To change this configuration, select the desired frame class below and frame type.") font.family: ScreenTools.demiboldFontFamily wrapMode: Text.WordWrap diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc index 8f80a4a5ddd9e63c73cc3bdaa602cc5c4c1beefa..f89d8557d474fadfb79d1f95fad44492ffba0989 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc @@ -13,6 +13,8 @@ #include "QGCApplication.h" #include "QGCFileDownload.h" #include "ParameterManager.h" +#include "ArduCopterFirmwarePlugin.h" +#include "ArduRoverFirmwarePlugin.h" #include #include @@ -21,8 +23,7 @@ #include #include - -// These should match the FRAME_CLASS parameter enum meta data +// These should match the ArduCopter FRAME_CLASS parameter enum meta data #define FRAME_CLASS_UNDEFINED 0 #define FRAME_CLASS_QUAD 1 #define FRAME_CLASS_HEX 2 @@ -38,7 +39,7 @@ #define FRAME_CLASS_DODECAHEXA 12 #define FRAME_CLASS_HELIQUAD 13 -// These should match the FRAME_TYPE parameter enum meta data +// These should match the ArduCopter FRAME_TYPE parameter enum meta data #define FRAME_TYPE_PLUS 0 #define FRAME_TYPE_X 1 #define FRAME_TYPE_V 2 @@ -51,13 +52,24 @@ #define FRAME_TYPE_DJIX 13 #define FRAME_TYPE_CLOCKWISEX 14 +// These should match the Rover FRAME_CLASS parameter enum meta data +#define FRAME_CLASS_ROVER 1 +#define FRAME_CLASS_BOAT 2 +#define FRAME_CLASS_BALANCEBOT 3 + +// These should match the Rover FRAME_TYPE parameter enum meta data +#define FRAME_TYPE_UNDEFINED 0 +#define FRAME_TYPE_OMNI3 1 +#define FRAME_TYPE_OMNIX 2 +#define FRAME_TYPE_OMNIPLUS 3 + typedef struct { int frameClass; int frameType; const char* imageResource; } FrameToImageInfo_t; -static const FrameToImageInfo_t s_rgFrameToImage[] = { +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" }, @@ -77,10 +89,15 @@ static const FrameToImageInfo_t s_rgFrameToImage[] = { { FRAME_CLASS_TRI, -1, "YPlus" }, }; -static QString s_findImageResource(int frameClass, int frameType) +static const FrameToImageInfo_t s_rgFrameToImageRover[] = { + { FRAME_CLASS_ROVER, -1, "Rover" }, + { FRAME_CLASS_BOAT, -1, "Boat" }, +}; + +static QString s_findImageResourceCopter(int frameClass, int frameType) { - for (size_t i=0; iframeClass == frameClass && pFrameToImageInfo->frameType == frameType) { return pFrameToImageInfo->imageResource; @@ -92,9 +109,24 @@ static QString s_findImageResource(int frameClass, int frameType) return QStringLiteral("AirframeUnknown"); } +static QString s_findImageResourceRover(int frameClass, int frameType) +{ + Q_UNUSED(frameType); + + for (size_t i=0; iframeClass == frameClass) { + return pFrameToImageInfo->imageResource; + } + } + + return QStringLiteral("AirframeUnknown"); +} + APMAirframeComponentController::APMAirframeComponentController(void) : _frameClassFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_CLASS"))) - , _frameTypeFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_TYPE"))) + , _frameTypeFact (getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME_TYPE"), false /* reportMissing */)) , _frameClassModel (new QmlObjectListModel(this)) { _fillFrameClasses(); @@ -107,26 +139,48 @@ APMAirframeComponentController::~APMAirframeComponentController() void APMAirframeComponentController::_fillFrameClasses() { - QList frameTypeNotSupported; - - frameTypeNotSupported << FRAME_CLASS_HELI - << FRAME_CLASS_SINGLECOPTER - << FRAME_CLASS_COAXCOPTER - << FRAME_CLASS_BICOPTER - << FRAME_CLASS_HELI_DUAL - << FRAME_CLASS_HELIQUAD; - - for (int i=1; i<_frameClassFact->enumStrings().count(); i++) { - QString frameClassName = _frameClassFact->enumStrings()[i]; - int frameClass = _frameClassFact->enumValues()[i].toInt(); - int defaultFrameType; - - if (frameTypeNotSupported.contains(frameClass)) { - defaultFrameType = -1; - } else { - defaultFrameType = FRAME_TYPE_X; + FirmwarePlugin* fwPlugin = _vehicle->firmwarePlugin(); + + if (qobject_cast(fwPlugin)) { + QList frameTypeNotSupported; + + frameTypeNotSupported << FRAME_CLASS_HELI + << FRAME_CLASS_SINGLECOPTER + << FRAME_CLASS_COAXCOPTER + << FRAME_CLASS_BICOPTER + << FRAME_CLASS_HELI_DUAL + << FRAME_CLASS_HELIQUAD; + + 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)); + } + } 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, frameClass, _frameTypeFact, defaultFrameType, _frameClassModel)); } } @@ -216,16 +270,19 @@ void APMAirframeComponentController::_paramFileDownloadError(QString errorMsg) qgcApp()->restoreOverrideCursor(); } -APMFrameClass::APMFrameClass(const QString& name, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent) +APMFrameClass::APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent) : QObject (parent) , _name (name) + , _copter (copter) , _frameClass (frameClass) , _defaultFrameType (defaultFrameType) , _frameTypeSupported (defaultFrameType != -1) , _frameTypeFact (frameTypeFact) { - connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::imageResourceChanged); - connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::frameTypeChanged); + if (frameTypeFact) { + connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::imageResourceChanged); + connect(frameTypeFact, &Fact::rawValueChanged, this, &APMFrameClass::frameTypeChanged); + } } APMFrameClass::~APMFrameClass() @@ -235,5 +292,14 @@ APMFrameClass::~APMFrameClass() QString APMFrameClass::imageResource(void) { - return QStringLiteral("/qmlimages/Airframe/%1").arg(s_findImageResource(_frameClass, _frameTypeFact->rawValue().toInt())); + QString imageResource; + + int frameType = _frameTypeFact ? _frameTypeFact->rawValue().toInt() : -1; + + if (_copter) { + imageResource = s_findImageResourceCopter(_frameClass, frameType); + } else { + imageResource = s_findImageResourceRover(_frameClass, frameType); + } + return QStringLiteral("/qmlimages/Airframe/%1").arg(imageResource); } diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h index 456b8bdb99b3ff3a728b3c99e85c47461b0bc827..16bb24bc1d859c377354d23964c79004e005f9f1 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.h +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.h @@ -54,7 +54,7 @@ class APMFrameClass : public QObject Q_OBJECT public: - APMFrameClass(const QString& name, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent = nullptr); + APMFrameClass(const QString& name, bool copter, int frameClass, Fact* frameTypeFact, int defaultFrameType, QObject* parent = nullptr); ~APMFrameClass(); Q_PROPERTY(QString name MEMBER _name CONSTANT) @@ -68,6 +68,7 @@ public: QString imageResource (void); QString _name; + bool _copter; QString _imageResource; int _frameClass; int _defaultFrameType; diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml index d5f6e3261cc59e7354130aa4e6a3ac625ebc0438..09b6fe94445062a30a31606ecc5109ac867a3c08 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml @@ -18,32 +18,23 @@ FactPanel { factPanel: panel } - property bool _frameAvailable: controller.parameterExists(-1, "FRAME") - - property Fact _frame: controller.getParameterFact(-1, "FRAME", false) - property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS", false) + property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS") property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE", false) + property bool _frameTypeAvailable: controller.parameterExists(-1, "FRAME_TYPE") Column { anchors.fill: parent - VehicleSummaryRow { - labelText: qsTr("Frame Type") - valueText: visible ? controller.currentAirframeTypeName() + " " + _frame.enumStringValue : "" - visible: _frameAvailable - } - VehicleSummaryRow { labelText: qsTr("Frame Class") - valueText: visible ? _frameClass.enumStringValue : "" - visible: !_frameAvailable + valueText: _frameClass.enumStringValue } VehicleSummaryRow { labelText: qsTr("Frame Type") valueText: visible ? _frameType.enumStringValue : "" - visible: !_frameAvailable + visible: _frameTypeAvailable } VehicleSummaryRow { diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index ea3e6aded19985f502c5c54b88c940a84d7be01a..3c005d101abd31ab03b02be10289e4b125c0c33e 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -132,7 +132,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name if (reportMissing) { _reportMissingParameter(componentId, name); } - return NULL; + return nullptr; } }