diff --git a/QGCApplication.pro b/QGCApplication.pro index 15517ec3ea684caf76f42cabb2626f8e94038abc..67f34fca37bb2c01d44c640b34f59429019639e9 100644 --- a/QGCApplication.pro +++ b/QGCApplication.pro @@ -620,7 +620,6 @@ INCLUDEPATH += \ HEADERS += \ src/FactSystem/Fact.h \ - src/FactSystem/FactBinder.h \ src/FactSystem/FactMetaData.h \ src/FactSystem/FactSystem.h \ src/FactSystem/FactValidator.h \ @@ -629,7 +628,6 @@ HEADERS += \ SOURCES += \ src/FactSystem/Fact.cc \ - src/FactSystem/FactBinder.cc \ src/FactSystem/FactMetaData.cc \ src/FactSystem/FactSystem.cc \ src/FactSystem/FactValidator.cc \ diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index 932b430d9c0793cf25186f70e55d0eacf93fc84c..41765aeecf8d53faba5742d0cbb1f58c5527d058 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -43,6 +43,11 @@ AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) : connect(this, &AutoPilotPlugin::pluginReadyChanged, this, &AutoPilotPlugin::_pluginReadyChanged); } +AutoPilotPlugin::~AutoPilotPlugin() +{ + +} + void AutoPilotPlugin::_uasDisconnected(void) { _pluginReady = false; @@ -112,14 +117,14 @@ void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& na _getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); } -bool AutoPilotPlugin::parameterExists(const QString& name) +bool AutoPilotPlugin::parameterExists(int componentId, const QString& name) { - return _getParameterLoader()->parameterExists(FactSystem::defaultComponentId, name); + return _getParameterLoader()->parameterExists(componentId, name); } -Fact* AutoPilotPlugin::getParameterFact(const QString& name) +Fact* AutoPilotPlugin::getParameterFact(int componentId, const QString& name) { - return _getParameterLoader()->getFact(FactSystem::defaultComponentId, name); + return _getParameterLoader()->getFact(componentId, name); } bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 4f635afb96528d743f2736de63686d8c7d0e282a..4fbd9435f3d84e3e39a060183f898868713cc9ec 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -51,6 +51,7 @@ class AutoPilotPlugin : public QObject public: AutoPilotPlugin(UASInterface* uas, QObject* parent); + ~AutoPilotPlugin(); /// true: plugin is ready for use, plugin should no longer be used Q_PROPERTY(bool pluginReady READ pluginReady NOTIFY pluginReadyChanged) @@ -71,16 +72,16 @@ public: Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix); /// Returns true if the specifed parameter exists from the default component - Q_INVOKABLE bool parameterExists(const QString& name); + Q_INVOKABLE bool parameterExists(int componentId, const QString& name); /// Returns all parameter names /// FIXME: component id missing, generic to fact QStringList parameterNames(void); /// Returns the specified parameter Fact from the default component - /// WARNING: Will assert if fact does not exists. If that possibility exists, check for existince first with - /// factExists. - Fact* getParameterFact(const QString& name); + /// WARNING: Returns a default Fact if parameter does not exists. If that possibility exists, check for existince first with + /// parameterExists. + Fact* getParameterFact(int componentId, const QString& name); /// Writes the parameter facts to the specified stream void writeParametersToStream(QTextStream &stream); diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.cc b/src/AutoPilotPlugins/AutoPilotPluginManager.cc index 624f0073806fc060cdaa7450ed550654f6ce2b7d..a18cb4eb96965d62b4af305a0f0a1a988887a20d 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.cc +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.cc @@ -74,13 +74,13 @@ void AutoPilotPluginManager::_uasCreated(UASInterface* uas) case MAV_AUTOPILOT_PX4: plugin = new PX4AutoPilotPlugin(uas, this); Q_CHECK_PTR(plugin); - _pluginMap[MAV_AUTOPILOT_PX4][uasId] = plugin; + _pluginMap[MAV_AUTOPILOT_PX4][uasId] = QSharedPointer(plugin); break; case MAV_AUTOPILOT_GENERIC: default: plugin = new GenericAutoPilotPlugin(uas, this); Q_CHECK_PTR(plugin); - _pluginMap[MAV_AUTOPILOT_GENERIC][uasId] = plugin; + _pluginMap[MAV_AUTOPILOT_GENERIC][uasId] = QSharedPointer(plugin); } } @@ -94,12 +94,12 @@ void AutoPilotPluginManager::_uasDeleted(UASInterface* uas) Q_ASSERT(uasId != 0); if (_pluginMap.contains(autopilotType) && _pluginMap[autopilotType].contains(uasId)) { - delete _pluginMap[autopilotType][uasId]; + _pluginMap[autopilotType][uasId].clear(); _pluginMap[autopilotType].remove(uasId); } } -AutoPilotPlugin* AutoPilotPluginManager::getInstanceForAutoPilotPlugin(UASInterface* uas) +QSharedPointer AutoPilotPluginManager::getInstanceForAutoPilotPlugin(UASInterface* uas) { Q_ASSERT(uas); diff --git a/src/AutoPilotPlugins/AutoPilotPluginManager.h b/src/AutoPilotPlugins/AutoPilotPluginManager.h index 03c76074438421736dbb1d92ee1d29b1657a0961..aa3808bae42c5b93164b04583d62542a211d63a8 100644 --- a/src/AutoPilotPlugins/AutoPilotPluginManager.h +++ b/src/AutoPilotPlugins/AutoPilotPluginManager.h @@ -47,9 +47,10 @@ class AutoPilotPluginManager : public QGCSingleton DECLARE_QGC_SINGLETON(AutoPilotPluginManager, AutoPilotPluginManager) public: - /// Returns the singleton AutoPilotPlugin instance for the specified uas. + /// Returns the singleton AutoPilotPlugin instance for the specified uas. Returned as QSharedPointer + /// to prevent shutdown ordering problems with Qml destruction happening after Facts are destroyed. /// @param uas Uas to get plugin for - AutoPilotPlugin* getInstanceForAutoPilotPlugin(UASInterface* uas); + QSharedPointer getInstanceForAutoPilotPlugin(UASInterface* uas); typedef struct { uint8_t baseMode; @@ -73,7 +74,7 @@ private: MAV_AUTOPILOT _installedAutopilotType(MAV_AUTOPILOT autopilot); - QMap > _pluginMap; ///< Map of AutoPilot plugins _pluginMap[MAV_TYPE][UASid] + QMap > > _pluginMap; ///< Map of AutoPilot plugins _pluginMap[MAV_TYPE][UASid] }; #endif diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.cc b/src/AutoPilotPlugins/PX4/AirframeComponent.cc index e9e4cd7db6dc503bae186d8f5663f02be3ebd705..f3c5fcd276b768c6ec7890dce6df154527efde63 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.cc @@ -142,7 +142,7 @@ bool AirframeComponent::requiresSetup(void) const bool AirframeComponent::setupComplete(void) const { - return _autopilot->getParameterFact("SYS_AUTOSTART")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->value().toInt() != 0; } QString AirframeComponent::setupStateDescription(void) const diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.qml b/src/AutoPilotPlugins/PX4/AirframeComponent.qml index cb4540f84b20fef331b41a1996557b332e760b28..bf6e95858a44c25849ba31713a994b23b063eeec 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.qml +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.qml @@ -31,6 +31,7 @@ import QGroundControl.FactControls 1.0 import QGroundControl.Palette 1.0 import QGroundControl.Controls 1.0 import QGroundControl.Controllers 1.0 +import QGroundControl.ScreenTools 1.0 QGCView { id: rootQGCView @@ -67,7 +68,7 @@ QGCView { "This configuration can only be modified through the Parameter Editor.\n\n" + "If you want to Reset your airframe configuration and select a standard configuration, click 'Reset' above." - Fact { id: sys_autostart; name: "SYS_AUTOSTART" } + property Fact sys_autostart: controller.getParameterFact(-1, "SYS_AUTOSTART") function accept() { sys_autostart.value = 0 @@ -107,7 +108,7 @@ QGCView { QGCLabel { id: header width: parent.width - font.pointSize: 20 + font.pointSize: ScreenTools.largeFontPointSize text: "AIRFRAME CONFIG" } diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc index ef516a8be5cac42326143dfda69eca16b7032a21..62674d32c9ccb190f48524d29134a5d2a869dffe 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentController.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponentController.cc @@ -48,16 +48,16 @@ AirframeComponentController::AirframeComponentController(void) : qmlRegisterUncreatableType("QGroundControl.Controllers", 1, 0, "Aiframe", "Can only reference Airframe"); } - QStringList usedFacts; - usedFacts << "SYS_AUTOSTART" << "SYS_AUTOCONFIG"; - if (!_allFactsExists(usedFacts)) { + QStringList usedParams; + usedParams << "SYS_AUTOSTART" << "SYS_AUTOCONFIG"; + if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) { return; } // Load up member variables bool autostartFound = false; - _autostartId = _autopilot->getParameterFact("SYS_AUTOSTART")->value().toInt(); + _autostartId = getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->value().toInt(); for (const AirframeComponentAirframes::AirframeType_t* pType=&AirframeComponentAirframes::rgAirframeTypes[0]; pType->name != NULL; pType++) { AirframeType* airframeType = new AirframeType(pType->name, pType->imageResource, this); @@ -99,9 +99,8 @@ void AirframeComponentController::changeAutostart(void) qgcApp()->setOverrideCursor(Qt::WaitCursor); - _autopilot->getParameterFact("SYS_AUTOSTART")->setValue(_autostartId); - _autopilot->getParameterFact("SYS_AUTOCONFIG")->setValue(1); - + getParameterFact(-1, "SYS_AUTOSTART")->setValue(_autostartId); + getParameterFact(-1, "SYS_AUTOCONFIG")->setValue(1); // Wait for the parameters to flow through system qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); diff --git a/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml b/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml index 2d47877e61c468c3eeb05c5426680d99859e3112..75dc76ddb01b8474dbc0e8b6a600b0a55462f7c1 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/AirframeComponentSummary.qml @@ -5,15 +5,18 @@ import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 import QGroundControl.Controllers 1.0 +import QGroundControl.Palette 1.0 FactPanel { id: panel anchors.fill: parent + color: qgcPal.windowShadeDark + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } AirframeComponentController { id: controller; factPanel: panel } - Fact { id: sysIdFact; name: "MAV_SYS_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: sysAutoStartFact; name: "SYS_AUTOSTART"; onFactMissing: showMissingFactOverlay(name) } + property Fact sysIdFact: controller.getParameterFact(-1, "MAV_SYS_ID") + property Fact sysAutoStartFact: controller.getParameterFact(-1, "SYS_AUTOSTART") property bool autoStartSet: sysAutoStartFact.value != 0 diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc index f0b03bd2eff55581879f0a2728a00d21ac3b48f3..f7f5e226657befcf5e9ab60220535f6e9534e038 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc @@ -73,7 +73,7 @@ bool FlightModesComponent::requiresSetup(void) const bool FlightModesComponent::setupComplete(void) const { - return _autopilot->getParameterFact("RC_MAP_MODE_SW")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->value().toInt() != 0; } QString FlightModesComponent::setupStateDescription(void) const diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml index 5c90016d68886c61ed9fa23be9423a1252951efa..bd76c307475e702c3ce6177b4662d52920c6fd75 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.qml +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.qml @@ -34,13 +34,14 @@ import QGroundControl.ScreenTools 1.0 Item { Loader { - property FlightModesComponentController controller: FlightModesComponentController { } + id: loader + anchors.fill: parent + sourceComponent: controller.validConfiguration ? validComponent : invalidComponent + + property FlightModesComponentController controller: FlightModesComponentController { factPanel: loader.item } property QGCPalette qgcPal: QGCPalette { colorGroupEnabled: true } property bool loading: true - anchors.fill: parent - sourceComponent: controller.validConfiguration ? validComponent : invalidComponent - onLoaded: loading = false } @@ -48,30 +49,28 @@ Item { id: validComponent FactPanel { - Fact { id: rc_map_throttle; name: "RC_MAP_THROTTLE"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_yaw; name: "RC_MAP_YAW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_pitch; name: "RC_MAP_PITCH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_roll; name: "RC_MAP_ROLL"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_flaps; name: "RC_MAP_FLAPS"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_aux1; name: "RC_MAP_AUX1"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_aux2; name: "RC_MAP_AUX2"; onFactMissing: showMissingFactOverlay(name) } - - Fact { id: rc_map_mode_sw; name: "RC_MAP_MODE_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_posctl_sw; name: "RC_MAP_POSCTL_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_return_sw; name: "RC_MAP_RETURN_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_offboard_sw; name: "RC_MAP_OFFB_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_loiter_sw; name: "RC_MAP_LOITER_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_map_acro_sw; name: "RC_MAP_ACRO_SW"; onFactMissing: showMissingFactOverlay(name) } - - Fact { id: rc_posctl_th; name: "RC_POSCTL_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_return_th; name: "RC_RETURN_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_offboard_th; name: "RC_OFFB_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_loiter_th; name: "RC_LOITER_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_acro_th; name: "RC_ACRO_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_assist_th; name: "RC_ASSIST_TH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: rc_auto_th; name: "RC_AUTO_TH"; onFactMissing: showMissingFactOverlay(name) } - - Fact { id: rc_th_user; name: "RC_TH_USER"; onFactMissing: showMissingFactOverlay(name) } + property Fact rc_map_throttle: controller.getParameterFact(-1, "RC_MAP_THROTTLE") + property Fact rc_map_yaw: controller.getParameterFact(-1, "RC_MAP_YAW") + property Fact rc_map_pitch: controller.getParameterFact(-1, "RC_MAP_PITCH") + property Fact rc_map_roll: controller.getParameterFact(-1, "RC_MAP_ROLL") + property Fact rc_map_flaps: controller.getParameterFact(-1, "RC_MAP_FLAPS") + property Fact rc_map_aux1: controller.getParameterFact(-1, "RC_MAP_AUX1") + property Fact rc_map_aux2: controller.getParameterFact(-1, "RC_MAP_AUX2") + + property Fact rc_map_mode_sw: controller.getParameterFact(-1, "RC_MAP_MODE_SW") + property Fact rc_map_posctl_sw: controller.getParameterFact(-1, "RC_MAP_POSCTL_SW") + property Fact rc_map_return_sw: controller.getParameterFact(-1, "RC_MAP_RETURN_SW") + property Fact rc_map_offboard_sw: controller.getParameterFact(-1, "RC_MAP_OFFB_SW") + property Fact rc_map_loiter_sw: controller.getParameterFact(-1, "RC_MAP_LOITER_SW") + + property Fact rc_assist_th: controller.getParameterFact(-1, "RC_ASSIST_TH") + property Fact rc_posctl_th: controller.getParameterFact(-1, "RC_POSCTL_TH") + property Fact rc_auto_th: controller.getParameterFact(-1, "RC_AUTO_TH") + property Fact rc_loiter_th: controller.getParameterFact(-1, "RC_LOITER_TH") + property Fact rc_return_th: controller.getParameterFact(-1, "RC_RETURN_TH") + property Fact rc_offboard_th: controller.getParameterFact(-1, "RC_OFFB_TH") + + property Fact rc_th_user: controller.getParameterFact(-1, "RC_TH_USER") property int throttleChannel: rc_map_throttle.value property int yawChannel: rc_map_yaw.value @@ -135,7 +134,7 @@ Item { id: unassignedModeTileComponent Rectangle { - Fact { id: fact; name: tileParam; onFactMissing: showMissingFactOverlay(name) } + property Fact fact: controller.getParameterFact(-1, tileParam) property bool dragEnabled: fact.value == 0 id: outerRect @@ -221,7 +220,8 @@ Item { id: assignedModeTileComponent Rectangle { - Fact { id: fact; name: tileDragEnabled ? tileParam : ""; onFactMissing: showMissingFactOverlay(name) } + Fact{ id: nullFact } + property Fact fact: tileDragEnabled ? controller.getParameterFact(-1, tileParam) : nullFact width: tileWidth height: tileHeight @@ -362,7 +362,7 @@ Item { QGCLabel { text: "FLIGHT MODES CONFIG" - font.pointSize: ScreenTools.fontPointFactor * (20); + font.pointSize: ScreenTools.largeFontPointSize } Item { height: 20; width: 10 } // spacer @@ -624,10 +624,10 @@ Item { Item { height: 20; width: 10 } // spacer FactCheckBox { - checkedValue: 0 + checkedValue: 0 uncheckedValue: 1 - fact: rc_th_user - text: "Allow setup to generate the thresholds for the flight mode positions within a switch (recommended)" + fact: rc_th_user + text: "Allow setup to generate the thresholds for the flight mode positions within a switch (recommended)" } Item { height: 20; width: 10 } // spacer @@ -639,8 +639,9 @@ Item { text: "Switch Display" } QGCCheckBox { - checked: controller.sendLiveRCSwitchRanges - text: "Show live RC display" + checked: controller.sendLiveRCSwitchRanges + text: "Show live RC display" + onClicked: { controller.sendLiveRCSwitchRanges = checked } @@ -650,11 +651,11 @@ Item { Item { height: 20; width: 10 } // spacer Row { - property bool modeSwitchVisible: modeChannel != 0 - property bool loiterSwitchVisible: loiterChannel != 0 && loiterChannel != modeChannel && loiterChannel != returnChannel - property bool posCtlSwitchVisible: posCtlChannel != 0 && posCtlChannel != modeChannel - property bool returnSwitchVisible: returnChannel != 0 - property bool offboardSwitchVisible: offboardChannel != 0 + property bool modeSwitchVisible: modeChannel != 0 + property bool loiterSwitchVisible: loiterChannel != 0 && loiterChannel != modeChannel && loiterChannel != returnChannel + property bool posCtlSwitchVisible: posCtlChannel != 0 && posCtlChannel != modeChannel + property bool returnSwitchVisible: returnChannel != 0 + property bool offboardSwitchVisible: offboardChannel != 0 width: parent.width spacing: 20 @@ -882,7 +883,7 @@ Item { Component { id: invalidComponent - Rectangle { + FactPanel { anchors.fill: parent color: qgcPal.window diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc index e603cabe99501fcf7af7ba5ad0b3de1cf65946d8..8d676838b2a033c8194ab5da18c25dd537a3407f 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.cc @@ -32,20 +32,17 @@ #include #include -FlightModesComponentController::FlightModesComponentController(QObject* parent) : - QObject(parent), +FlightModesComponentController::FlightModesComponentController(void) : _liveRCValues(false), _validConfiguration(false), - _channelCount(18), - _autoPilotPlugin(NULL) + _channelCount(18) { - _uas = UASManager::instance()->getActiveUAS(); - Q_ASSERT(_uas); + QStringList usedParams; + usedParams << "RC_MAP_THROTTLE" << "RC_MAP_YAW" << "RC_MAP_PITCH" << "RC_MAP_ROLL" << "RC_MAP_FLAPS" << "RC_MAP_AUX1" << "RC_MAP_AUX2" << "RC_MAP_ACRO_SW"; + if (!_allParametersExists(FactSystem::defaultComponentId, usedParams)) { + return; + } - _autoPilotPlugin = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas); - Q_ASSERT(_autoPilotPlugin); - Q_ASSERT(_autoPilotPlugin->pluginReady()); - _initRcValues(); _validateConfiguration(); } @@ -69,16 +66,14 @@ void FlightModesComponentController::_validateConfiguration(void) { _validConfiguration = true; - _channelCount = _autoPilotPlugin->parameterExists("RC_CHAN_CNT") ? - _autoPilotPlugin->getParameterFact("RC_CHAN_CNT")->value().toInt() : - _chanMax; + _channelCount = parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT") ? getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->value().toInt() : _chanMax; if (_channelCount <= 0 || _channelCount > _chanMax) { // Parameter exists, but has not yet been set or is invalid. Use default _channelCount = _chanMax; } // Acro is not full supported yet. If Acro is mapped you uhave to set up the hard way. - if (_autoPilotPlugin->getParameterFact("RC_MAP_ACRO_SW")->value().toInt() != 0) { + if (getParameterFact(FactSystem::defaultComponentId, "RC_MAP_ACRO_SW")->value().toInt() != 0) { _validConfiguration = false; _configurationErrors += "Flight Mode setup does not yet support Acro switch"; } @@ -92,7 +87,7 @@ void FlightModesComponentController::_validateConfiguration(void) switchNames << "Mode Switch" << "Return Switch" << "Loiter Switch" << "PosCtl Switch" << "Offboard Switch"; for(int i=0; igetParameterFact(switchParams[i])->value().toInt(); + int map = getParameterFact(FactSystem::defaultComponentId, switchParams[i])->value().toInt(); switchMappings << map; if (map < 0 || map > _channelCount) { @@ -109,7 +104,7 @@ void FlightModesComponentController::_validateConfiguration(void) attitudeNames << "Throttle" << "Yaw" << "Pitch" << "Roll" << "Flaps" << "Aux1" << "Aux2" << "Acro"; for (int i=0; igetParameterFact(attitudeParams[i])->value().toInt(); + int map = getParameterFact(FactSystem::defaultComponentId, attitudeParams[i])->value().toInt(); for (int j=0; jgetParameterFact(singleSwitchParams[i])->value().toInt(); + int map = getParameterFact(FactSystem::defaultComponentId, singleSwitchParams[i])->value().toInt(); for (int j=0; jgetParameterFact(rcMinParam)->value().toInt(); - _rgRCMax[i] = _autoPilotPlugin->getParameterFact(rcMaxParam)->value().toInt(); + _rgRCMin[i] = getParameterFact(FactSystem::defaultComponentId, rcMinParam)->value().toInt(); + _rgRCMax[i] = getParameterFact(FactSystem::defaultComponentId, rcMaxParam)->value().toInt(); - float floatReversed = _autoPilotPlugin->getParameterFact(rcRevParam)->value().toFloat(); + float floatReversed = getParameterFact(-1, rcRevParam)->value().toFloat(); _rgRCReversed[i] = floatReversed == -1.0f; } @@ -196,7 +191,7 @@ double FlightModesComponentController::_switchLiveRange(const QString& param) { QVariant value; - int channel = _autoPilotPlugin->getParameterFact(param)->value().toInt(); + int channel = getParameterFact(-1, param)->value().toInt(); if (channel == 0) { return 1.0; } else { diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentController.h b/src/AutoPilotPlugins/PX4/FlightModesComponentController.h index 8fa0448b4d24604ca03fbfc9f83d6d846edaa265..cefc4df0e74fc7ae7bc91dd2d7dc5f1ff56f4ae0 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentController.h +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentController.h @@ -33,14 +33,15 @@ #include "UASInterface.h" #include "AutoPilotPlugin.h" +#include "FactPanelController.h" /// MVC Controller for FlightModesComponent.qml. -class FlightModesComponentController : public QObject +class FlightModesComponentController : public FactPanelController { Q_OBJECT public: - FlightModesComponentController(QObject* parent = NULL); + FlightModesComponentController(void); ~FlightModesComponentController(); Q_PROPERTY(bool validConfiguration MEMBER _validConfiguration CONSTANT) @@ -79,8 +80,6 @@ private: static const int _chanMax = 18; - UASInterface* _uas; - QList _rcValues; bool _liveRCValues; int _rgRCMin[_chanMax]; @@ -90,8 +89,6 @@ private: bool _validConfiguration; QString _configurationErrors; int _channelCount; - - AutoPilotPlugin* _autoPilotPlugin; }; #endif diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml b/src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml index 451bf8aa32990595e0e7819f5657c5e8f6cb90ab..bbf7cf4438726927d797a246c435d79856fcca9d 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/FlightModesComponentSummary.qml @@ -4,14 +4,20 @@ import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 FactPanel { - anchors.fill: parent + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark - Fact { id: modeSwFact; name: "RC_MAP_MODE_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: posCtlSwFact; name: "RC_MAP_POSCTL_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: loiterSwFact; name: "RC_MAP_LOITER_SW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: returnSwFact; name: "RC_MAP_RETURN_SW"; onFactMissing: showMissingFactOverlay(name) } + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact modeSwFact: controller.getParameterFact(-1, "RC_MAP_MODE_SW") + property Fact posCtlSwFact: controller.getParameterFact(-1, "RC_MAP_POSCTL_SW") + property Fact loiterSwFact: controller.getParameterFact(-1, "RC_MAP_LOITER_SW") + property Fact returnSwFact: controller.getParameterFact(-1, "RC_MAP_RETURN_SW") Column { anchors.fill: parent diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index 469ec176e9b591be94df79bd6e1d646f3c2f017c..643fe81f6824a0ad31e8ff27cc58a04933c6fe6e 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -249,7 +249,7 @@ void PX4AutoPilotPlugin::_pluginReadyPreChecks(void) // Check for older parameter version set // FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp // should be used instead. - if (parameterExists("SENS_GYRO_XOFF")) { + if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF")) { _incorrectParameterVersion = true; QGCMessageBox::warning("Setup", "This version of GroundControl can only perform vehicle setup on a newer version of firmware. " "Please perform a Firmware Upgrade if you wish to use Vehicle Setup."); diff --git a/src/AutoPilotPlugins/PX4/PX4Component.cc b/src/AutoPilotPlugins/PX4/PX4Component.cc index 81072833ab7a6ffb213d915c8122416ce480b7b4..85fd90983146fa8a01195163930ad4694539b254 100644 --- a/src/AutoPilotPlugins/PX4/PX4Component.cc +++ b/src/AutoPilotPlugins/PX4/PX4Component.cc @@ -39,7 +39,7 @@ void PX4Component::setupTriggerSignals(void) { // Watch for changed on trigger list params foreach (QString paramName, setupCompleteChangedTriggerList()) { - Fact* fact = _autopilot->getParameterFact(paramName); + Fact* fact = _autopilot->getParameterFact(FactSystem::defaultComponentId, paramName); connect(fact, &Fact::valueChanged, this, &PX4Component::_triggerUpdated); } diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index d1bf8fef201d5dcaf588073ebc3f7d2eefdce2a3..469f3dd0d5b7c94249c0f8dddb5d897730c9fb65 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -58,9 +58,9 @@ bool PowerComponent::requiresSetup(void) const bool PowerComponent::setupComplete(void) const { QVariant cvalue, evalue, nvalue; - return _autopilot->getParameterFact("BAT_V_CHARGED")->value().toFloat() != 0.0f && - _autopilot->getParameterFact("BAT_V_EMPTY")->value().toFloat() != 0.0f && - _autopilot->getParameterFact("BAT_N_CELLS")->value().toInt() != 0; + return _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->value().toFloat() != 0.0f && + _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->value().toFloat() != 0.0f && + _autopilot->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->value().toInt() != 0; } QString PowerComponent::setupStateDescription(void) const diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.qml b/src/AutoPilotPlugins/PX4/PowerComponent.qml index 8d709a06bfdb5e816e016468c2d3c0f0a28f6e87..efc80dda9ff2f206e2bff7be1c29eef7eca95dc2 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.qml +++ b/src/AutoPilotPlugins/PX4/PowerComponent.qml @@ -55,9 +55,10 @@ QGCView { property int firstColumnWidth: 220 property int textEditWidth: 80 - property Fact battNumCells: Fact { name: "BAT_N_CELLS"; onFactMissing: showMissingFactOverlay(name) } - property Fact battHighVolt: Fact { name: "BAT_V_CHARGED"; onFactMissing: showMissingFactOverlay(name) } - property Fact battLowVolt: Fact { name: "BAT_V_EMPTY"; onFactMissing: showMissingFactOverlay(name) } + property Fact battNumCells: controller.getParameterFact(-1, "BAT_N_CELLS") + property Fact battHighVolt: controller.getParameterFact(-1, "BAT_V_CHARGED") + property Fact battLowVolt: controller.getParameterFact(-1, "BAT_V_EMPTY") + property Fact battVoltLoadDrop: controller.getParameterFact(-1, "BAT_V_LOAD_DROP") property alias battHigh: battHighRow property alias battLow: battLowRow @@ -150,7 +151,7 @@ QGCView { FactTextField { id: cellsField width: textEditWidth - fact: Fact { name: "BAT_N_CELLS"; onFactMissing: showMissingFactOverlay(name) } + fact: battNumCells showUnits: true } } @@ -161,7 +162,7 @@ QGCView { FactTextField { id: battHighField width: textEditWidth - fact: Fact { name: "BAT_V_CHARGED"; onFactMissing: showMissingFactOverlay(name) } + fact: battHighVolt showUnits: true } } @@ -172,7 +173,7 @@ QGCView { FactTextField { id: battLowField width: textEditWidth - fact: Fact { name: "BAT_V_EMPTY"; onFactMissing: showMissingFactOverlay(name) } + fact: battLowVolt showUnits: true } } @@ -332,7 +333,7 @@ QGCView { FactTextField { id: battDropField width: textEditWidth - fact: Fact { name: "BAT_V_LOAD_DROP"; onFactMissing: showMissingFactOverlay(name) } + fact: battVoltLoadDrop showUnits: true } } diff --git a/src/AutoPilotPlugins/PX4/PowerComponentSummary.qml b/src/AutoPilotPlugins/PX4/PowerComponentSummary.qml index 86c3800fa9f13030d02d559d0f402cde1d645e44..3343295371c2ca35cc6610a5d013210290db2754 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/PowerComponentSummary.qml @@ -31,13 +31,19 @@ import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 FactPanel { - anchors.fill: parent + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark - Fact { id: batVChargedFact; name: "BAT_V_CHARGED"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: batVEmptyFact; name: "BAT_V_EMPTY"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: batCellsFact; name: "BAT_N_CELLS"; onFactMissing: showMissingFactOverlay(name) } + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact batVChargedFact: controller.getParameterFact(-1, "BAT_V_CHARGED") + property Fact batVEmptyFact: controller.getParameterFact(-1, "BAT_V_EMPTY") + property Fact batCellsFact: controller.getParameterFact(-1, "BAT_N_CELLS") Column { anchors.fill: parent diff --git a/src/AutoPilotPlugins/PX4/RadioComponent.cc b/src/AutoPilotPlugins/PX4/RadioComponent.cc index 275cc813968df5b093299d3c468e99763a655370..ad6ecd24028121effde8cb1f90bbfbb11f9bd6d0 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/RadioComponent.cc @@ -62,7 +62,7 @@ bool RadioComponent::setupComplete(void) const QStringList attitudeMappings; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; foreach(QString mapParam, attitudeMappings) { - if (_autopilot->getParameterFact(mapParam)->value().toInt() == 0) { + if (_autopilot->getParameterFact(FactSystem::defaultComponentId, mapParam)->value().toInt() == 0) { return false; } } @@ -80,13 +80,13 @@ bool RadioComponent::setupComplete(void) const QString param; param = QString("RC%1_MIN").arg(i); - rcMin = _autopilot->getParameterFact(param)->value().toInt(); + rcMin = _autopilot->getParameterFact(FactSystem::defaultComponentId, param)->value().toInt(); param = QString("RC%1_MAX").arg(i); - rcMax = _autopilot->getParameterFact(param)->value().toInt(); + rcMax = _autopilot->getParameterFact(FactSystem::defaultComponentId, param)->value().toInt(); param = QString("RC%1_TRIM").arg(i); - rcTrim = _autopilot->getParameterFact(param)->value().toInt(); + rcTrim = _autopilot->getParameterFact(FactSystem::defaultComponentId, param)->value().toInt(); if (rcMin == rcMinDefault && rcMax == rcMaxDefault && rcTrim == rcTrimDefault) { return false; diff --git a/src/AutoPilotPlugins/PX4/RadioComponentSummary.qml b/src/AutoPilotPlugins/PX4/RadioComponentSummary.qml index d74e4552d1d250f80367367b9555a8ab3c7ae546..663d2649bea978c6c4d0529b28422c6ffc6c817b 100644 --- a/src/AutoPilotPlugins/PX4/RadioComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/RadioComponentSummary.qml @@ -4,17 +4,23 @@ import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 FactPanel { - anchors.fill: parent - - Fact { id: mapRollFact; name: "RC_MAP_ROLL"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapPitchFact; name: "RC_MAP_PITCH"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapYawFact; name: "RC_MAP_YAW"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapThrottleFact; name: "RC_MAP_THROTTLE"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapFlapsFact; name: "RC_MAP_FLAPS"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapAux1Fact; name: "RC_MAP_AUX1"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: mapAux2Fact; name: "RC_MAP_AUX2"; onFactMissing: showMissingFactOverlay(name) } + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark + + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact mapRollFact: controller.getParameterFact(-1, "RC_MAP_ROLL") + property Fact mapPitchFact: controller.getParameterFact(-1, "RC_MAP_PITCH") + property Fact mapYawFact: controller.getParameterFact(-1, "RC_MAP_YAW") + property Fact mapThrottleFact: controller.getParameterFact(-1, "RC_MAP_THROTTLE") + property Fact mapFlapsFact: controller.getParameterFact(-1, "RC_MAP_FLAPS") + property Fact mapAux1Fact: controller.getParameterFact(-1, "RC_MAP_AUX1") + property Fact mapAux2Fact: controller.getParameterFact(-1, "RC_MAP_AUX2") Column { anchors.fill: parent diff --git a/src/AutoPilotPlugins/PX4/SafetyComponent.qml b/src/AutoPilotPlugins/PX4/SafetyComponent.qml index a955a4d2bf281a3f10a2babe2f8cf559b34e227d..7f340e3463867e708f9b38c126ef0c964938fa35 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponent.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponent.qml @@ -31,12 +31,11 @@ import QGroundControl.Palette 1.0 import QGroundControl.Controls 1.0 import QGroundControl.ScreenTools 1.0 -Rectangle { - QGCPalette { id: palette; colorGroupEnabled: true } +FactPanel { + id: panel - width: 600 - height: 600 - color: palette.window + QGCPalette { id: palette; colorGroupEnabled: true } + FactPanelController { id: controller; factPanel: panel } property int flightLineWidth: 2 // width of lines for flight graphic property int loiterAltitudeColumnWidth: 180 // width of loiter altitude column @@ -53,7 +52,7 @@ Rectangle { QGCLabel { text: "SAFETY CONFIG" - font.pointSize: ScreenTools.fontPointFactor * (20); + font.pointSize: ScreenTools.largeFontPointSize } Item { height: 20; width: 10 } // spacer @@ -61,7 +60,7 @@ Rectangle { //----------------------------------------------------------------- //-- Return Home Triggers - QGCLabel { text: "Triggers For Return Home"; color: palette.text; font.pointSize: ScreenTools.fontPointFactor * (20); } + QGCLabel { text: "Triggers For Return Home"; font.pointSize: ScreenTools.mediumFontPointSize; } Item { height: 10; width: 10 } // spacer @@ -84,29 +83,29 @@ Rectangle { QGCLabel { text: "RC Transmitter Signal Loss"; width: firstColumnWidth; anchors.baseline: rcLossField.baseline } QGCLabel { text: "Return Home after"; anchors.baseline: rcLossField.baseline } FactTextField { - id: rcLossField - fact: Fact { name: "COM_RC_LOSS_T" } - showUnits: true + id: rcLossField + fact: controller.getParameterFact(-1, "COM_RC_LOSS_T") + showUnits: true } } Row { spacing: 10 FactCheckBox { - id: telemetryTimeoutCheckbox - fact: Fact { name: "COM_DL_LOSS_EN" } - checkedValue: 1 - uncheckedValue: 0 - text: "Telemetry Signal Timeout" - anchors.baseline: telemetryLossField.baseline - width: firstColumnWidth + id: telemetryTimeoutCheckbox + anchors.baseline: telemetryLossField.baseline + width: firstColumnWidth + fact: controller.getParameterFact(-1, "COM_DL_LOSS_EN") + checkedValue: 1 + uncheckedValue: 0 + text: "Telemetry Signal Timeout" } QGCLabel { text: "Return Home after"; anchors.baseline: telemetryLossField.baseline } FactTextField { - id: telemetryLossField - fact: Fact { name: "COM_DL_LOSS_T" } - showUnits: true - enabled: telemetryTimeoutCheckbox.checked + id: telemetryLossField + fact: controller.getParameterFact(-1, "COM_DL_LOSS_T") + showUnits: true + enabled: telemetryTimeoutCheckbox.checked } } @@ -120,59 +119,61 @@ Rectangle { //----------------------------------------------------------------- //-- Return Home Settings - QGCLabel { text: "Return Home Settings"; font.pointSize: ScreenTools.fontPointFactor * (20); } + QGCLabel { text: "Return Home Settings"; font.pointSize: ScreenTools.mediumFontPointSize; } Item { height: 10; width: 10 } // spacer Rectangle { - width: parent.width + width: parent.width height: settingsColumn.height - color: palette.windowShade + color: palette.windowShade Column { - id: settingsColumn - width: parent.width - anchors.margins: shadedMargin - anchors.left: parent.left + id: settingsColumn + width: parent.width + anchors.margins: shadedMargin + anchors.left: parent.left Item { height: shadedMargin; width: 10 } // top margin // This item is the holder for the climb alt and loiter seconds fields Item { - width: parent.width + width: parent.width height: climbAltitudeColumn.height Column { - id: climbAltitudeColumn - spacing: controlVerticalSpacing + id: climbAltitudeColumn + spacing: controlVerticalSpacing QGCLabel { text: "Climb to altitude of" } FactTextField { - id: climbField - fact: Fact { name: "RTL_RETURN_ALT" } - showUnits: true + id: climbField + fact: controller.getParameterFact(-1, "RTL_RETURN_ALT") + showUnits: true } } Column { - x: flightGraphic.width - 200 - spacing: controlVerticalSpacing + x: flightGraphic.width - 200 + spacing: controlVerticalSpacing QGCCheckBox { - id: homeLoiterCheckbox - property Fact fact: Fact { name: "RTL_LAND_DELAY" } + id: homeLoiterCheckbox + checked: fact.value > 0 + text: "Loiter at Home altitude for" + + property Fact fact: controller.getParameterFact(-1, "RTL_LAND_DELAY") - checked: fact.value > 0 - text: "Loiter at Home altitude for" onClicked: { fact.value = checked ? 60 : -1 } } + FactTextField { - fact: Fact { name: "RTL_LAND_DELAY" } - showUnits: true - enabled: homeLoiterCheckbox.checked == true + fact: controller.getParameterFact(-1, "RTL_LAND_DELAY") + showUnits: true + enabled: homeLoiterCheckbox.checked == true } } } @@ -181,88 +182,88 @@ Rectangle { // This row holds the flight graphic and the home loiter alt column Row { - width: parent.width - spacing: 20 + width: parent.width + spacing: 20 // Flight graphic Item { - id: flightGraphic - width: parent.width - loiterAltitudeColumnWidth + id: flightGraphic + width: parent.width - loiterAltitudeColumnWidth height: 200 // controls the height of the flight graphic Rectangle { - x: planeWidth / 2 + x: planeWidth / 2 height: planeImage.y - 5 - width: flightLineWidth - color: palette.button + width: flightLineWidth + color: palette.button } Rectangle { - x: planeWidth / 2 + x: planeWidth / 2 height: flightLineWidth - width: parent.width - x - color: palette.button + width: parent.width - x + color: palette.button } Rectangle { - x: parent.width - flightLineWidth + x: parent.width - flightLineWidth height: parent.height - homeWidth - arrowToHomeSpacing - width: flightLineWidth - color: palette.button + width: flightLineWidth + color: palette.button } QGCColoredImage { - id: planeImage - y: parent.height - planeWidth - 40 - source: "/qml/SafetyComponentPlane.png" - fillMode: Image.PreserveAspectFit - width: planeWidth - height: planeWidth - smooth: true - color: palette.button + id: planeImage + y: parent.height - planeWidth - 40 + source: "/qml/SafetyComponentPlane.png" + fillMode: Image.PreserveAspectFit + width: planeWidth + height: planeWidth + smooth: true + color: palette.button } QGCColoredImage { - x: planeWidth + 70 - y: parent.height - height - 20 - width: 80 - height: parent.height / 2 - source: "/qml/SafetyComponentTree.svg" - fillMode: Image.Stretch - smooth: true - color: palette.windowShadeDark + x: planeWidth + 70 + y: parent.height - height - 20 + width: 80 + height: parent.height / 2 + source: "/qml/SafetyComponentTree.svg" + fillMode: Image.Stretch + smooth: true + color: palette.windowShadeDark } QGCColoredImage { - x: planeWidth + 15 - y: parent.height - height - width: 100 - height: parent.height * .75 - source: "/qml/SafetyComponentTree.svg" - fillMode: Image.PreserveAspectFit - smooth: true - color: palette.button + x: planeWidth + 15 + y: parent.height - height + width: 100 + height: parent.height * .75 + source: "/qml/SafetyComponentTree.svg" + fillMode: Image.PreserveAspectFit + smooth: true + color: palette.button } QGCColoredImage { - x: parent.width - (arrowWidth/2) - 1 - y: parent.height - homeWidth - arrowToHomeSpacing - 2 - source: "/qml/SafetyComponentArrowDown.png" - fillMode: Image.PreserveAspectFit - width: arrowWidth - height: arrowWidth - smooth: true - color: palette.button + x: parent.width - (arrowWidth/2) - 1 + y: parent.height - homeWidth - arrowToHomeSpacing - 2 + source: "/qml/SafetyComponentArrowDown.png" + fillMode: Image.PreserveAspectFit + width: arrowWidth + height: arrowWidth + smooth: true + color: palette.button } QGCColoredImage { - id: homeImage - x: parent.width - (homeWidth / 2) - y: parent.height - homeWidth - source: "/qml/SafetyComponentHome.png" - fillMode: Image.PreserveAspectFit - width: homeWidth - height: homeWidth - smooth: true - color: palette.button + id: homeImage + x: parent.width - (homeWidth / 2) + y: parent.height - homeWidth + source: "/qml/SafetyComponentHome.png" + fillMode: Image.PreserveAspectFit + width: homeWidth + height: homeWidth + smooth: true + color: palette.button } } @@ -270,15 +271,15 @@ Rectangle { spacing: controlVerticalSpacing QGCLabel { - text: "Home loiter altitude"; - color: palette.text; - enabled: homeLoiterCheckbox.checked === true + text: "Home loiter altitude"; + color: palette.text; + enabled: homeLoiterCheckbox.checked === true } FactTextField { - id: descendField; - fact: Fact { name: "RTL_DESCEND_ALT" } - enabled: homeLoiterCheckbox.checked === true - showUnits: true + id: descendField; + fact: controller.getParameterFact(-1, "RTL_DESCEND_ALT") + enabled: homeLoiterCheckbox.checked === true + showUnits: true } } } @@ -288,20 +289,23 @@ Rectangle { } QGCLabel { - property Fact fact: Fact { name: "NAV_RCL_OBC" } - width: parent.width - font.pointSize: ScreenTools.fontPointFactor * (14); - text: "Warning: You have an advanced safety configuration set using the NAV_RCL_OBC parameter. The above settings may not apply."; - visible: fact.value !== 0 - wrapMode: Text.Wrap + width: parent.width + font.pointSize: ScreenTools.mediumFontPointSize + text: "Warning: You have an advanced safety configuration set using the NAV_RCL_OBC parameter. The above settings may not apply."; + visible: fact.value !== 0 + wrapMode: Text.Wrap + + property Fact fact: controller.getParameterFact(-1, "NAV_RCL_OBC") } + QGCLabel { - property Fact fact: Fact { name: "NAV_DLL_OBC" } - width: parent.width - font.pointSize: ScreenTools.fontPointFactor * (14); - text: "Warning: You have an advanced safety configuration set using the NAV_DLL_OBC parameter. The above settings may not apply."; - visible: fact.value !== 0 - wrapMode: Text.Wrap + width: parent.width + font.pointSize: ScreenTools.mediumFontPointSize + text: "Warning: You have an advanced safety configuration set using the NAV_DLL_OBC parameter. The above settings may not apply."; + visible: fact.value !== 0 + wrapMode: Text.Wrap + + property Fact fact: controller.getParameterFact(-1, "NAV_DLL_OBC") } } } diff --git a/src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml b/src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml index f5acedbc0454facbfe37bd89ad4b45c35f31660f..46785ad6033b05bb34f1d4ada5a076dfca5fac27 100644 --- a/src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/SafetyComponentSummary.qml @@ -4,15 +4,21 @@ import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 FactPanel { - anchors.fill: parent - - Fact { id: returnAltFact; name: "RTL_RETURN_ALT"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: descendAltFact; name: "RTL_DESCEND_ALT"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: landDelayFact; name: "RTL_LAND_DELAY"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: commDLLossFact; name: "COM_DL_LOSS_EN"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: commRCLossFact; name: "COM_RC_LOSS_T"; onFactMissing: showMissingFactOverlay(name) } + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark + + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact returnAltFact: controller.getParameterFact(-1, "RTL_RETURN_ALT") + property Fact descendAltFact: controller.getParameterFact(-1, "RTL_DESCEND_ALT") + property Fact landDelayFact: controller.getParameterFact(-1, "RTL_LAND_DELAY") + property Fact commDLLossFact: controller.getParameterFact(-1, "COM_DL_LOSS_EN") + property Fact commRCLossFact: controller.getParameterFact(-1, "COM_RC_LOSS_T") Column { anchors.fill: parent diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index ef7bfd2c562f3d82de38f0cad4ecdb6fa0312d6a..ac931624c90585f7a10a7a37b235626f62421ad1 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -62,7 +62,7 @@ bool SensorsComponent::requiresSetup(void) const bool SensorsComponent::setupComplete(void) const { foreach(QString triggerParam, setupCompleteChangedTriggerList()) { - if (_autopilot->getParameterFact(triggerParam)->value().toFloat() == 0.0f) { + if (_autopilot->getParameterFact(FactSystem::defaultComponentId, triggerParam)->value().toFloat() == 0.0f) { return false; } } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.qml b/src/AutoPilotPlugins/PX4/SensorsComponent.qml index 5d05fb7ce0de63facc9f010ae14d344ae9422422..a4884e9baa17f3841a80d3145bc5d7b3226f1f77 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.qml @@ -91,12 +91,19 @@ QGCView { "ROTATION_ROLL_270_YAW_270" ] - Fact { id: cal_mag0_id; name: "CAL_MAG0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: cal_mag1_id; name: "CAL_MAG1_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: cal_mag2_id; name: "CAL_MAG2_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: cal_mag0_rot; name: "CAL_MAG0_ROT"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: cal_mag1_rot; name: "CAL_MAG1_ROT"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: cal_mag2_rot; name: "CAL_MAG2_ROT"; onFactMissing: showMissingFactOverlay(name) } + property Fact cal_mag0_id: controller.getParameterFact(-1, "CAL_MAG0_ID") + property Fact cal_mag1_id: controller.getParameterFact(-1, "CAL_MAG1_ID") + property Fact cal_mag2_id: controller.getParameterFact(-1, "CAL_MAG2_ID") + property Fact cal_mag0_rot: controller.getParameterFact(-1, "CAL_MAG0_ROT") + property Fact cal_mag1_rot: controller.getParameterFact(-1, "CAL_MAG1_ROT") + property Fact cal_mag2_rot: controller.getParameterFact(-1, "CAL_MAG2_ROT") + + property Fact cal_gyro0_id: controller.getParameterFact(-1, "CAL_GYRO0_ID") + property Fact cal_acc0_id: controller.getParameterFact(-1, "CAL_ACC0_ID") + + property Fact sens_board_rot: controller.getParameterFact(-1, "SENS_BOARD_ROT") + property Fact sens_board_x_off: controller.getParameterFact(-1, "SENS_BOARD_X_OFF") + property Fact sens_dpres_off: controller.getParameterFact(-1, "SENS_DPRES_OFF") // Id > = signals compass available, rot < 0 signals internal compass property bool showCompass0Rot: cal_mag0_id.value > 0 && cal_mag0_rot.value >= 0 @@ -165,7 +172,7 @@ QGCView { width: rotationColumnWidth model: rotations visible: preCalibrationDialogType != "airspeed" && (preCalibrationDialogType != "gyro") - fact: Fact { name: "SENS_BOARD_ROT"; onFactMissing: showMissingFactOverlay(name) } + fact: sens_board_rot } } } @@ -204,7 +211,7 @@ QGCView { id: compass0RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG0_ROT"; onFactMissing: showMissingFactOverlay(name) } + fact: cal_mag0_rot } } Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel : null } @@ -222,7 +229,7 @@ QGCView { id: compass1RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG1_ROT"; onFactMissing: showMissingFactOverlay(name) } + fact: cal_mag1_rot } } Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel : null } @@ -241,7 +248,7 @@ QGCView { id: compass1RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG2_ROT"; onFactMissing: showMissingFactOverlay(name) } + fact: cal_mag2_rot } } Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel : null } @@ -285,7 +292,7 @@ QGCView { QGCLabel { text: "SENSORS CONFIG" - font.pointSize: ScreenTools.fontPointFactor * (20); + font.pointSize: ScreenTools.largeFontPointSize } Item { height: 20; width: 10 } // spacer @@ -298,12 +305,10 @@ QGCView { QGCLabel { text: "Calibrate:"; anchors.baseline: compassButton.baseline } IndicatorButton { - property Fact fact: Fact { name: "CAL_MAG0_ID" } - id: compassButton width: parent.buttonWidth text: "Compass" - indicatorGreen: fact.value != 0 + indicatorGreen: cal_mag0_id.value != 0 onClicked: { preCalibrationDialogType = "compass" @@ -313,12 +318,10 @@ QGCView { } IndicatorButton { - property Fact fact: Fact { name: "CAL_GYRO0_ID" } - id: gyroButton width: parent.buttonWidth text: "Gyroscope" - indicatorGreen: fact.value != 0 + indicatorGreen: cal_gyro0_id.value != 0 onClicked: { preCalibrationDialogType = "gyro" @@ -328,12 +331,10 @@ QGCView { } IndicatorButton { - property Fact fact: Fact { name: "CAL_ACC0_ID" } - id: accelButton width: parent.buttonWidth text: "Accelerometer" - indicatorGreen: fact.value != 0 + indicatorGreen: cal_acc0_id.value != 0 onClicked: { preCalibrationDialogType = "accel" @@ -343,15 +344,11 @@ QGCView { } IndicatorButton { - property Fact fact: Fact { name: "SENS_BOARD_X_OFF" } - property Fact checkAcc: Fact { name: "CAL_ACC0_ID" } - property Fact checkGyro: Fact { name: "CAL_GYRO0_ID" } - id: levelButton width: parent.buttonWidth text: "Level Horizon" - indicatorGreen: fact.value != 0 - enabled: checkAcc.value != 0 && checkGyro.value != 0 + indicatorGreen: sens_board_x_off.value != 0 + enabled: cal_acc0_id.value != 0 && cal_gyro0_id.value != 0 onClicked: { preCalibrationDialogType = "level" @@ -361,13 +358,11 @@ QGCView { } IndicatorButton { - property Fact fact: Fact { name: "SENS_DPRES_OFF" } - id: airspeedButton width: parent.buttonWidth text: "Airspeed" visible: controller.fixedWing - indicatorGreen: fact.value != 0 + indicatorGreen: sens_dpres_off.value != 0 onClicked: { preCalibrationDialogType = "airspeed" @@ -511,7 +506,7 @@ QGCView { id: boardRotationCombo width: rotationColumnWidth; model: rotations - fact: Fact { name: "SENS_BOARD_ROT" } + fact: sens_board_rot } } @@ -534,7 +529,7 @@ QGCView { id: compass0RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG0_ROT" } + fact: cal_mag0_rot } } Loader { sourceComponent: showCompass0Rot ? compass0ComponentLabel2 : null } @@ -559,7 +554,7 @@ QGCView { id: compass1RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG1_ROT" } + fact: cal_mag1_rot } } Loader { sourceComponent: showCompass1Rot ? compass1ComponentLabel2 : null } @@ -584,7 +579,7 @@ QGCView { id: compass1RotationCombo width: rotationColumnWidth model: rotations - fact: Fact { name: "CAL_MAG2_ROT" } + fact: cal_mag2_rot } } Loader { sourceComponent: showCompass2Rot ? compass2ComponentLabel2 : null } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index 6a5a73b958e7b7ba25e01f377cc0295a021ea19c..edca633d737ca63ec0a8a0f95e85759a2a296461 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -69,13 +69,7 @@ SensorsComponentController::SensorsComponentController(void) : _unknownFirmwareVersion(false), _waitingForCancel(false) { - // Mag rotation parameters are optional - _showCompass0 = _autopilot->parameterExists("CAL_MAG0_ROT") && - _autopilot->getParameterFact("CAL_MAG0_ROT")->value().toInt() >= 0; - _showCompass1 = _autopilot->parameterExists("CAL_MAG1_ROT") && - _autopilot->getParameterFact("CAL_MAG1_ROT")->value().toInt() >= 0; - _showCompass2 = _autopilot->parameterExists("CAL_MAG2_ROT") && - _autopilot->getParameterFact("CAL_MAG2_ROT")->value().toInt() >= 0; + } /// Appends the specified text to the status log area in the ui diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.h b/src/AutoPilotPlugins/PX4/SensorsComponentController.h index 985b33661eb09ccbe2d1defb1165fec500ec6f15..fb56488360387eff9980b2919777317207136c7d 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.h +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.h @@ -135,10 +135,6 @@ private: bool _showGyroCalArea; bool _showOrientationCalArea; - bool _showCompass0; - bool _showCompass1; - bool _showCompass2; - bool _gyroCalInProgress; bool _magCalInProgress; bool _accelCalInProgress; diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentSummary.qml b/src/AutoPilotPlugins/PX4/SensorsComponentSummary.qml index b79a2206f30b4a68864053ee49231404a6c0858f..2f7a3edb9fbb0ea1870cc6a8179cfbd29d11bd0e 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentSummary.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponentSummary.qml @@ -5,17 +5,23 @@ import QtQuick.Controls.Styles 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 /* IMPORTANT NOTE: Any changes made here must also be made to SensorsComponentSummary.qml */ FactPanel { - anchors.fill: parent + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark - Fact { id: mag0IdFact; name: "CAL_MAG0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: gyro0IdFact; name: "CAL_GYRO0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: accel0IdFact; name: "CAL_ACC0_ID"; onFactMissing: showMissingFactOverlay(name) } + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact mag0IdFact: controller.getParameterFact(-1, "CAL_MAG0_ID") + property Fact gyro0IdFact: controller.getParameterFact(-1, "CAL_GYRO0_ID") + property Fact accel0IdFact: controller.getParameterFact(-1, "CAL_ACC0_ID") Column { anchors.fill: parent diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentSummaryFixedWing.qml b/src/AutoPilotPlugins/PX4/SensorsComponentSummaryFixedWing.qml index 23580cafa906502cd9a408dabb22b488dd0441de..3128cd5c47425822ce6c79c094e4584e1eb1011c 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentSummaryFixedWing.qml +++ b/src/AutoPilotPlugins/PX4/SensorsComponentSummaryFixedWing.qml @@ -4,18 +4,24 @@ import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 import QGroundControl.FactControls 1.0 import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 /* IMPORTANT NOTE: Any changes made here must also be made to SensorsComponentSummary.qml */ FactPanel { - anchors.fill: parent + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark - Fact { id: mag0IdFact; name: "CAL_MAG0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: gyro0IdFact; name: "CAL_GYRO0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: accel0IdFact; name: "CAL_ACC0_ID"; onFactMissing: showMissingFactOverlay(name) } - Fact { id: dPressOffFact; name: "SENS_DPRES_OFF"; onFactMissing: showMissingFactOverlay(name) } + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + property Fact mag0IdFact: controller.getParameterFact(-1, "CAL_MAG0_ID") + property Fact gyro0IdFact: controller.getParameterFact(-1, "CAL_GYRO0_ID") + property Fact accel0IdFact: controller.getParameterFact(-1, "CAL_ACC0_ID") + property Fact dpresssOffFact: controller.getParameterFact(-1, "SENS_DPRES_OFF") Column { anchors.fill: parent diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc index 356b3493e797cb80142520a3ed707bc07e4d74ce..dc70c8313b6d6e81d2468e30bd25bcd740a66711 100644 --- a/src/FactSystem/Fact.cc +++ b/src/FactSystem/Fact.cc @@ -28,14 +28,25 @@ #include +Fact::Fact(void) : + _componentId(-1), + _value(0), + _type(FactMetaData::valueTypeInt32), + _metaData(NULL) +{ + FactMetaData* metaData = new FactMetaData(_type, this); + setMetaData(metaData); +} + Fact::Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObject* parent) : QObject(parent), _name(name), _componentId(componentId), + _value(0), _type(type), _metaData(NULL) { - _value = 0; + } void Fact::setValue(const QVariant& value) diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h index 5d0cb58cf95a01e5eff16582490ceb3e0de204db..a8b486f749466907e91228e8bc17f3e605cb73e7 100644 --- a/src/FactSystem/Fact.h +++ b/src/FactSystem/Fact.h @@ -40,8 +40,24 @@ class Fact : public QObject Q_OBJECT public: + Fact(void); Fact(int componentId, QString name, FactMetaData::ValueType_t type, QObject* parent = NULL); + Q_PROPERTY(int componentId READ componentId CONSTANT) + Q_PROPERTY(QString name READ name CONSTANT) + Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) + Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) + Q_PROPERTY(QString units READ units CONSTANT) + Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT) + Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable CONSTANT) + Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) + Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT) + Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT) + Q_PROPERTY(QString longDescription READ longDescription CONSTANT) + Q_PROPERTY(QVariant min READ min CONSTANT) + Q_PROPERTY(QVariant max READ max CONSTANT) + Q_PROPERTY(QString group READ group CONSTANT) + // Property system methods QString name(void) const; diff --git a/src/FactSystem/FactBinder.cc b/src/FactSystem/FactBinder.cc deleted file mode 100644 index 55c1965d06d06ba0cac7ca2201616caec3be64c9..0000000000000000000000000000000000000000 --- a/src/FactSystem/FactBinder.cc +++ /dev/null @@ -1,239 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -/// @file -/// @author Don Gagne - -#include "FactBinder.h" -#include "UASManager.h" -#include "AutoPilotPluginManager.h" -#include "QGCApplication.h" - -#include - -FactBinder::FactBinder(void) : - _autopilotPlugin(NULL), - _fact(NULL), - _componentId(FactSystem::defaultComponentId), - _factMissingSignalConnected(false) -{ - UASInterface* uas = UASManager::instance()->getActiveUAS(); - Q_ASSERT(uas); - - _autopilotPlugin = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(uas); - Q_ASSERT(_autopilotPlugin); - Q_ASSERT(_autopilotPlugin->pluginReady()); -} - -QString FactBinder::name(void) const -{ - if (_fact) { - return _fact->name(); - } else { - return QString(); - } -} - -int FactBinder::componentId(void) const -{ - return _componentId; -} - -void FactBinder::setName(const QString& name) -{ - if (_fact) { - disconnect(_fact, &Fact::valueChanged, this, &FactBinder::valueChanged); - _fact = NULL; - } - - if (!name.isEmpty()) { - QString parsedName = name; - - // Component id + name combination? - if (name.contains(":")) { - QStringList parts = name.split(":"); - if (parts.count() == 2) { - parsedName = parts[0]; - _componentId = parts[1].toInt(); - } - } - - if (_autopilotPlugin->factExists(FactSystem::ParameterProvider, _componentId, parsedName)) { - _fact = _autopilotPlugin->getFact(FactSystem::ParameterProvider, _componentId, parsedName); - connect(_fact, &Fact::valueChanged, this, &FactBinder::valueChanged); - - emit valueChanged(); - emit nameChanged(); - emit metaDataChanged(); - } else { - qgcApp()->reportMissingFact(name); - if (_factMissingSignalConnected) { - emit factMissing(name); - } else { - _missedFactMissingSignals << name; - } - } - } -} - -QVariant FactBinder::value(void) const -{ - if (_fact) { - return _fact->value(); - } else { - return QVariant(0); - } -} - -void FactBinder::setValue(const QVariant& value) -{ - if (_fact) { - _fact->setValue(value); - } else { - qWarning() << "FAILED SETTING PARAM VALUE" << _fact->name() << ": PARAM DOES NOT EXIST ON SYSTEM!"; - Q_ASSERT(false); - } -} - -QString FactBinder::valueString(void) const -{ - if (_fact) { - return _fact->valueString(); - } else { - return QString(); - } -} - -QString FactBinder::units(void) const -{ - if (_fact) { - return _fact->units(); - } else { - return QString(); - } -} - -QVariant FactBinder::defaultValue(void) -{ - if (_fact) { - return _fact->defaultValue(); - } else { - return QVariant(0); - } -} - -FactMetaData::ValueType_t FactBinder::type(void) -{ - if (_fact) { - return _fact->type(); - } else { - return FactMetaData::valueTypeUint32; - } -} - -QString FactBinder::shortDescription(void) -{ - if (_fact) { - return _fact->shortDescription(); - } else { - return QString(); - } -} - -QString FactBinder::longDescription(void) -{ - if (_fact) { - return _fact->longDescription(); - } else { - return QString(); - } -} - -QVariant FactBinder::min(void) -{ - if (_fact) { - return _fact->min(); - } else { - return QVariant(0); - } -} - -QVariant FactBinder::max(void) -{ - if (_fact) { - return _fact->max(); - } else { - return QVariant(0); - } -} - -QString FactBinder::group(void) -{ - if (_fact) { - return _fact->group(); - } else { - return QString(); - } -} - -bool FactBinder::defaultValueAvailable(void) -{ - if (_fact) { - return _fact->defaultValueAvailable(); - } else { - return false; - } -} - -bool FactBinder::valueEqualsDefault(void) -{ - if (_fact) { - return _fact->valueEqualsDefault(); - } else { - return false; - } -} - -void FactBinder::connectNotify(const QMetaMethod & signal) -{ - if (signal == QMetaMethod::fromSignal(&FactBinder::factMissing)) { - _factMissingSignalConnected = true; - if (_missedFactMissingSignals.count()) { - QTimer::singleShot(10, this, &FactBinder::_delayedFactMissing); - } - } -} - -void FactBinder::disconnectNotify(const QMetaMethod & signal) -{ - if (signal == QMetaMethod::fromSignal(&FactBinder::factMissing)) { - _factMissingSignalConnected = false; - } -} - -void FactBinder::_delayedFactMissing(void) -{ - foreach (QString name, _missedFactMissingSignals) { - emit factMissing(name); - } -} \ No newline at end of file diff --git a/src/FactSystem/FactBinder.h b/src/FactSystem/FactBinder.h deleted file mode 100644 index 22bb9f0c458fa3a009678db15500f0e56a508166..0000000000000000000000000000000000000000 --- a/src/FactSystem/FactBinder.h +++ /dev/null @@ -1,101 +0,0 @@ -/*===================================================================== - - QGroundControl Open Source Ground Control Station - - (c) 2009 - 2014 QGROUNDCONTROL PROJECT - - This file is part of the QGROUNDCONTROL project - - QGROUNDCONTROL is free software: you can redistribute it and/or modify - it under the terms of the GNU General Public License as published by - the Free Software Foundation, either version 3 of the License, or - (at your option) any later version. - - QGROUNDCONTROL is distributed in the hope that it will be useful, - but WITHOUT ANY WARRANTY; without even the implied warranty of - MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - GNU General Public License for more details. - - You should have received a copy of the GNU General Public License - along with QGROUNDCONTROL. If not, see . - - ======================================================================*/ - -/// @file -/// @author Don Gagne - -#ifndef FACTBINDER_H -#define FACTBINDER_H - -#include "Fact.h" -#include "AutoPilotPlugin.h" - -#include -#include - -/// This object is used to instantiate a connection to a Fact from within Qml. -class FactBinder : public QObject -{ - Q_OBJECT - - Q_PROPERTY(int componentId READ componentId NOTIFY nameChanged) - Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) - Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) - Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) - Q_PROPERTY(QString units READ units NOTIFY metaDataChanged) - Q_PROPERTY(QVariant defaultValue READ defaultValue NOTIFY metaDataChanged) - Q_PROPERTY(bool defaultValueAvailable READ defaultValueAvailable NOTIFY metaDataChanged) - Q_PROPERTY(bool valueEqualsDefault READ valueEqualsDefault NOTIFY valueChanged) - Q_PROPERTY(FactMetaData::ValueType_t type READ type NOTIFY metaDataChanged) - Q_PROPERTY(QString shortDescription READ shortDescription NOTIFY metaDataChanged) - Q_PROPERTY(QString longDescription READ longDescription NOTIFY metaDataChanged) - Q_PROPERTY(QVariant min READ min NOTIFY metaDataChanged) - Q_PROPERTY(QVariant max READ max NOTIFY metaDataChanged) - Q_PROPERTY(QString group READ group NOTIFY metaDataChanged) - -public: - FactBinder(void); - - int componentId(void) const; - - QString name(void) const; - void setName(const QString& name); - - QVariant value(void) const; - void setValue(const QVariant& value); - - QString valueString(void) const; - - QString units(void) const; - QVariant defaultValue(void); - bool defaultValueAvailable(void); - bool valueEqualsDefault(void); - FactMetaData::ValueType_t type(void); - QString shortDescription(void); - QString longDescription(void); - QVariant min(void); - QVariant max(void); - QString group(void); - -signals: - void factMissing(const QString& name); - void nameChanged(void); - void valueChanged(void); - void metaDataChanged(void); - -private slots: - void _delayedFactMissing(void); - -private: - // Overrides from QObject - void connectNotify(const QMetaMethod & signal); - void disconnectNotify(const QMetaMethod & signal); - - AutoPilotPlugin* _autopilotPlugin; - Fact* _fact; - int _componentId; - bool _factMissingSignalConnected; - QStringList _missedFactMissingSignals; -}; - -#endif \ No newline at end of file diff --git a/src/FactSystem/FactControls/FactPanel.qml b/src/FactSystem/FactControls/FactPanel.qml index f941f82bbbfdfa64d17bb894f52db56a7949eca0..fda596eca8f2bfed73f335723b7cc4339e0028f7 100644 --- a/src/FactSystem/FactControls/FactPanel.qml +++ b/src/FactSystem/FactControls/FactPanel.qml @@ -36,18 +36,24 @@ Rectangle { QGCPalette { id: __qgcPal; colorGroupEnabled: true } - property string __missingFacts: "" + property string __missingParams: "" + property string __errorMsg: "" - function showMissingFactOverlay(missingFactName) { - if (__missingFacts.length != 0) { - __missingFacts = __missingFacts.concat(", ") + function showMissingParameterOverlay(missingParamName) { + if (__missingParams.length != 0) { + __missingParams = __missingParams.concat(", ") } - __missingFacts = __missingFacts.concat(missingFactName) - __missingFactOverlay.visible = true + __missingParams = __missingParams.concat(missingParamName) + __missingParamsOverlay.visible = true + } + + function showError(errorMsg) { + __errorMsg = errorMsg + __missingParamsOverlay.visible = true } Rectangle { - id: __missingFactOverlay + id: __missingParamsOverlay anchors.fill: parent z: 9999 visible: false @@ -57,7 +63,7 @@ Rectangle { QGCLabel { anchors.fill: parent wrapMode: Text.WordWrap - text: "Fact(s) missing: " + __missingFacts + text: __errorMsg.length ? __errorMsg : "Paremeters(s) missing: " + __missingParams } } } diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 25df92b12fcc2807a7d5da8f47cda2e84808b3be..c6bfaa309732a3d985064dbe0b111d3d9db8afae 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -26,13 +26,19 @@ #include "AutoPilotPluginManager.h" #include "QGCMessageBox.h" +#include + /// @file /// @author Don Gagne +QGC_LOGGING_CATEGORY(FactPanelControllerLog, "FactPanelControllerLog") + FactPanelController::FactPanelController(void) : _autopilot(NULL), _factPanel(NULL) { + // FIXME: Get rid of these asserts + _uas = UASManager::instance()->getActiveUAS(); Q_ASSERT(_uas); @@ -51,48 +57,64 @@ QQuickItem* FactPanelController::factPanel(void) void FactPanelController::setFactPanel(QQuickItem* panel) { - // Once we finally have the _factPanel member set send any + // Once we finally have the _factPanel member set, send any // missing fact notices that were waiting to go out _factPanel = panel; - foreach (QString missingFact, _delayedMissingFacts) { - _notifyPanelMissingFact(missingFact); + foreach (QString missingParam, _delayedMissingParams) { + _notifyPanelMissingParameter(missingParam); + } + _delayedMissingParams.clear(); +} + +void FactPanelController::_notifyPanelMissingParameter(const QString& missingParam) +{ + if (_factPanel) { + QVariant returnedValue; + + QMetaObject::invokeMethod(_factPanel, + "showMissingParameterOverlay", + Q_RETURN_ARG(QVariant, returnedValue), + Q_ARG(QVariant, missingParam)); } - _delayedMissingFacts.clear(); } -void FactPanelController::_notifyPanelMissingFact(const QString& missingFact) +void FactPanelController::_notifyPanelErrorMsg(const QString& errorMsg) { - QVariant returnedValue; + if (_factPanel) { + QVariant returnedValue; - QMetaObject::invokeMethod(_factPanel, - "showMissingFactOverlay", - Q_RETURN_ARG(QVariant, returnedValue), - Q_ARG(QVariant, missingFact)); + QMetaObject::invokeMethod(_factPanel, + "showError", + Q_RETURN_ARG(QVariant, returnedValue), + Q_ARG(QVariant, errorMsg)); + } } -void FactPanelController::_reportMissingFact(const QString& missingFact) +void FactPanelController::_reportMissingParameter(int componentId, const QString& name) { - qgcApp()->reportMissingFact(missingFact); + qgcApp()->reportMissingParameter(componentId, name); + + QString missingParam = QString("%1:%2").arg(componentId).arg(name); - // If missing facts a reported from the constructor of a derived class we + // If missing parameters a reported from the constructor of a derived class we // will not have access to _factPanel yet. Just record list of missing facts // in that case instead of notify. Once _factPanel is available they will be // send out for real. if (_factPanel) { - _notifyPanelMissingFact(missingFact); + _notifyPanelMissingParameter(missingParam); } else { - _delayedMissingFacts += missingFact; + _delayedMissingParams += missingParam; } } -bool FactPanelController::_allFactsExists(QStringList factList) +bool FactPanelController::_allParametersExists(int componentId, QStringList names) { bool noMissingFacts = true; - foreach (QString fact, factList) { - if (!_autopilot->parameterExists(fact)) { - _reportMissingFact(fact); + foreach (QString name, names) { + if (!_autopilot->parameterExists(componentId, name)) { + _reportMissingParameter(componentId, name); noMissingFacts = false; } } @@ -103,6 +125,30 @@ bool FactPanelController::_allFactsExists(QStringList factList) void FactPanelController::_checkForMissingFactPanel(void) { if (!_factPanel) { - QGCMessageBox::critical("Incorrect FactPanel Qml implementation", "FactPanelController used without passing in factPanel. This could lead to non-functioning user interface being displayed."); + _showInternalError("Incorrect FactPanel Qml implementation. FactPanelController used without passing in factPanel."); } +} + +Fact* FactPanelController::getParameterFact(int componentId, const QString& name) +{ + if (_autopilot->parameterExists(componentId, name)) { + Fact* fact = _autopilot->getParameterFact(componentId, name); + QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership); + return fact; + } else { + _reportMissingParameter(componentId, name); + return NULL; + } +} + +bool FactPanelController::parameterExists(int componentId, const QString& name) +{ + return _autopilot->parameterExists(componentId, name); +} + +void FactPanelController::_showInternalError(const QString& errorMsg) +{ + _notifyPanelErrorMsg(QString("Internal Error: %1").arg(errorMsg)); + qCWarning(FactPanelControllerLog) << "Internal Error" << errorMsg; + QGCMessageBox::critical("Internal Error", errorMsg); } \ No newline at end of file diff --git a/src/FactSystem/FactControls/FactPanelController.h b/src/FactSystem/FactControls/FactPanelController.h index 9d21b712b164f37aeb2df59e9a771666618c6017..e2da76fd12cadd136ef6de87384a10a2b630d134 100644 --- a/src/FactSystem/FactControls/FactPanelController.h +++ b/src/FactSystem/FactControls/FactPanelController.h @@ -33,6 +33,9 @@ #include "UASInterface.h" #include "AutoPilotPlugin.h" #include "UASManagerInterface.h" +#include "QGCLoggingCategory.h" + +Q_DECLARE_LOGGING_CATEGORY(FactPanelControllerLog) /// FactPanelController is used in combination with the FactPanel Qml control for handling /// missing Facts from C++ code. @@ -45,28 +48,33 @@ public: Q_PROPERTY(QQuickItem* factPanel READ factPanel WRITE setFactPanel) + Q_INVOKABLE Fact* getParameterFact(int componentId, const QString& name); + Q_INVOKABLE bool parameterExists(int componentId, const QString& name); + QQuickItem* factPanel(void); void setFactPanel(QQuickItem* panel); protected: - /// Checks for existence of the specified facts - /// @return true: all facts exists, false: facts missing and reported - bool _allFactsExists(QStringList factList); + /// Checks for existence of the specified parameters + /// @return true: all parameters exists, false: parameters missing and reported + bool _allParametersExists(int componentId, QStringList names); - /// Report a missing fact to the FactPanel Qml element - void _reportMissingFact(const QString& missingFact); + /// Report a missing parameter to the FactPanel Qml element + void _reportMissingParameter(int componentId, const QString& name); - UASInterface* _uas; - AutoPilotPlugin* _autopilot; + UASInterface* _uas; + QSharedPointer _autopilot; private slots: void _checkForMissingFactPanel(void); private: - void _notifyPanelMissingFact(const QString& missingFact); + void _notifyPanelMissingParameter(const QString& missingParam); + void _notifyPanelErrorMsg(const QString& errorMsg); + void _showInternalError(const QString& errorMsg); QQuickItem* _factPanel; - QStringList _delayedMissingFacts; + QStringList _delayedMissingParams; }; #endif \ No newline at end of file diff --git a/src/FactSystem/FactControls/FactTextField.qml b/src/FactSystem/FactControls/FactTextField.qml index 94f21d48ea4f7decea7671db8aaa9fc2001bbdc3..5beff149ab79d989161e6d333d208e67efd6d77e 100644 --- a/src/FactSystem/FactControls/FactTextField.qml +++ b/src/FactSystem/FactControls/FactTextField.qml @@ -7,7 +7,7 @@ import QGroundControl.Palette 1.0 import QGroundControl.Controls 1.0 QGCTextField { - property Fact fact: Fact { } + property Fact fact: null text: fact.valueString unitsLabel: fact.units onEditingFinished: fact.value = text diff --git a/src/FactSystem/FactSystem.cc b/src/FactSystem/FactSystem.cc index 257193792f210e982dbdf84e47c6ad578f8c0118..05caa927ae9d981e424f5199bae875f4ff6035da 100644 --- a/src/FactSystem/FactSystem.cc +++ b/src/FactSystem/FactSystem.cc @@ -28,7 +28,6 @@ #include "UASManager.h" #include "QGCApplication.h" #include "VehicleComponent.h" -#include "FactBinder.h" #include "FactPanelController.h" #include @@ -40,7 +39,8 @@ const char* FactSystem::_factSystemQmlUri = "QGroundControl.FactSystem"; FactSystem::FactSystem(QObject* parent) : QGCSingleton(parent) { - qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact"); + + qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact"); qmlRegisterType(_factSystemQmlUri, 1, 0, "FactPanelController"); qmlRegisterUncreatableType(_factSystemQmlUri, 1, 0, "VehicleComponent", "Can only reference, cannot create"); } diff --git a/src/FactSystem/FactSystemTest.qml b/src/FactSystem/FactSystemTest.qml index 885b4b22ff6f24d824777265d1684034a85c486b..2590dfbff98e99d6f843f04f01ecd13bac4813ec 100644 --- a/src/FactSystem/FactSystemTest.qml +++ b/src/FactSystem/FactSystemTest.qml @@ -24,21 +24,29 @@ import QtQuick 2.2 import QtQuick.Controls 1.2 import QGroundControl.FactSystem 1.0 +import QGroundControl.FactControls 1.0 + +FactPanel { + id: panel + + FactPanelController { id: controller; factPanel: panel } -Item { // Use default component id TextInput { objectName: "testControl" - Fact { id: fact1; name: "RC_MAP_THROTTLE" } - text: fact1.value - onAccepted: { fact1.value = text; } + text: fact1.value + + property Fact fact1: controller.getParameterFact(-1, "RC_MAP_THROTTLE") + + onAccepted: fact1.value = text } // Use specific component id TextInput { - objectName: "testControl" - Fact { id: fact2; name: "COMPONENT_51:51" } - text: fact2.value - onAccepted: { fact2.value = text; } + text: fact2.value + + property Fact fact2: controller.getParameterFact(51, "COMPONENT_51") + + onAccepted: fact2.value = text } } diff --git a/src/FactSystem/FactSystemTestBase.cc b/src/FactSystem/FactSystemTestBase.cc index 1035c81d1e85347d0bae8fe2f4b2f7f858cb3a5c..cd6a6433d86a61ddefd3813e51f206a3bc6c71c2 100644 --- a/src/FactSystem/FactSystemTestBase.cc +++ b/src/FactSystem/FactSystemTestBase.cc @@ -64,7 +64,7 @@ void FactSystemTestBase::_init(MAV_AUTOPILOT autopilot) AutoPilotPluginManager* pluginMgr = AutoPilotPluginManager::instance(); Q_ASSERT(pluginMgr); - _plugin = pluginMgr->getInstanceForAutoPilotPlugin(_uas); + _plugin = pluginMgr->getInstanceForAutoPilotPlugin(_uas).data(); Q_ASSERT(_plugin); // Wait for the plugin to be ready @@ -129,6 +129,8 @@ void FactSystemTestBase::_qml_test(void) QVariant qmlValue = control->property("text").toInt(); QCOMPARE(qmlValue.toInt(), 3); + + delete widget; } /// Test QML getting an updated Fact value @@ -143,7 +145,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) // Change the value QVariant paramValue = 12; - _plugin->getParameterFact("RC_MAP_THROTTLE")->setValue(paramValue); + _plugin->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setValue(paramValue); QTest::qWait(500); // Let the signals flow through @@ -153,5 +155,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) QObject* control = rootObject->findChild("testControl"); QVERIFY(control != NULL); QCOMPARE(control->property("text").toInt(), 12); + + delete widget; } diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 736a2268169c8f145c57c3bf1844161f59fe30a8..df44ae8ecf82de266c0140cc890e593f0b9b1b15 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -35,6 +35,8 @@ QGC_LOGGING_CATEGORY(ParameterLoaderLog, "ParameterLoaderLog") +Fact ParameterLoader::_defaultFact; + ParameterLoader::ParameterLoader(AutoPilotPlugin* autopilot, UASInterface* uas, QObject* parent) : QObject(parent), _autopilot(autopilot), @@ -386,13 +388,11 @@ Fact* ParameterLoader::getFact(int componentId, const QString& name) componentId = _actualComponentId(componentId); if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(name)) { - return NULL; + qgcApp()->reportMissingParameter(componentId, name); + return &_defaultFact; } - Fact* fact = _mapParameterName2Variant[componentId][name].value(); - Q_ASSERT(fact); - - return fact; + return _mapParameterName2Variant[componentId][name].value(); } QStringList ParameterLoader::parameterNames(void) diff --git a/src/FactSystem/ParameterLoader.h b/src/FactSystem/ParameterLoader.h index 925faaebc7b779275b6d986dd77a5783758cf089..df64e2f4d19741e1b17f0ee33affc4cbb900ac2a 100644 --- a/src/FactSystem/ParameterLoader.h +++ b/src/FactSystem/ParameterLoader.h @@ -147,6 +147,8 @@ private: bool _fullRefresh; QMutex _dataMutex; + + static Fact _defaultFact; ///< Used to return default fact, when parameter not found }; #endif \ No newline at end of file diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index b5df4aa71bbb28daf9bce8baf72145f69f822059..9719936aa648c58a1d6aa768f0ef4e2ace8a450a 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -185,9 +185,9 @@ QGCApplication::QGCApplication(int &argc, char* argv[], bool unitTesting) : #endif // Set up timer for delayed missing fact display - _missingFactDelayedDisplayTimer.setSingleShot(true); - _missingFactDelayedDisplayTimer.setInterval(_missingFactDelayedDisplayTimerTimeout); - connect(&_missingFactDelayedDisplayTimer, &QTimer::timeout, this, &QGCApplication::_missingFactsDisplay); + _missingParamsDelayedDisplayTimer.setSingleShot(true); + _missingParamsDelayedDisplayTimer.setInterval(_missingParamsDelayedDisplayTimerTimeout); + connect(&_missingParamsDelayedDisplayTimer, &QTimer::timeout, this, &QGCApplication::_missingParamsDisplay); // Set application information if (_runningUnitTests) { @@ -675,28 +675,28 @@ void QGCApplication::_loadCurrentStyle(void) restoreOverrideCursor(); } -void QGCApplication::reportMissingFact(const QString& name) +void QGCApplication::reportMissingParameter(int componentId, const QString& name) { - _missingFacts += name; - _missingFactDelayedDisplayTimer.start(); + _missingParams += QString("%1:%2").arg(componentId).arg(name); + _missingParamsDelayedDisplayTimer.start(); } -/// Called when the delay timer fires to show the missing facts warning -void QGCApplication::_missingFactsDisplay(void) +/// Called when the delay timer fires to show the missing parameters warning +void QGCApplication::_missingParamsDisplay(void) { - Q_ASSERT(_missingFacts.count()); + Q_ASSERT(_missingParams.count()); - QString facts; - foreach (QString fact, _missingFacts) { - if (facts.isEmpty()) { - facts += fact; + QString params; + foreach (QString name, _missingParams) { + if (params.isEmpty()) { + params += name; } else { - facts += QString(", %1").arg(fact); + params += QString(", %1").arg(name); } } - _missingFacts.clear(); + _missingParams.clear(); QGCMessageBox::critical("Missing Parameters", QString("Parameters missing from firmware: %1.\n\n" - "You should quit QGroundControl immediately and update your firmware.").arg(facts)); + "You should quit QGroundControl immediately and update your firmware.").arg(params)); } \ No newline at end of file diff --git a/src/QGCApplication.h b/src/QGCApplication.h index 44e52c73c09a180beb11055f8a85bc4b4bae47cf..0e86dc6a0f3ec08e4f18b6b0066e31973ccf6f46 100644 --- a/src/QGCApplication.h +++ b/src/QGCApplication.h @@ -96,9 +96,9 @@ public: /// Set the current UI style void setStyle(bool styleIsDark); - /// Used to report a missing Fact. Warning will be displayed to user. Method may be called + /// Used to report a missing Parameter. Warning will be displayed to user. Method may be called /// multiple times. - void reportMissingFact(const QString& name); + void reportMissingParameter(int componentId, const QString& name); public slots: /// You can connect to this slot to show an information message box from a different thread. @@ -140,7 +140,7 @@ public: static QGCApplication* _app; ///< Our own singleton. Should be reference directly by qgcApp private slots: - void _missingFactsDisplay(void); + void _missingParamsDisplay(void); private: void _createSingletons(void); @@ -163,9 +163,9 @@ private: static const char* _lightStyleFile; bool _styleIsDark; ///< true: dark style, false: light style - static const int _missingFactDelayedDisplayTimerTimeout = 1000; ///< Timeout to wait for next missing fact to come in before display - QTimer _missingFactDelayedDisplayTimer; ///< Timer use to delay missing fact display - QStringList _missingFacts; ///< List of missing facts to be displayed + static const int _missingParamsDelayedDisplayTimerTimeout = 1000; ///< Timeout to wait for next missing fact to come in before display + QTimer _missingParamsDelayedDisplayTimer; ///< Timer use to delay missing fact display + QStringList _missingParams; ///< List of missing facts to be displayed /// Unit Test have access to creating and destroying singletons friend class UnitTest; diff --git a/src/QmlControls/ParameterEditor.qml b/src/QmlControls/ParameterEditor.qml index 0d39e0302957116019dbe73d3cbdabfcb1558345..7dbc52159dbbbd6263a8e24ba8ec64e8dd3c17fa 100644 --- a/src/QmlControls/ParameterEditor.qml +++ b/src/QmlControls/ParameterEditor.qml @@ -43,7 +43,6 @@ QGCView { property bool fullMode: true QGCPalette { id: __qgcPal; colorGroupEnabled: true } - ParameterEditorController { id: __controller } QGCLabel { id: __textMeasure; text: "X"; visible: false } property Fact __editorDialogFact: Fact { } @@ -61,6 +60,8 @@ QGCView { QGCViewPanel { id: panel + ParameterEditorController { id: controller; factPanel: panel } + Component { id: factRowsComponent @@ -82,22 +83,16 @@ QGCView { } Repeater { - model: __controller.getFactsForGroup(componentId, group) + model: controller.getFactsForGroup(componentId, group) Column { + property Fact modelFact: controller.getParameterFact(componentId, modelData) + Item { x: __leftMargin width: parent.width height: __textHeight + (ScreenTools.pixelSizeFactor * (9)) - Fact { - id: modelFact - - Component.onCompleted: { - name = modelData + ":" + componentId - } - } - QGCLabel { id: nameLabel width: __textWidth * (__maxParamChars + 1) @@ -166,22 +161,22 @@ QGCView { QGCButton { text: "Clear RC to Param" - onClicked: __controller.clearRCToParam() + onClicked: controller.clearRCToParam() } QGCButton { text: "Save to file" visible: fullMode - onClicked: __controller.saveToFile() + onClicked: controller.saveToFile() } QGCButton { text: "Load from file" visible: fullMode - onClicked: __controller.loadFromFile() + onClicked: controller.loadFromFile() } QGCButton { id: firstButton text: "Refresh" - onClicked: __controller.refresh() + onClicked: controller.refresh() } } } @@ -203,7 +198,7 @@ QGCView { Column { Repeater { - model: __controller.componentIds + model: controller.componentIds Column { id: componentColumn @@ -218,7 +213,7 @@ QGCView { } Repeater { - model: __controller.getGroupsForComponent(componentColumn.componentId) + model: controller.getGroupsForComponent(componentColumn.componentId) Column { QGCButton { @@ -260,8 +255,8 @@ QGCView { id: factRowsLoader width: factScrollView.width - property int componentId: __controller.componentIds[0] - property string group: __controller.getGroupsForComponent(__controller.componentIds[0])[0] + property int componentId: controller.componentIds[0] + property string group: controller.getGroupsForComponent(controller.componentIds[0])[0] sourceComponent: factRowsComponent } } // ScrollView - Facts @@ -276,6 +271,8 @@ QGCView { QGCViewDialog { id: editorDialog + ParameterEditorController { id: controller; factPanel: editorDialog } + property bool fullMode: true function accept() { @@ -364,7 +361,7 @@ QGCView { anchors.bottom: parent.bottom visible: __editorDialogFact.defaultValueAvailable text: "Set RC to Param..." - onClicked: __controller.setRCToParam(__editorDialogFact.name) + onClicked: controller.setRCToParam(__editorDialogFact.name) } } // Rectangle - editorDialog } // Component - Editor Dialog diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 03e000f2bd46089b7ec30a5464d761e4f522a80e..2ba5f61c70476508a854d62f17a74969e53731f2 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -33,17 +33,8 @@ #include "MainWindow.h" /// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens. -ParameterEditorController::ParameterEditorController(void) : - _uas(NULL), - _autopilot(NULL) +ParameterEditorController::ParameterEditorController(void) { - _uas = UASManager::instance()->getActiveUAS(); - Q_ASSERT(_uas); - - _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas); - Q_ASSERT(_autopilot); - Q_ASSERT(_autopilot->pluginReady()); - const QMap >& groupMap = _autopilot->getGroupMap(); foreach (int componentId, groupMap.keys()) { @@ -51,6 +42,11 @@ ParameterEditorController::ParameterEditorController(void) : } } +ParameterEditorController::~ParameterEditorController() +{ + +} + QStringList ParameterEditorController::getGroupsForComponent(int componentId) { const QMap >& groupMap = _autopilot->getGroupMap(); diff --git a/src/QmlControls/ParameterEditorController.h b/src/QmlControls/ParameterEditorController.h index 3f38266712e2a54576a32afd34fdc2f63940ec60..0f556a309ea8ed5ce11718fba9e0343cbb74a2b4 100644 --- a/src/QmlControls/ParameterEditorController.h +++ b/src/QmlControls/ParameterEditorController.h @@ -32,13 +32,15 @@ #include "AutoPilotPlugin.h" #include "UASInterface.h" +#include "FactPanelController.h" -class ParameterEditorController : public QObject +class ParameterEditorController : public FactPanelController { Q_OBJECT public: ParameterEditorController(void); + ~ParameterEditorController(); Q_PROPERTY(QStringList componentIds MEMBER _componentIds CONSTANT) @@ -54,8 +56,6 @@ public: QList model(void); private: - UASInterface* _uas; - AutoPilotPlugin* _autopilot; QStringList _componentIds; }; diff --git a/src/QmlControls/ScreenTools.cc b/src/QmlControls/ScreenTools.cc index 77c0ccb1973b7f34dfcd903ba1db45f8a65580cb..c7d59f4cf69aec041a01f7cc06c899ba2b556744 100644 --- a/src/QmlControls/ScreenTools.cc +++ b/src/QmlControls/ScreenTools.cc @@ -36,9 +36,14 @@ const double ScreenTools::_largeFontPointSize = 20; ScreenTools::ScreenTools() { - connect(MainWindow::instance(), &MainWindow::repaintCanvas, this, &ScreenTools::_updateCanvas); - connect(MainWindow::instance(), &MainWindow::pixelSizeChanged, this, &ScreenTools::_updatePixelSize); - connect(MainWindow::instance(), &MainWindow::fontSizeChanged, this, &ScreenTools::_updateFontSize); + MainWindow* mainWindow = MainWindow::instance(); + + // Unit tests can run Qml without MainWindow + if (mainWindow) { + connect(mainWindow, &MainWindow::repaintCanvas, this, &ScreenTools::_updateCanvas); + connect(mainWindow, &MainWindow::pixelSizeChanged, this, &ScreenTools::_updatePixelSize); + connect(mainWindow, &MainWindow::fontSizeChanged, this, &ScreenTools::_updateFontSize); + } } qreal ScreenTools::adjustFontPointSize(qreal pointSize) diff --git a/src/VehicleSetup/SetupView.cc b/src/VehicleSetup/SetupView.cc index 31fc188cb1571c8e1e8ff6148f9730c7eb7010ce..3878600e0629bfc47199c34985b93bf13eae2ea0 100644 --- a/src/VehicleSetup/SetupView.cc +++ b/src/VehicleSetup/SetupView.cc @@ -84,7 +84,7 @@ void SetupView::_setActiveUAS(UASInterface* uas) _uasCurrent = uas; if (_uasCurrent) { - _autoPilotPlugin = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uasCurrent); + _autoPilotPlugin = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uasCurrent).data(); _pluginReadyChanged(_autoPilotPlugin->pluginReady()); connect(_autoPilotPlugin, &AutoPilotPlugin::pluginReadyChanged, this, &SetupView::_pluginReadyChanged); } diff --git a/src/VehicleSetup/SetupViewTest.cc b/src/VehicleSetup/SetupViewTest.cc index b04605077616f9e6e4ebc2c8d37d20f5bdbf2cf2..54a544f2383db9b6217308e752c496eb9b886d98 100644 --- a/src/VehicleSetup/SetupViewTest.cc +++ b/src/VehicleSetup/SetupViewTest.cc @@ -71,7 +71,7 @@ void SetupViewTest::_clickThrough_test(void) linkMgr->connectLink(link); QTest::qWait(5000); // Give enough time for UI to settle and heartbeats to go through - AutoPilotPlugin* autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()); + AutoPilotPlugin* autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()).data(); Q_ASSERT(autopilot); QSignalSpy spyPlugin(autopilot, SIGNAL(pluginReadyChanged(bool))); diff --git a/src/ViewWidgets/ViewWidget.qml b/src/ViewWidgets/ViewWidget.qml index aab2e57cca8ffa22466aecb5466b9f78c4124dad..b8cfc7e7cd2a8c00dc12604164e4c83189b4c73e 100644 --- a/src/ViewWidgets/ViewWidget.qml +++ b/src/ViewWidgets/ViewWidget.qml @@ -25,8 +25,9 @@ Rectangle { } onPluginDisconnected: { + pageLoader.sourceComponent = null pageLoader.sourceComponent = disconnectedComponent - pageLoader.autopilot = {} + pageLoader.autopilot = null } } diff --git a/src/ViewWidgets/ViewWidgetController.cc b/src/ViewWidgets/ViewWidgetController.cc index 095bb4db34b2fb5ab1d0437be248389ad33fe5d9..c8434f7f5c2b04a279f15982b4be2b34ba923d95 100644 --- a/src/ViewWidgets/ViewWidgetController.cc +++ b/src/ViewWidgets/ViewWidgetController.cc @@ -41,13 +41,13 @@ void ViewWidgetController::_activeUasChanged(UASInterface* currentUas) if (_uas) { disconnect(_autopilot, &AutoPilotPlugin::pluginReadyChanged, this, &ViewWidgetController::_pluginReadyChanged); _uas = NULL; - _autopilot = NULL; + _autopilot = NULL; emit pluginDisconnected(); } if (currentUas) { _uas = currentUas; - _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(currentUas); + _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(currentUas).data(); Q_ASSERT(_autopilot); connect(_autopilot, &AutoPilotPlugin::pluginReadyChanged, this, &ViewWidgetController::_pluginReadyChanged); diff --git a/src/ViewWidgets/ViewWidgetController.h b/src/ViewWidgets/ViewWidgetController.h index 63a73f00dc3db8973f112f229016153692d1f305..64ba1cdcb373ab7d03200cad192dc38a59ddcf0b 100644 --- a/src/ViewWidgets/ViewWidgetController.h +++ b/src/ViewWidgets/ViewWidgetController.h @@ -48,9 +48,9 @@ private slots: void _pluginReadyChanged(bool pluginReady); private: - AutoPilotPlugin* _autopilot; - UASManagerInterface* _uasManager; - UASInterface* _uas; + AutoPilotPlugin* _autopilot; + UASManagerInterface* _uasManager; + UASInterface* _uas; }; #endif \ No newline at end of file diff --git a/src/qgcunittest/PX4RCCalibrationTest.cc b/src/qgcunittest/PX4RCCalibrationTest.cc index f22dd4221bdaccc3ad4abd8814ea30aaa634e40e..633911505ad5b02cdd00a1f90cac7eae0b79d906 100644 --- a/src/qgcunittest/PX4RCCalibrationTest.cc +++ b/src/qgcunittest/PX4RCCalibrationTest.cc @@ -151,7 +151,7 @@ void PX4RCCalibrationTest::init(void) LinkManager::instance()->connectLink(_mockLink); QTest::qWait(5000); // Give enough time for UI to settle and heartbeats to go through - _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()); + _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(UASManager::instance()->getActiveUAS()).data(); Q_ASSERT(_autopilot); QSignalSpy spyPlugin(_autopilot, SIGNAL(pluginReadyChanged(bool))); @@ -412,7 +412,7 @@ void PX4RCCalibrationTest::_fullCalibration_test(void) switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; foreach (QString switchParam, switchList) { - Q_ASSERT(_autopilot->getParameterFact(switchParam)->value().toInt() != channel + 1); + Q_ASSERT(_autopilot->getParameterFact(FactSystem::defaultComponentId, switchParam)->value().toInt() != channel + 1); } _rgFunctionChannelMap[function] = channel; @@ -424,7 +424,7 @@ void PX4RCCalibrationTest::_fullCalibration_test(void) // If we aren't mapping this function during calibration, set it to the previous setting if (!found) { - _rgFunctionChannelMap[function] = _autopilot->getParameterFact(PX4RCCalibration::_rgFunctionInfo[function].parameterName)->value().toInt(); + _rgFunctionChannelMap[function] = _autopilot->getParameterFact(FactSystem::defaultComponentId, PX4RCCalibration::_rgFunctionInfo[function].parameterName)->value().toInt(); qCDebug(PX4RCCalibrationTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function]; if (_rgFunctionChannelMap[function] == 0) { _rgFunctionChannelMap[function] = -1; // -1 signals no mapping @@ -488,8 +488,8 @@ void PX4RCCalibrationTest::_validateParameters(void) expectedParameterValue = chanIndex + 1; // 1-based parameter value } - qCDebug(PX4RCCalibrationTestLog) << "Validate" << chanFunction << _autopilot->getParameterFact(PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(); - QCOMPARE(_autopilot->getParameterFact(PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedParameterValue); + qCDebug(PX4RCCalibrationTestLog) << "Validate" << chanFunction << _autopilot->getParameterFact(FactSystem::defaultComponentId, PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(); + QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedParameterValue); } // Validate the channel settings. Note the channels are 1-based in parameter names. @@ -503,13 +503,13 @@ void PX4RCCalibrationTest::_validateParameters(void) int rcTrimExpected = _rgChannelSettingsValidate[chan].rcTrim; bool rcReversedExpected = _rgChannelSettingsValidate[chan].reversed; - int rcMinActual = _autopilot->getParameterFact(minTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcMinActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->value().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcMaxActual = _autopilot->getParameterFact(maxTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcMaxActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->value().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcTrimActual = _autopilot->getParameterFact(trimTpl.arg(oneBasedChannel))->value().toInt(&convertOk); + int rcTrimActual = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->value().toInt(&convertOk); QCOMPARE(convertOk, true); - float rcReversedFloat = _autopilot->getParameterFact(revTpl.arg(oneBasedChannel))->value().toFloat(&convertOk); + float rcReversedFloat = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->value().toFloat(&convertOk); QCOMPARE(convertOk, true); bool rcReversedActual = (rcReversedFloat == -1.0f); @@ -531,6 +531,6 @@ void PX4RCCalibrationTest::_validateParameters(void) expectedValue = _rgFunctionChannelMap[chanFunction] + 1; // 1-based } // qCDebug(PX4RCCalibrationTestLog) << chanFunction << expectedValue << mapParamsSet[PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName].toInt(); - QCOMPARE(_autopilot->getParameterFact(PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedValue); + QCOMPARE(_autopilot->getParameterFact(FactSystem::defaultComponentId, PX4RCCalibration::_rgFunctionInfo[chanFunction].parameterName)->value().toInt(), expectedValue); } } diff --git a/src/ui/QGCMapRCToParamDialog.cpp b/src/ui/QGCMapRCToParamDialog.cpp index e061058e5cf04bd0547937043ed796a9ddb1275d..f4e9c5d434809b3598de8dce8f338af1a97cf09a 100644 --- a/src/ui/QGCMapRCToParamDialog.cpp +++ b/src/ui/QGCMapRCToParamDialog.cpp @@ -101,13 +101,13 @@ ParamLoader::ParamLoader(QString paramName, UASInterface* uas, QObject* parent) _paramName(paramName), _paramReceived(false) { - _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas); + _autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas).data(); Q_ASSERT(_autopilot); } void ParamLoader::load() { - connect(_autopilot->getParameterFact(_paramName), &Fact::valueChanged, this, &ParamLoader::_parameterUpdated); + connect(_autopilot->getParameterFact(FactSystem::defaultComponentId, _paramName), &Fact::valueChanged, this, &ParamLoader::_parameterUpdated); // refresh the parameter from onboard to make sure the current value is used _autopilot->refreshParameter(FactSystem::defaultComponentId, _paramName); @@ -117,5 +117,5 @@ void ParamLoader::_parameterUpdated(QVariant value) { Q_UNUSED(value); - emit paramLoaded(true, _autopilot->getParameterFact(_paramName)->value().toFloat(), ""); + emit paramLoaded(true, _autopilot->getParameterFact(FactSystem::defaultComponentId, _paramName)->value().toFloat(), ""); } diff --git a/src/ui/px4_configuration/PX4RCCalibration.cc b/src/ui/px4_configuration/PX4RCCalibration.cc index 4f288c5d401fe21e6adb320009146defe080678a..ac019ee0a7c84c50eae2e5f5d67485dd1326719a 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.cc +++ b/src/ui/px4_configuration/PX4RCCalibration.cc @@ -707,7 +707,7 @@ void PX4RCCalibration::_resetInternalCalibrationValues(void) enum rcCalFunctions curFunction = rgFlightModeFunctions[i]; bool ok; - int switchChannel = _autopilot->getParameterFact(_rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok); + int switchChannel = _autopilot->getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[curFunction].parameterName)->value().toInt(&ok); Q_ASSERT(ok); // Parameter: 1-based channel, 0=not mapped @@ -749,16 +749,16 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) for (int i = 0; i < _chanMax; ++i) { struct ChannelInfo* info = &_rgChannelInfo[i]; - info->rcTrim = _autopilot->getParameterFact(trimTpl.arg(i+1))->value().toInt(&convertOk); + info->rcTrim = _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMin = _autopilot->getParameterFact(minTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMin = _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - info->rcMax = _autopilot->getParameterFact(maxTpl.arg(i+1))->value().toInt(&convertOk); + info->rcMax = _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->value().toInt(&convertOk); Q_ASSERT(convertOk); - float floatReversed = _autopilot->getParameterFact(revTpl.arg(i+1))->value().toFloat(&convertOk); + float floatReversed = _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1))->value().toFloat(&convertOk); Q_ASSERT(convertOk); Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); info->reversed = floatReversed == -1.0f; @@ -767,7 +767,7 @@ void PX4RCCalibration::_setInternalCalibrationValuesFromParameters(void) for (int i=0; igetParameterFact(_rgFunctionInfo[i].parameterName)->value().toInt(&convertOk); + paramChannel = _autopilot->getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->value().toInt(&convertOk); Q_ASSERT(convertOk); if (paramChannel != 0) { @@ -877,10 +877,10 @@ void PX4RCCalibration::_writeCalibration(void) struct ChannelInfo* info = &_rgChannelInfo[chan]; int oneBasedChannel = chan + 1; - _autopilot->getParameterFact(trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim); - _autopilot->getParameterFact(minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin); - _autopilot->getParameterFact(maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax); - _autopilot->getParameterFact(revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f); + _autopilot->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->setValue((float)info->rcTrim); + _autopilot->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->setValue((float)info->rcMin); + _autopilot->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->setValue((float)info->rcMax); + _autopilot->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->setValue(info->reversed ? -1.0f : 1.0f); } // Write function mapping parameters @@ -893,12 +893,12 @@ void PX4RCCalibration::_writeCalibration(void) // Note that the channel value is 1-based paramChannel = _rgFunctionChannelMapping[i] + 1; } - _autopilot->getParameterFact(_rgFunctionInfo[i].parameterName)->setValue(paramChannel); + _autopilot->getParameterFact(FactSystem::defaultComponentId, _rgFunctionInfo[i].parameterName)->setValue(paramChannel); } // If the RC_CHAN_COUNT parameter is available write the channel count - if (_autopilot->parameterExists("RC_CHAN_CNT")) { - _autopilot->getParameterFact("RC_CHAN_CNT")->setValue(_chanCount); + if (_autopilot->parameterExists(FactSystem::defaultComponentId, "RC_CHAN_CNT")) { + _autopilot->getParameterFact(FactSystem::defaultComponentId, "RC_CHAN_CNT")->setValue(_chanCount); } _stopCalibration(); diff --git a/src/ui/px4_configuration/PX4RCCalibration.h b/src/ui/px4_configuration/PX4RCCalibration.h index 718bb38e7b69ae5d73cb0e2bd3b4f2a70dd01f66..66d827e6f6b50fdddef030d61f86b07d9b928fbd 100644 --- a/src/ui/px4_configuration/PX4RCCalibration.h +++ b/src/ui/px4_configuration/PX4RCCalibration.h @@ -256,8 +256,8 @@ private: RCValueWidget* _rgRCValueMonitorWidget[_chanMax]; ///< Array of radio channel value widgets QLabel* _rgRCValueMonitorLabel[_chanMax]; ///< Array of radio channel value labels - UASInterface* _uas; - AutoPilotPlugin* _autopilot; + UASInterface* _uas; + QSharedPointer _autopilot; Ui::PX4RCCalibration* _ui; diff --git a/src/ui/toolbar/MainToolBar.cc b/src/ui/toolbar/MainToolBar.cc index 470cd8ab7fc68a96549d2d8fd58d7eaeee2b3e7e..d799d8bdd2c8471ea3c8f1c232790e58a7530ca7 100644 --- a/src/ui/toolbar/MainToolBar.cc +++ b/src/ui/toolbar/MainToolBar.cc @@ -282,7 +282,7 @@ void MainToolBar::_forgetUAS(UASInterface* uas) if (_mav != NULL && _mav == uas) { disconnect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MainToolBar::_handleTextMessage); disconnect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged); - disconnect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue); + disconnect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav).data(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue); _mav = NULL; } } @@ -302,7 +302,7 @@ void MainToolBar::_setActiveUAS(UASInterface* active) { connect(UASMessageHandler::instance(), &UASMessageHandler::textMessageCountChanged, this, &MainToolBar::_handleTextMessage); connect(_mav, &UASInterface::remoteControlRSSIChanged, this, &MainToolBar::_remoteControlRSSIChanged); - connect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue); + connect(AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_mav).data(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBar::_setProgressBarValue); } }