From e92110a7d39d2df04712aef393b25a83e1cad546 Mon Sep 17 00:00:00 2001 From: Don Gagne Date: Sun, 18 Sep 2016 12:05:29 -0700 Subject: [PATCH] Refactor parameter apis from AutoPilotPlugin to ParameterManager --- QGCCommon.pri | 2 +- .../APM/APMAirframeComponent.cc | 7 +- .../APM/APMAirframeComponentController.cc | 3 +- .../APM/APMAutoPilotPlugin.cc | 28 +---- src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h | 4 - src/AutoPilotPlugins/APM/APMCompassCal.cc | 11 +- src/AutoPilotPlugins/APM/APMPowerComponent.cc | 3 +- src/AutoPilotPlugins/APM/APMRadioComponent.cc | 21 ++-- .../APM/APMSensorsComponent.cc | 15 +-- .../APM/APMSensorsComponentController.cc | 11 +- .../APM/APMTuningComponent.cc | 3 +- src/AutoPilotPlugins/AutoPilotPlugin.cc | 104 ++---------------- src/AutoPilotPlugins/AutoPilotPlugin.h | 57 +--------- .../Common/ESP8266ComponentController.cc | 3 +- .../Generic/GenericAutoPilotPlugin.cc | 9 -- .../Generic/GenericAutoPilotPlugin.h | 4 - src/AutoPilotPlugins/PX4/AirframeComponent.cc | 3 +- .../PX4/FlightModesComponent.cc | 12 +- .../PX4/PX4AutoPilotPlugin.cc | 21 ++-- src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h | 7 +- src/AutoPilotPlugins/PX4/PX4RadioComponent.cc | 8 +- src/AutoPilotPlugins/PX4/PowerComponent.cc | 6 +- .../PX4/PowerComponentController.cc | 4 +- src/AutoPilotPlugins/PX4/SensorsComponent.cc | 6 +- .../PX4/SensorsComponentController.cc | 15 ++- .../FactControls/FactPanelController.cc | 10 +- src/FactSystem/FactSystemTestBase.cc | 11 +- src/FactSystem/ParameterManager.cc | 80 +++++++++----- src/FactSystem/ParameterManager.h | 49 +++++---- src/FactSystem/ParameterManagerTest.cc | 8 +- src/FirmwarePlugin/APM/APMGeoFenceManager.cc | 28 ++--- .../APM/ArduCopterFirmwarePlugin.cc | 3 +- src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc | 10 +- src/MissionManager/GeoFenceController.cc | 12 +- src/MissionManager/MissionController.cc | 2 +- src/QGCApplication.cc | 4 +- src/QmlControls/ParameterEditorController.cc | 26 ++--- src/Vehicle/MultiVehicleManager.cc | 15 +-- src/Vehicle/MultiVehicleManager.h | 2 +- src/Vehicle/Vehicle.cc | 35 +----- src/Vehicle/Vehicle.h | 20 +--- src/VehicleSetup/SetupView.qml | 2 +- src/VehicleSetup/VehicleComponent.cc | 5 +- src/qgcunittest/RadioConfigTest.cc | 18 +-- src/ui/QGCMapRCToParamDialog.cpp | 5 +- src/ui/toolbar/MainToolBarController.cc | 5 +- 46 files changed, 268 insertions(+), 449 deletions(-) diff --git a/QGCCommon.pri b/QGCCommon.pri index c2c9c7aba..8238a85ae 100644 --- a/QGCCommon.pri +++ b/QGCCommon.pri @@ -66,7 +66,7 @@ linux { } else { QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6 } - QMAKE_MAC_SDK = macosx10.11 + QMAKE_MAC_SDK = macosx10.12 QMAKE_CXXFLAGS += -fvisibility=hidden } else { error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported") diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc index ce09588cf..ccbb3ee0c 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponent.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponent.cc @@ -7,12 +7,9 @@ * ****************************************************************************/ - -/// @file -/// @author Don Gagne - #include "APMAirframeComponent.h" #include "ArduCopterFirmwarePlugin.h" +#include "ParameterManager.h" APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent) @@ -52,7 +49,7 @@ bool APMAirframeComponent::requiresSetup(void) const bool APMAirframeComponent::setupComplete(void) const { if (_requiresFrameSetup) { - return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0; + return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0; } else { return true; } diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc index f095b6a96..3f488f217 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentController.cc @@ -18,6 +18,7 @@ #include "AutoPilotPluginManager.h" #include "QGCApplication.h" #include "QGCFileDownload.h" +#include "ParameterManager.h" #include #include @@ -107,7 +108,7 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri } } qgcApp()->restoreOverrideCursor(); - _autopilot->refreshAllParameters(); + _vehicle->parameterManager()->refreshAllParameters(); } APMAirframeType::APMAirframeType(const QString& name, const QString& imageResource, int type, QObject* parent) : diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc index 9f1e94478..ece082b97 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.cc @@ -59,9 +59,7 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin() const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) { if (_components.count() == 0 && !_incorrectParameterVersion) { - Q_ASSERT(_vehicle); - - if (parametersReady()) { + if (_vehicle->parameterManager()->parametersReady()) { _airframeComponent = new APMAirframeComponent(_vehicle, this); _airframeComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); @@ -107,7 +105,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); //-- Is there an ESP8266 Connected? - if(factExists(FactSystem::ParameterProvider, MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { + if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { _esp8266Component = new ESP8266Component(_vehicle, this); _esp8266Component->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); @@ -119,25 +117,3 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) return _components; } - -/// This will perform various checks prior to signalling that the plug in ready -void APMAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) -{ -#if 0 - I believe APM has parameter version stamp, we should check that - - // 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(FactSystem::defaultComponentId, "SENS_GYRO_XOFF")) { - _incorrectParameterVersion = true; - qgcApp()->showMessage("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."); - } -#endif - Q_UNUSED(missingParameters); - _parametersReady = true; - _missingParameters = false; // we apply only the parameters that do exists on the FactSystem. - emit missingParametersChanged(_missingParameters); - emit parametersReadyChanged(_parametersReady); -} diff --git a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h index 35d870d61..62ffbdf06 100644 --- a/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/APM/APMAutoPilotPlugin.h @@ -52,10 +52,6 @@ public: APMTuningComponent* tuningComponent (void) const { return _tuningComponent; } ESP8266Component* esp8266Component (void) const { return _esp8266Component; } -public slots: - // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle - void _parametersReadyPreChecks(bool missingParameters); - private: bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed QVariantList _components; diff --git a/src/AutoPilotPlugins/APM/APMCompassCal.cc b/src/AutoPilotPlugins/APM/APMCompassCal.cc index 71a257032..42939faee 100644 --- a/src/AutoPilotPlugins/APM/APMCompassCal.cc +++ b/src/AutoPilotPlugins/APM/APMCompassCal.cc @@ -10,6 +10,7 @@ #include "APMCompassCal.h" #include "AutoPilotPlugin.h" +#include "ParameterManager.h" QGC_LOGGING_CATEGORY(APMCompassCalLog, "APMCompassCalLog") @@ -613,11 +614,11 @@ void APMCompassCal::startCalibration(void) _calWorkerThread->rgCompassAvailable[i] = true; const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3]; - if (_vehicle->parameterExists(-1, deviceIdParam)) { - _calWorkerThread->rgCompassAvailable[i] = _vehicle->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0; + if (_vehicle->parameterManager()->parameterExists(-1, deviceIdParam)) { + _calWorkerThread->rgCompassAvailable[i] = _vehicle->parameterManager()->getParameter(-1, deviceIdParam)->rawValue().toInt() > 0; for (int j=0; j<3; j++) { const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; - Fact* paramFact = _vehicle->getParameterFact(-1, offsetParam); + Fact* paramFact = _vehicle->parameterManager()->getParameter(-1, offsetParam); _rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat(); paramFact->setRawValue(0.0); @@ -639,8 +640,8 @@ void APMCompassCal::cancelCalibration(void) for (int i=0; i<3; i++) { for (int j=0; j<3; j++) { const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; - if (_vehicle->parameterExists(-1, offsetParam)) { - _vehicle->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]); + if (_vehicle->parameterManager()->parameterExists(-1, offsetParam)) { + _vehicle->parameterManager()->getParameter(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]); } } } diff --git a/src/AutoPilotPlugins/APM/APMPowerComponent.cc b/src/AutoPilotPlugins/APM/APMPowerComponent.cc index a63f48bba..11b8ebe74 100644 --- a/src/AutoPilotPlugins/APM/APMPowerComponent.cc +++ b/src/AutoPilotPlugins/APM/APMPowerComponent.cc @@ -11,6 +11,7 @@ #include "APMPowerComponent.h" #include "APMAutoPilotPlugin.h" #include "APMAirframeComponent.h" +#include "ParameterManager.h" APMPowerComponent::APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent), @@ -40,7 +41,7 @@ bool APMPowerComponent::requiresSetup(void) const bool APMPowerComponent::setupComplete(void) const { - return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0; + return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0; } QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const diff --git a/src/AutoPilotPlugins/APM/APMRadioComponent.cc b/src/AutoPilotPlugins/APM/APMRadioComponent.cc index 3b1748a18..4b6ef968c 100644 --- a/src/AutoPilotPlugins/APM/APMRadioComponent.cc +++ b/src/AutoPilotPlugins/APM/APMRadioComponent.cc @@ -11,6 +11,7 @@ #include "APMRadioComponent.h" #include "APMAutoPilotPlugin.h" #include "APMAirframeComponent.h" +#include "ParameterManager.h" APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent), @@ -19,7 +20,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo _mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE"); foreach (const QString& mapParam, _mapParams) { - Fact* fact = _vehicle->getParameterFact(-1, mapParam); + Fact* fact = _vehicle->parameterManager()->getParameter(-1, mapParam); connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); } @@ -56,7 +57,7 @@ bool APMRadioComponent::setupComplete(void) const // First check for all attitude controls mapped for (int i=0; i<_mapParams.count(); i++) { - mapValues << _vehicle->getParameterFact(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt(); + mapValues << _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt(); if (mapValues[i] <= 0) { return false; } @@ -64,14 +65,14 @@ bool APMRadioComponent::setupComplete(void) const // Next check RC#_MIN/MAX/TRIM all at defaults foreach (const QString& mapParam, _mapParams) { - int channel = _vehicle->getParameterFact(-1, mapParam)->rawValue().toInt(); - if (_vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) { + int channel = _vehicle->parameterManager()->getParameter(-1, mapParam)->rawValue().toInt(); + if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) { return true; } - if (_vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) { + if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) { return true; } - if (_vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) { + if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) { return true; } } @@ -116,17 +117,17 @@ void APMRadioComponent::_connectSetupTriggers(void) // Get the channels for attitude controls and connect to those values for triggers foreach (const QString& mapParam, _mapParams) { - int channel = _vehicle->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt(); + int channel = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, mapParam)->rawValue().toInt(); - Fact* fact = _vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel)); + Fact* fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_MIN").arg(channel)); _triggerFacts << fact; connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); - fact = _vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel)); + fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_MAX").arg(channel)); _triggerFacts << fact; connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); - fact = _vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel)); + fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_TRIM").arg(channel)); _triggerFacts << fact; connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponent.cc b/src/AutoPilotPlugins/APM/APMSensorsComponent.cc index aa353e174..3f45eeca4 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponent.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponent.cc @@ -12,6 +12,7 @@ #include "APMAutoPilotPlugin.h" #include "APMSensorsComponentController.h" #include "APMAirframeComponent.h" +#include "ParameterManager.h" // These two list must be kept in sync @@ -62,7 +63,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const // Accelerometer triggers triggers << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; - if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) { + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) { triggers << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3"); triggers << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z"); triggers << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z"); @@ -108,10 +109,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z"); for (size_t i=0; igetParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 && - _vehicle->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 && + _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) { for (size_t j=0; jgetParameterFact(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) { return true; } } @@ -133,7 +134,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const rgOffsets.clear(); // This parameter is not available in all firmware version. Specifically missing from older Solo firmware. - if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) { + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) { rgUse << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3"); // We have usage information for the remaining accels, so we can test them sa well @@ -147,9 +148,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const } for (int i=0; igetParameterFact(FactSystem::defaultComponentId, rgUse[i])->rawValue().toInt() != 0) { + if (rgUse.count() == 0 || _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgUse[i])->rawValue().toInt() != 0) { for (int j=0; jgetParameterFact(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) { return true; } } diff --git a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc index 601450325..4b7510a50 100644 --- a/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc +++ b/src/AutoPilotPlugins/APM/APMSensorsComponentController.cc @@ -13,6 +13,7 @@ #include "UAS.h" #include "QGCApplication.h" #include "APMAutoPilotPlugin.h" +#include "ParameterManager.h" #include #include @@ -214,9 +215,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, Q_UNUSED(compId); Q_UNUSED(severity); - UASInterface* uas = _autopilot->vehicle()->uas(); - Q_ASSERT(uas); - if (uasId != uas->getUASID()) { + if (uasId != _vehicle->id()) { return; } @@ -428,12 +427,12 @@ void APMSensorsComponentController::_refreshParams(void) fastRefreshList << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z"); foreach (const QString ¶mName, fastRefreshList) { - _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); + _vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, paramName); } // Now ask for all to refresh - _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_")); - _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_")); + _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_")); + _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_")); } void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) diff --git a/src/AutoPilotPlugins/APM/APMTuningComponent.cc b/src/AutoPilotPlugins/APM/APMTuningComponent.cc index d2e30b42b..32bd528b9 100644 --- a/src/AutoPilotPlugins/APM/APMTuningComponent.cc +++ b/src/AutoPilotPlugins/APM/APMTuningComponent.cc @@ -11,6 +11,7 @@ #include "APMTuningComponent.h" #include "APMAutoPilotPlugin.h" #include "APMAirframeComponent.h" +#include "ParameterManager.h" APMTuningComponent::APMTuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent(vehicle, autopilot, parent) @@ -60,7 +61,7 @@ QUrl APMTuningComponent::setupSource(void) const case MAV_TYPE_OCTOROTOR: case MAV_TYPE_TRICOPTER: // Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares - if (_vehicle->parameterExists(-1, QStringLiteral("CH9_OPT"))) { + if (_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("CH9_OPT"))) { qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml"); } break; diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.cc b/src/AutoPilotPlugins/AutoPilotPlugin.cc index fb87d736b..4f938d0f9 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/AutoPilotPlugin.cc @@ -21,15 +21,9 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) : QObject(parent) , _vehicle(vehicle) , _firmwarePlugin(vehicle->firmwarePlugin()) - , _parametersReady(false) - , _missingParameters(false) , _setupComplete(false) { - Q_ASSERT(vehicle); - - connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected); - connect(this, &AutoPilotPlugin::parametersReadyChanged, this, &AutoPilotPlugin::_parametersReadyChanged); } AutoPilotPlugin::~AutoPilotPlugin() @@ -37,26 +31,6 @@ AutoPilotPlugin::~AutoPilotPlugin() } -void AutoPilotPlugin::_uasDisconnected(void) -{ - _parametersReady = false; - emit parametersReadyChanged(_parametersReady); -} - -void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady) -{ - if (parametersReady) { - _recalcSetupComplete(); - if (!_setupComplete) { - qgcApp()->showMessage("One or more vehicle components require setup prior to flight."); - - // Take the user to Vehicle Summary - qgcApp()->showSetupView(); - qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); - } - } -} - void AutoPilotPlugin::_recalcSetupComplete(void) { bool newSetupComplete = true; @@ -79,81 +53,17 @@ void AutoPilotPlugin::_recalcSetupComplete(void) bool AutoPilotPlugin::setupComplete(void) { - Q_ASSERT(_parametersReady); return _setupComplete; } -void AutoPilotPlugin::resetAllParametersToDefaults(void) -{ - mavlink_message_t msg; - MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); - - mavlink_msg_command_long_pack(mavlink->getSystemId(), - mavlink->getComponentId(), - &msg, - _vehicle->id(), // Target systeem - _vehicle->defaultComponentId(), // Target component - MAV_CMD_PREFLIGHT_STORAGE, - 0, // Confirmation - 2, // 2 = Reset params to default - -1, // -1 = No change to mission storage - 0, // 0 = Ignore - 0, 0, 0, 0); // Unused - _vehicle->sendMessageOnPriorityLink(msg); -} - -void AutoPilotPlugin::refreshAllParameters(unsigned char componentID) -{ - _vehicle->getParameterManager()->refreshAllParameters((uint8_t)componentID); -} - -void AutoPilotPlugin::refreshParameter(int componentId, const QString& name) -{ - _vehicle->getParameterManager()->refreshParameter(componentId, name); -} - -void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix) +void AutoPilotPlugin::parametersReadyPreChecks(void) { - _vehicle->getParameterManager()->refreshParametersPrefix(componentId, namePrefix); -} + _recalcSetupComplete(); + if (!_setupComplete) { + qgcApp()->showMessage("One or more vehicle components require setup prior to flight."); -bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) -{ - switch (provider) { - case FactSystem::ParameterProvider: - return _vehicle->getParameterManager()->parameterExists(componentId, name); - - // Other providers will go here once they come online + // Take the user to Vehicle Summary + qgcApp()->showSetupView(); + qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents); } - - Q_ASSERT(false); - return false; -} - -Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, const QString& name) -{ - switch (provider) { - case FactSystem::ParameterProvider: - return _vehicle->getParameterManager()->getFact(componentId, name); - - // Other providers will go here once they come online - } - - Q_ASSERT(false); - return NULL; -} - -QStringList AutoPilotPlugin::parameterNames(int componentId) -{ - return _vehicle->getParameterManager()->parameterNames(componentId); -} - -void AutoPilotPlugin::writeParametersToStream(QTextStream &stream) -{ - _vehicle->getParameterManager()->writeParametersToStream(stream); -} - -QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream) -{ - return _vehicle->getParameterManager()->readParametersFromStream(stream); } diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h index 74d86449a..b5aeb7c8f 100644 --- a/src/AutoPilotPlugins/AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/AutoPilotPlugin.h @@ -38,68 +38,24 @@ public: AutoPilotPlugin(Vehicle* vehicle, QObject* parent); ~AutoPilotPlugin(); - /// true: parameters are ready for use - Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) - - /// true: parameters are missing from firmware response, false: all parameters received from firmware - Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) - /// List of VehicleComponent objects Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT) /// false: One or more vehicle components require setup Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) - /// Reset all parameters to their default values - Q_INVOKABLE void resetAllParametersToDefaults(void); - - /// Re-request the full set of parameters from the autopilot - Q_INVOKABLE void refreshAllParameters(unsigned char componentID = MAV_COMP_ID_ALL); - - /// Request a refresh on the specific parameter - Q_INVOKABLE void refreshParameter(int componentId, const QString& name); - - /// Request a refresh on all parameters that begin with the specified prefix - Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix); - - /// Returns all parameter names - QStringList parameterNames(int componentId); - - /// Writes the parameter facts to the specified stream - void writeParametersToStream(QTextStream &stream); - - /// Reads the parameters from the stream and updates values - /// @return Errors during load. Empty string for no errors - QString readParametersFromStream(QTextStream &stream); - - /// Returns true if the specifed fact exists - Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider - int componentId, ///< fact component, -1=default component - const QString& name); ///< fact name - - /// Returns the specified Fact. - /// WARNING: Will assert if fact does not exists. If that possibility exists, check for existence first with - /// factExists. - Fact* getFact(FactSystem::Provider_t provider, ///< fact provider - int componentId, ///< fact component, -1=default component - const QString& name); ///< fact name + /// Called when parameters are ready for the first time. Note that parameters may still be missing. + /// Overrides must call base class. + virtual void parametersReadyPreChecks(void); // Must be implemented by derived class virtual const QVariantList& vehicleComponents(void) = 0; // Property accessors - bool parametersReady(void) { return _parametersReady; } - bool missingParameters(void) { return _missingParameters; } bool setupComplete(void); - Vehicle* vehicle(void) { return _vehicle; } - virtual void _parametersReadyPreChecks(bool parametersReady) = 0; - signals: - void parametersReadyChanged(bool parametersReady); - void missingParametersChanged(bool missingParameters); void setupCompleteChanged(bool setupComplete); - void parameterListProgress(float value); protected: /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin @@ -107,15 +63,8 @@ protected: Vehicle* _vehicle; FirmwarePlugin* _firmwarePlugin; - bool _parametersReady; - bool _missingParameters; bool _setupComplete; - -private slots: - void _uasDisconnected(void); - void _parametersReadyChanged(bool parametersReady); - private: void _recalcSetupComplete(void); }; diff --git a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc index 0c2418b65..5e6ad14c5 100644 --- a/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc +++ b/src/AutoPilotPlugins/Common/ESP8266ComponentController.cc @@ -16,6 +16,7 @@ #include "AutoPilotPluginManager.h" #include "QGCApplication.h" #include "UAS.h" +#include "ParameterManager.h" #include #include @@ -393,7 +394,7 @@ ESP8266ComponentController::_commandAck(uint8_t compID, uint16_t command, uint8_ emit busyChanged(); qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command; if(command == MAV_CMD_PREFLIGHT_STORAGE) { - _autopilot->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE); + _vehicle->parameterManager()->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE); } } } diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc index ecfe4e441..f2c7771c5 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc @@ -25,12 +25,3 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) return emptyList; } - -/// This will perform various checks prior to signalling that the plug in ready -void GenericAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) -{ - _parametersReady = true; - _missingParameters = missingParameters; - emit missingParametersChanged(_missingParameters); - emit parametersReadyChanged(_parametersReady); -} diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h index 1dda57b00..64bb3e77a 100644 --- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h +++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h @@ -27,10 +27,6 @@ public: // Overrides from AutoPilotPlugin virtual const QVariantList& vehicleComponents(void); - -public slots: - // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle - void _parametersReadyPreChecks(bool missingParameters); }; #endif diff --git a/src/AutoPilotPlugins/PX4/AirframeComponent.cc b/src/AutoPilotPlugins/PX4/AirframeComponent.cc index daa0eb436..5525cc264 100644 --- a/src/AutoPilotPlugins/PX4/AirframeComponent.cc +++ b/src/AutoPilotPlugins/PX4/AirframeComponent.cc @@ -13,6 +13,7 @@ #include "AirframeComponent.h" #include "QGCQmlWidgetHolder.h" +#include "ParameterManager.h" #if 0 // Broken by latest mavlink module changes. Not used yet. Comment out for now. @@ -129,7 +130,7 @@ bool AirframeComponent::requiresSetup(void) const bool AirframeComponent::setupComplete(void) const { - return _vehicle->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0; + return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0; } QStringList AirframeComponent::setupCompleteChangedTriggerList(void) const diff --git a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc index da66034d3..2adfeb226 100644 --- a/src/AutoPilotPlugins/PX4/FlightModesComponent.cc +++ b/src/AutoPilotPlugins/PX4/FlightModesComponent.cc @@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const bool FlightModesComponent::requiresSetup(void) const { - return _vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; + return _vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; } bool FlightModesComponent::setupComplete(void) const { - if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) { + if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) { return true; } - if (_vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 || - (_vehicle->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 || + (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) { return true; } @@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const QString FlightModesComponent::prerequisiteSetup(void) const { - if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) { + if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) { // No RC input return QString(); } else { @@ -92,7 +92,7 @@ QString FlightModesComponent::prerequisiteSetup(void) const return plugin->airframeComponent()->name(); } else if (!plugin->radioComponent()->setupComplete()) { return plugin->radioComponent()->name(); - } else if (!plugin->vehicle()->hilMode() && !plugin->sensorsComponent()->setupComplete()) { + } else if (!_vehicle->hilMode() && !plugin->sensorsComponent()->setupComplete()) { return plugin->sensorsComponent()->name(); } } diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc index 805a9b2d5..af9d98d3c 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc @@ -52,7 +52,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) if (_components.count() == 0 && !_incorrectParameterVersion) { Q_ASSERT(_vehicle); - if (parametersReady()) { + if (_vehicle->parameterManager()->parametersReady()) { _airframeComponent = new AirframeComponent(_vehicle, this); _airframeComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); @@ -91,14 +91,14 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) _components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent)); //-- Is there support for cameras? - if(factExists(FactSystem::ParameterProvider, _vehicle->id(), "TRIG_MODE")) { + if(_vehicle->parameterManager()->parameterExists(_vehicle->id(), "TRIG_MODE")) { _cameraComponent = new CameraComponent(_vehicle, this); _cameraComponent->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); } //-- Is there an ESP8266 Connected? - if(factExists(FactSystem::ParameterProvider, MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { + if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) { _esp8266Component = new ESP8266Component(_vehicle, this); _esp8266Component->setupTriggerSignals(); _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); @@ -111,21 +111,18 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) return _components; } -/// This will perform various checks prior to signalling that the plug in ready -void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters) +void PX4AutoPilotPlugin::parametersReadyPreChecks(void) { + // Base class must be called + AutoPilotPlugin::parametersReadyPreChecks(); + // 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 (_vehicle->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") || - _vehicle->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) { + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") || + _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) { _incorrectParameterVersion = true; qgcApp()->showMessage("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."); } - - _parametersReady = true; - _missingParameters = missingParameters; - emit missingParametersChanged(_missingParameters); - emit parametersReadyChanged(_parametersReady); } diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h index 9bb2737ad..32f63dd14 100644 --- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h +++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h @@ -40,7 +40,8 @@ public: ~PX4AutoPilotPlugin(); // Overrides from AutoPilotPlugin - virtual const QVariantList& vehicleComponents(void); + const QVariantList& vehicleComponents(void) final; + void parametersReadyPreChecks(void) final; // These methods should only be used by objects within the plugin AirframeComponent* airframeComponent(void) { return _airframeComponent; } @@ -54,10 +55,6 @@ public: MotorComponent* motorComponent(void) { return _motorComponent; } PX4TuningComponent* tuningComponent(void) { return _tuningComponent; } -public slots: - // FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle - void _parametersReadyPreChecks(bool missingParameters); - private: PX4AirframeLoader* _airframeFacts; QVariantList _components; diff --git a/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc b/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc index b0b762dd9..ed3d68b8d 100644 --- a/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc +++ b/src/AutoPilotPlugins/PX4/PX4RadioComponent.cc @@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const bool PX4RadioComponent::requiresSetup(void) const { - return _vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; + return _vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true; } bool PX4RadioComponent::setupComplete(void) const { - if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { + if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { // The best we can do to detect the need for a radio calibration is look for attitude // controls to be mapped. QStringList attitudeMappings; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; foreach(const QString &mapParam, attitudeMappings) { - if (_vehicle->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, mapParam)->rawValue().toInt() == 0) { return false; } } @@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const QString PX4RadioComponent::prerequisiteSetup(void) const { - if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { + if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() != 1) { PX4AutoPilotPlugin* plugin = dynamic_cast(_autopilot); if (!plugin->airframeComponent()->setupComplete()) { diff --git a/src/AutoPilotPlugins/PX4/PowerComponent.cc b/src/AutoPilotPlugins/PX4/PowerComponent.cc index fa43c9a23..9a71a3a1d 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponent.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponent.cc @@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const bool PowerComponent::setupComplete(void) const { QVariant cvalue, evalue, nvalue; - return _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && - _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && - _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; + return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && + _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && + _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; } QStringList PowerComponent::setupCompleteChangedTriggerList(void) const diff --git a/src/AutoPilotPlugins/PX4/PowerComponentController.cc b/src/AutoPilotPlugins/PX4/PowerComponentController.cc index a232af99d..f26def0bb 100644 --- a/src/AutoPilotPlugins/PX4/PowerComponentController.cc +++ b/src/AutoPilotPlugins/PX4/PowerComponentController.cc @@ -58,9 +58,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int Q_UNUSED(compId); Q_UNUSED(severity); - UASInterface* uas = _autopilot->vehicle()->uas(); - Q_ASSERT(uas); - if (uasId != uas->getUASID()) { + if (uasId != _vehicle->id()) { return; } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponent.cc b/src/AutoPilotPlugins/PX4/SensorsComponent.cc index 4d8928a4e..5d93625f0 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponent.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponent.cc @@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const bool SensorsComponent::setupComplete(void) const { foreach (const QString &triggerParam, _deviceIds) { - if (_vehicle->getParameterFact(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, triggerParam)->rawValue().toFloat() == 0.0f) { return false; } } if (_vehicle->fixedWing() || _vehicle->vtol()) { - if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) { - if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) { + if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) { return false; } } diff --git a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc index cd1cac975..7150e49c4 100644 --- a/src/AutoPilotPlugins/PX4/SensorsComponentController.cc +++ b/src/AutoPilotPlugins/PX4/SensorsComponentController.cc @@ -15,6 +15,7 @@ #include "QGCMAVLink.h" #include "UAS.h" #include "QGCApplication.h" +#include "ParameterManager.h" #include #include @@ -219,9 +220,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in Q_UNUSED(compId); Q_UNUSED(severity); - UASInterface* uas = _autopilot->vehicle()->uas(); - Q_ASSERT(uas); - if (uasId != uas->getUASID()) { + if (uasId != _vehicle->id()) { return; } @@ -306,9 +305,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in // Work out what the autopilot is configured to int sides = 0; - if (_vehicle->parameterExists(FactSystem::defaultComponentId, "CAL_MAG_SIDES")) { + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "CAL_MAG_SIDES")) { // Read the requested calibration directions off the system - sides = _vehicle->getParameterFact(FactSystem::defaultComponentId, "CAL_MAG_SIDES")->rawValue().toFloat(); + sides = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "CAL_MAG_SIDES")->rawValue().toFloat(); } else { // There is no valid setting, default to all six sides sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0); @@ -449,12 +448,12 @@ void SensorsComponentController::_refreshParams(void) // We ask for a refresh on these first so that the rotation combo show up as fast as possible fastRefreshList << "CAL_MAG0_ID" << "CAL_MAG1_ID" << "CAL_MAG2_ID" << "CAL_MAG0_ROT" << "CAL_MAG1_ROT" << "CAL_MAG2_ROT"; foreach (const QString ¶mName, fastRefreshList) { - _autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); + _vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, paramName); } // Now ask for all to refresh - _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_"); - _autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_"); + _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_"); + _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_"); } void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 3ada975e6..7e7759933 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -7,11 +7,11 @@ * ****************************************************************************/ - #include "FactPanelController.h" #include "MultiVehicleManager.h" #include "UAS.h" #include "QGCApplication.h" +#include "ParameterManager.h" #include @@ -104,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name bool noMissingFacts = true; foreach (const QString &name, names) { - if (_vehicle && !_vehicle->parameterExists(componentId, name)) { + if (_vehicle && !_vehicle->parameterManager()->parameterExists(componentId, name)) { _reportMissingParameter(componentId, name); noMissingFacts = false; } @@ -122,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void) Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing) { - if (_vehicle && _vehicle->parameterExists(componentId, name)) { - Fact* fact = _vehicle->getParameterFact(componentId, name); + if (_vehicle && _vehicle->parameterManager()->parameterExists(componentId, name)) { + Fact* fact = _vehicle->parameterManager()->getParameter(componentId, name); QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership); return fact; } else { @@ -135,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name bool FactPanelController::parameterExists(int componentId, const QString& name) { - return _vehicle ? _vehicle->parameterExists(componentId, name) : false; + return _vehicle ? _vehicle->parameterManager()->parameterExists(componentId, name) : false; } void FactPanelController::_showInternalError(const QString& errorMsg) diff --git a/src/FactSystem/FactSystemTestBase.cc b/src/FactSystem/FactSystemTestBase.cc index 991d043ef..41cb1195c 100644 --- a/src/FactSystem/FactSystemTestBase.cc +++ b/src/FactSystem/FactSystemTestBase.cc @@ -19,6 +19,7 @@ #include "MultiVehicleManager.h" #include "QGCApplication.h" #include "QGCQuickWidget.h" +#include "ParameterManager.h" #include @@ -46,8 +47,8 @@ void FactSystemTestBase::_cleanup(void) /// Basic test of parameter values in Fact System void FactSystemTestBase::_parameter_default_component_id_test(void) { - QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE")); - Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE"); + QVERIFY(_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")); + Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_THROTTLE"); QVERIFY(fact != NULL); QVariant factValue = fact->rawValue(); QCOMPARE(factValue.isValid(), true); @@ -57,8 +58,8 @@ void FactSystemTestBase::_parameter_default_component_id_test(void) void FactSystemTestBase::_parameter_specific_component_id_test(void) { - QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE")); - Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE"); + QVERIFY(_vehicle->parameterManager()->parameterExists(50, "RC_MAP_THROTTLE")); + Fact* fact = _vehicle->parameterManager()->getParameter(50, "RC_MAP_THROTTLE"); QVERIFY(fact != NULL); QVariant factValue = fact->rawValue(); QCOMPARE(factValue.isValid(), true); @@ -96,7 +97,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) // Change the value QVariant paramValue = 12; - qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue); + qgcApp()->toolbox()->multiVehicleManager()->activeVehicle()->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_THROTTLE")->setRawValue(paramValue); QTest::qWait(500); // Let the signals flow through diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 64e61cd9f..a7c45a39c 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -47,6 +47,7 @@ ParameterManager::ParameterManager(Vehicle* vehicle) , _vehicle(vehicle) , _mavlink(NULL) , _parametersReady(false) + , _missingParameters(false) , _initialLoadComplete(false) , _waitingForDefaultComponent(false) , _saveRequired(false) @@ -95,17 +96,17 @@ ParameterManager::~ParameterManager() } /// Called whenever a parameter is updated or first seen. -void ParameterManager::_parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value) +void ParameterManager::_parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value) { // Is this for our uas? - if (uasId != _vehicle->id()) { + if (vehicleId != _vehicle->id()) { return; } _initialRequestTimeoutTimer.stop(); if (_initialLoadComplete) { - qCDebug(ParameterManagerLog) << "_parameterUpdate (id:" << uasId << + qCDebug(ParameterManagerLog) << "_parameterUpdate (id:" << vehicleId << "componentId:" << componentId << "name:" << parameterName << "count:" << parameterCount << @@ -115,7 +116,7 @@ void ParameterManager::_parameterUpdate(int uasId, int componentId, QString para ")"; } else { // This is too noisy during initial load - qCDebug(ParameterManagerVerboseLog) << "_parameterUpdate (id:" << uasId << + qCDebug(ParameterManagerVerboseLog) << "_parameterUpdate (id:" << vehicleId << "componentId:" << componentId << "name:" << parameterName << "count:" << parameterCount << @@ -143,7 +144,7 @@ void ParameterManager::_parameterUpdate(int uasId, int componentId, QString para if (_vehicle->px4Firmware() && parameterName == "_HASH_CHECK") { /* we received a cache hash, potentially load from cache */ - _tryCacheHashLoad(uasId, componentId, value); + _tryCacheHashLoad(vehicleId, componentId, value); return; } _dataMutex.lock(); @@ -328,7 +329,7 @@ void ParameterManager::_parameterUpdate(int uasId, int componentId, QString para if (_vehicle->px4Firmware()) { if (_prevWaitingReadParamIndexCount + _prevWaitingReadParamNameCount != 0 && readWaitingParamCount == 0) { // All reads just finished, update the cache - _writeLocalParamCache(uasId, componentId); + _writeLocalParamCache(vehicleId, componentId); } } @@ -482,7 +483,7 @@ bool ParameterManager::parameterExists(int componentId, const QString& name) return ret; } -Fact* ParameterManager::getFact(int componentId, const QString& name) +Fact* ParameterManager::getParameter(int componentId, const QString& name) { componentId = _actualComponentId(componentId); @@ -571,7 +572,7 @@ void ParameterManager::_waitingParamTimeout(void) paramsRequested = true; _waitingWriteParamNameMap[componentId][paramName]++; // Bump retry count if (_waitingWriteParamNameMap[componentId][paramName] <= _maxReadWriteRetry) { - _writeParameterRaw(componentId, paramName, _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->rawValue()); + _writeParameterRaw(componentId, paramName, getParameter(componentId, paramName)->rawValue()); qCDebug(ParameterManagerLog) << "Write resend for (componentId:" << componentId << "paramName:" << paramName << "retryCount:" << _waitingWriteParamNameMap[componentId][paramName] << ")"; if (++batchCount > maxBatchSize) { goto Out; @@ -632,7 +633,7 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN mavlink_param_set_t p; mavlink_param_union_t union_value; - FactMetaData::ValueType_t factType = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName)->type(); + FactMetaData::ValueType_t factType = getParameter(componentId, paramName)->type(); p.param_type = _factTypeToMavType(factType); switch (factType) { @@ -680,7 +681,7 @@ void ParameterManager::_writeParameterRaw(int componentId, const QString& paramN _vehicle->sendMessageOnLink(_vehicle->priorityLink(), msg); } -void ParameterManager::_writeLocalParamCache(int uasId, int componentId) +void ParameterManager::_writeLocalParamCache(int vehicleId, int componentId) { MapID2NamedParam cache_map; @@ -690,7 +691,7 @@ void ParameterManager::_writeLocalParamCache(int uasId, int componentId) cache_map[id] = NamedParam(name, ParamTypeVal(fact->type(), fact->rawValue())); } - QFile cache_file(parameterCacheFile(uasId, componentId)); + QFile cache_file(parameterCacheFile(vehicleId, componentId)); cache_file.open(QIODevice::WriteOnly | QIODevice::Truncate); QDataStream ds(&cache_file); @@ -703,17 +704,17 @@ QDir ParameterManager::parameterCacheDir() return spath + QDir::separator() + "ParamCache"; } -QString ParameterManager::parameterCacheFile(int uasId, int componentId) +QString ParameterManager::parameterCacheFile(int vehicleId, int componentId) { - return parameterCacheDir().filePath(QString("%1_%2").arg(uasId).arg(componentId)); + return parameterCacheDir().filePath(QString("%1_%2").arg(vehicleId).arg(componentId)); } -void ParameterManager::_tryCacheHashLoad(int uasId, int componentId, QVariant hash_value) +void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value) { uint32_t crc32_value = 0; /* The datastructure of the cache table */ MapID2NamedParam cache_map; - QFile cache_file(parameterCacheFile(uasId, componentId)); + QFile cache_file(parameterCacheFile(vehicleId, componentId)); if (!cache_file.exists()) { /* no local cache, just wait for them to come in*/ return; @@ -743,7 +744,7 @@ void ParameterManager::_tryCacheHashLoad(int uasId, int componentId, QVariant ha const QVariant &value = cache_map[id].second.second; const FactMetaData::ValueType_t fact_type = static_cast(cache_map[id].second.first); const int mavType = _factTypeToMavType(fact_type); - _parameterUpdate(uasId, componentId, name, count, id, mavType, value); + _parameterUpdate(vehicleId, componentId, name, count, id, mavType, value); } // Return the hash value to notify we don't want any more updates mavlink_param_set_t p; @@ -814,7 +815,7 @@ QString ParameterManager::readParametersFromStream(QTextStream& stream) QString valStr = wpParams.at(3); uint mavType = wpParams.at(4).toUInt(); - if (!_vehicle->autopilotPlugin()->factExists(FactSystem::ParameterProvider, componentId, paramName)) { + if (!parameterExists(componentId, paramName)) { QString error; error = QString("Skipped parameter %1:%2 - does not exist on this vehicle\n").arg(componentId).arg(paramName); errors += error; @@ -822,7 +823,7 @@ QString ParameterManager::readParametersFromStream(QTextStream& stream) continue; } - Fact* fact = _vehicle->autopilotPlugin()->getFact(FactSystem::ParameterProvider, componentId, paramName); + Fact* fact = getParameter(componentId, paramName); if (fact->type() != _mavTypeToFactType((MAV_PARAM_TYPE)mavType)) { QString error; error = QString("Skipped parameter %1:%2 - type mismatch %3:%4\n").arg(componentId).arg(paramName).arg(fact->type()).arg(_mavTypeToFactType((MAV_PARAM_TYPE)mavType)); @@ -994,7 +995,10 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) qCDebug(ParameterManagerLog) << "Gave up on initial load after max retries (componentId:" << componentId << "paramIndex:" << paramIndex << ")"; } } + + _missingParameters = false; if (initialLoadFailures) { + _missingParameters = true; qgcApp()->showMessage("QGroundControl was unable to retrieve the full set of parameters from the vehicle. " "This will cause QGroundControl to be unable to display its full user interface. " "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. " @@ -1002,12 +1006,9 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) if (!qgcApp()->runningUnitTests()) { qCWarning(ParameterManagerLog) << "The following parameter indices could not be loaded after the maximum number of retries: " << indexList; } - emit parametersReady(true /* missingParameters */); - return; - } - - // Check for missing default component when we should have one - if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) { + } else if (_defaultComponentId == FactSystem::defaultComponentId && !_defaultComponentIdParam.isEmpty()) { + // Missing default component when we should have one + _missingParameters = true; qgcApp()->showMessage("QGroundControl did not receive parameters from the default component. " "This will cause QGroundControl to be unable to display its full user interface. " "If you are using modified firmware, you may need to resolve any vehicle startup errors to resolve the issue. " @@ -1015,14 +1016,14 @@ void ParameterManager::_checkInitialLoadComplete(bool failIfNoDefaultComponent) if (!qgcApp()->runningUnitTests()) { qCWarning(ParameterManagerLog) << "Default component was never found, param:" << _defaultComponentIdParam; } - emit parametersReady(true /* missingParameters */); - return; } - // No failures, signal good load + // Signal load complete _parametersReady = true; _determineDefaultComponentId(); - emit parametersReady(false /* no missingParameters */); + _vehicle->autopilotPlugin()->parametersReadyPreChecks(); + emit parametersReadyChanged(true); + emit missingParametersChanged(_missingParameters); } void ParameterManager::_initialRequestTimeout(void) @@ -1337,7 +1338,7 @@ void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSa } QJsonObject paramJson; - Fact* fact = getFact(compId, paramName); + Fact* fact = getParameter(compId, paramName); paramJson.insert(_jsonCompIdKey, QJsonValue(compId)); paramJson.insert(_jsonParamNameKey, QJsonValue(fact->name())); paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble())); @@ -1396,10 +1397,29 @@ bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QStr continue; } - Fact* fact = getFact(compId, name); + Fact* fact = getParameter(compId, name); fact->setRawValue(value); } return true; } +void ParameterManager::resetAllParametersToDefaults(void) +{ + mavlink_message_t msg; + MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol(); + + mavlink_msg_command_long_pack(mavlink->getSystemId(), + mavlink->getComponentId(), + &msg, + _vehicle->id(), // Target systeem + _vehicle->defaultComponentId(), // Target component + MAV_CMD_PREFLIGHT_STORAGE, + 0, // Confirmation + 2, // 2 = Reset params to default + -1, // -1 = No change to mission storage + 0, // 0 = Ignore + 0, 0, 0, 0); // Unused + _vehicle->sendMessageOnPriorityLink(msg); +} + diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index 1c182fc80..2f46da4b4 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -38,17 +38,22 @@ class ParameterManager : public QObject public: /// @param uas Uas which this set of facts is associated with ParameterManager(Vehicle* vehicle); - ~ParameterManager(); + /// true: Parameters are ready for use + Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) + bool parametersReady(void) { return _parametersReady; } + + /// true: Parameters are missing from firmware response, false: all parameters received from firmware + Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) + bool missingParameters(void) { return _missingParameters; } + /// @return Directory of parameter caches static QDir parameterCacheDir(); /// @return Location of parameter cache file - static QString parameterCacheFile(int uasId, int componentId); + static QString parameterCacheFile(int vehicleId, int componentId); - /// Returns true if the full set of facts are ready - bool parametersAreReady(void) { return _parametersReady; } /// Re-request the full set of parameters from the autopilot void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL); @@ -59,18 +64,21 @@ public: /// Request a refresh on all parameters that begin with the specified prefix void refreshParametersPrefix(int componentId, const QString& namePrefix); + void resetAllParametersToDefaults(void); + /// Returns true if the specifed parameter exists - bool parameterExists(int componentId, ///< fact component, -1=default component - const QString& name); ///< fact name - + /// @param componentId Component id or FactSystem::defaultComponentId + /// @param name Parameter name + bool parameterExists(int componentId, const QString& name); + /// Returns all parameter names QStringList parameterNames(int componentId); - /// Returns the specified Fact. - /// WARNING: Will assert if parameter does not exists. If that possibily exists, check for existence first with - /// parameterExists. - Fact* getFact(int componentId, ///< fact component, -1=default component - const QString& name); ///< fact name + /// Returns the specified Parameter. Returns a default empty fact is parameter does not exists. Also will pop + /// a missing parameter error to user if parameter does not exist. + /// @param componentId Component id or FactSystem::defaultComponentId + /// @param name Parameter name + Fact* getParameter(int componentId, const QString& name); const QMap >& getGroupMap(void); @@ -107,13 +115,15 @@ public: /// @return true: success, false: failure (errorString set) bool loadFromJson(const QJsonObject& json, bool required, QString& errorString); + Vehicle* vehicle(void) { return _vehicle; } + signals: - /// Signalled when the full set of facts are ready - void parametersReady(bool missingParameters); + void parametersReadyChanged(bool parametersReady); + void missingParametersChanged(bool missingParameters); /// Signalled to update progress of full parameter list request void parameterListProgress(float value); - + /// Signalled to ourselves in order to get call on our own thread void restartWaitingParamTimer(void); @@ -121,7 +131,7 @@ protected: Vehicle* _vehicle; MAVLinkProtocol* _mavlink; - void _parameterUpdate(int uasId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); + void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); void _valueUpdated(const QVariant& value); void _restartWaitingParamTimer(void); void _waitingParamTimeout(void); @@ -135,8 +145,8 @@ private: void _setupGroupMap(void); void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); - void _writeLocalParamCache(int uasId, int componentId); - void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value); + void _writeLocalParamCache(int vehicleId, int componentId); + void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value); void _addMetaDataToDefaultComponent(void); QString _remapParamNameToVersion(const QString& paramName); void _loadOfflineEditingParams(void); @@ -156,7 +166,8 @@ private: /// Second mapping is group name, to Fact QMap > _mapGroup2ParameterName; - bool _parametersReady; ///< true: full set of parameters correctly loaded + bool _parametersReady; ///< true: parameter load complete + bool _missingParameters; ///< true: parameter missing from initial load bool _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not bool _waitingForDefaultComponent; ///< true: last chance wait for default component params bool _saveRequired; ///< true: _saveToEEPROM should be called diff --git a/src/FactSystem/ParameterManagerTest.cc b/src/FactSystem/ParameterManagerTest.cc index 16f6b09c9..c47d8bed3 100644 --- a/src/FactSystem/ParameterManagerTest.cc +++ b/src/FactSystem/ParameterManagerTest.cc @@ -34,7 +34,7 @@ void ParameterManagerTest::_noFailureWorker(MockConfiguration::FailureMode_t fai QVERIFY(vehicle); // We should get progress bar updates during load - QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float))); + QSignalSpy spyProgress(vehicle->parameterManager(), SIGNAL(parameterListProgress(float))); QCOMPARE(spyProgress.wait(2000), true); arguments = spyProgress.takeFirst(); QCOMPARE(arguments.count(), 1); @@ -85,7 +85,7 @@ void ParameterManagerTest::_requestListNoResponse(void) QVERIFY(vehicle); QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); - QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float))); + QSignalSpy spyProgress(vehicle->parameterManager(), SIGNAL(parameterListProgress(float))); // We should not get any progress bar updates, nor a parameter ready signal QCOMPARE(spyProgress.wait(500), false); @@ -120,7 +120,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void) QVERIFY(vehicle); QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); - QSignalSpy spyProgress(vehicle->getParameterManager(), SIGNAL(parameterListProgress(float))); + QSignalSpy spyProgress(vehicle->parameterManager(), SIGNAL(parameterListProgress(float))); // We will get progress bar updates, since it will fail after getting partially through the request QCOMPARE(spyProgress.wait(2000), true); @@ -130,7 +130,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void) // We should get a parameters ready signal, but Vehicle should indicate missing params QCOMPARE(spyParamsReady.wait(40000), true); - QCOMPARE(vehicle->missingParameters(), true); + QCOMPARE(vehicle->parameterManager()->missingParameters(), true); // User should have been notified checkExpectedMessageBox(); diff --git a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc index 25e339fa9..3759459db 100644 --- a/src/FirmwarePlugin/APM/APMGeoFenceManager.cc +++ b/src/FirmwarePlugin/APM/APMGeoFenceManager.cc @@ -29,10 +29,10 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) , _fenceEnableFact(NULL) , _fenceTypeFact(NULL) { - connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); - connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &APMGeoFenceManager::_parametersReady); + connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); + connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMGeoFenceManager::_parametersReady); - if (_vehicle->getParameterManager()->parametersAreReady()) { + if (_vehicle->parameterManager()->parametersReady()) { _parametersReady(); } } @@ -75,13 +75,13 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const // First thing is to turn off geo fence while we are updating. This prevents the vehicle from going haywire it is in the air. // Unfortunately the param to do this with differs between plane and copter. const char* enableParam = _vehicle->fixedWing() ? _fenceActionParam : _fenceEnableParam; - Fact* fenceEnableFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, enableParam); + Fact* fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, enableParam); QVariant savedEnableState = fenceEnableFact->rawValue(); fenceEnableFact->setRawValue(0); // Total point count, +1 polygon close in last index, +1 for breach in index 0 _cWriteFencePoints = (validatedPolygonCount ? (validatedPolygonCount + 1) : 0) + 1 ; - _vehicle->getParameterFact(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints); + _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->setRawValue(_cWriteFencePoints); // FIXME: No validation of correct fence received for (uint8_t index=0; index<_cWriteFencePoints; index++) { @@ -108,7 +108,7 @@ void APMGeoFenceManager::loadFromVehicle(void) // Point 0: Breach return point (ArduPlane only) // Point [1,N]: Polygon points // Point N+1: Close polygon point (same as point 1) - int cFencePoints = _vehicle->getParameterFact(FactSystem::defaultComponentId, _fenceTotalParam)->rawValue().toInt(); + int cFencePoints = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _fenceTotalParam)->rawValue().toInt(); int minFencePoints = 6; qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints; if (cFencePoints == 0) { @@ -224,8 +224,8 @@ bool APMGeoFenceManager::_geoFenceSupported(void) return false; } - if (!_vehicle->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) || - !_vehicle->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) { + if (!_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) || + !_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) { return false; } else { return true; @@ -243,20 +243,20 @@ void APMGeoFenceManager::_parametersReady(void) if (!_firstParamLoadComplete) { _firstParamLoadComplete = true; - _fenceSupported = _vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION")); + _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION")); if (_fenceSupported) { QStringList paramNames; QStringList paramLabels; if (_vehicle->multiRotor()) { - _fenceEnableFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FENCE_ENABLE")); - _fenceTypeFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE")); + _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_ENABLE")); + _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE")); connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags); connect(_fenceTypeFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags); - _circleRadiusFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS")); + _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_RADIUS")); connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged); emit circleRadiusChanged(circleRadius()); @@ -275,8 +275,8 @@ void APMGeoFenceManager::_parametersReady(void) _paramLabels.clear(); for (int i=0; iparameterExists(FactSystem::defaultComponentId, paramName)) { - Fact* paramFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) { + Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName); _params << QVariant::fromValue(paramFact); _paramLabels << paramLabels[i]; } diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index c2c3dca03..d1420de92 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -14,6 +14,7 @@ #include "ArduCopterFirmwarePlugin.h" #include "QGCApplication.h" #include "MissionManager.h" +#include "ParameterManager.h" bool ArduCopterFirmwarePlugin::_remapParamNameIntialized = false; FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remapParamName; @@ -210,7 +211,7 @@ bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle) bool ArduCopterFirmwarePlugin::multiRotorXConfig(Vehicle* vehicle) { - return vehicle->getParameterFact(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0; + return vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "FRAME")->rawValue().toInt() != 0; } QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle) diff --git a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc index 683896e74..c7b2251ea 100644 --- a/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc +++ b/src/FirmwarePlugin/PX4/PX4GeoFenceManager.cc @@ -17,9 +17,9 @@ PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) , _firstParamLoadComplete(false) , _circleRadiusFact(NULL) { - connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &PX4GeoFenceManager::_parametersReady); + connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &PX4GeoFenceManager::_parametersReady); - if (_vehicle->getParameterManager()->parametersAreReady()) { + if (_vehicle->parameterManager()->parametersReady()) { _parametersReady(); } } @@ -34,7 +34,7 @@ void PX4GeoFenceManager::_parametersReady(void) if (!_firstParamLoadComplete) { _firstParamLoadComplete = true; - _circleRadiusFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST")); + _circleRadiusFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("GF_MAX_HOR_DIST")); connect(_circleRadiusFact, &Fact::rawValueChanged, this, &PX4GeoFenceManager::_circleRadiusRawValueChanged); emit circleRadiusChanged(circleRadius()); @@ -48,8 +48,8 @@ void PX4GeoFenceManager::_parametersReady(void) _paramLabels.clear(); for (int i=0; iparameterExists(FactSystem::defaultComponentId, paramName)) { - Fact* paramFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) { + Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName); _params << QVariant::fromValue(paramFact); _paramLabels << paramLabels[i]; } diff --git a/src/MissionManager/GeoFenceController.cc b/src/MissionManager/GeoFenceController.cc index de996ec47..5768e7642 100644 --- a/src/MissionManager/GeoFenceController.cc +++ b/src/MissionManager/GeoFenceController.cc @@ -128,7 +128,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr return false; } - if (!_activeVehicle->getParameterManager()->loadFromJson(json, false /* required */, errorString)) { + if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) { return false; } @@ -274,7 +274,7 @@ void GeoFenceController::saveToFile(const QString& filename) fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; QStringList paramNames; - ParameterManager* paramMgr = _activeVehicle->getParameterManager(); + ParameterManager* paramMgr = _activeVehicle->parameterManager(); GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager(); QVariantList params = fenceMgr->params(); @@ -322,21 +322,21 @@ void GeoFenceController::removeAll(void) void GeoFenceController::loadFromVehicle(void) { - if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) { _activeVehicle->geoFenceManager()->loadFromVehicle(); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress(); } } void GeoFenceController::sendToVehicle(void) { - if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) { setDirty(false); _polygon.setDirty(false); _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList()); } else { - qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->getParameterManager()->parametersAreReady() << syncInProgress(); + qCWarning(GeoFenceControllerLog) << "GeoFenceController::loadFromVehicle call at wrong time" << _activeVehicle->parameterManager()->parametersReady() << syncInProgress(); } } diff --git a/src/MissionManager/MissionController.cc b/src/MissionManager/MissionController.cc index 3e0f10797..a54abc2d3 100644 --- a/src/MissionManager/MissionController.cc +++ b/src/MissionManager/MissionController.cc @@ -1052,7 +1052,7 @@ void MissionController::_activeVehicleSet(void) connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); - if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { + if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) { // We are switching between two previously existing vehicles. We have to manually ask for the items from the Vehicle. // We don't request mission items for new vehicles since that will happen autamatically. loadFromVehicle(); diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc index aff3a4d23..a9a182763 100644 --- a/src/QGCApplication.cc +++ b/src/QGCApplication.cc @@ -95,6 +95,7 @@ #include "MissionCommandTree.h" #include "GeoFenceController.h" #include "QGCMapPolygon.h" +#include "ParameterManager.h" #ifndef __ios__ #include "SerialLink.h" @@ -379,10 +380,11 @@ void QGCApplication::_initCommon(void) qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); - qmlRegisterUncreatableType ("QGroundControl.FlightMap", 1, 0, "QGCMapPolygon", "Reference only"); + qmlRegisterUncreatableType ("QGroundControl.FlightMap", 1, 0, "QGCMapPolygon", "Reference only"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "ParameterEditorController"); qmlRegisterType ("QGroundControl.Controllers", 1, 0, "APMFlightModesComponentController"); diff --git a/src/QmlControls/ParameterEditorController.cc b/src/QmlControls/ParameterEditorController.cc index 9c7eda15f..16eafae33 100644 --- a/src/QmlControls/ParameterEditorController.cc +++ b/src/QmlControls/ParameterEditorController.cc @@ -29,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void) : _currentComponentId(_vehicle->defaultComponentId()) , _parameters(new QmlObjectListModel(this)) { - const QMap >& groupMap = _vehicle->getParameterManager()->getGroupMap(); + const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); foreach (int componentId, groupMap.keys()) { _componentIds += QString("%1").arg(componentId); } @@ -49,14 +49,14 @@ ParameterEditorController::~ParameterEditorController() QStringList ParameterEditorController::getGroupsForComponent(int componentId) { - const QMap >& groupMap = _vehicle->getParameterManager()->getGroupMap(); + const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); return groupMap[componentId].keys(); } QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group) { - const QMap >& groupMap = _vehicle->getParameterManager()->getGroupMap(); + const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); return groupMap[componentId][group]; } @@ -65,11 +65,11 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen { QStringList list; - foreach(const QString ¶mName, _autopilot->parameterNames(componentId)) { + foreach(const QString ¶mName, _vehicle->parameterManager()->parameterNames(componentId)) { if (searchText.isEmpty()) { list += paramName; } else { - Fact* fact = _vehicle->getParameterFact(componentId, paramName); + Fact* fact = _vehicle->parameterManager()->getParameter(componentId, paramName); if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { list += paramName; @@ -105,7 +105,7 @@ void ParameterEditorController::saveToFile(const QString& filename) } QTextStream stream(&file); - _autopilot->writeParametersToStream(stream); + _vehicle->parameterManager()->writeParametersToStream(stream); file.close(); } } @@ -141,7 +141,7 @@ void ParameterEditorController::loadFromFile(const QString& filename) } QTextStream stream(&file); - errors = _autopilot->readParametersFromStream(stream); + errors = _vehicle->parameterManager()->readParametersFromStream(stream); file.close(); if (!errors.isEmpty()) { @@ -163,12 +163,12 @@ void ParameterEditorController::loadFromFilePicker(void) void ParameterEditorController::refresh(void) { - _autopilot->refreshAllParameters(); + _vehicle->parameterManager()->refreshAllParameters(); } void ParameterEditorController::resetAllToDefaults(void) { - _autopilot->resetAllParametersToDefaults(); + _vehicle->parameterManager()->resetAllParametersToDefaults(); refresh(); } @@ -188,13 +188,13 @@ void ParameterEditorController::_updateParameters(void) QObjectList newParameterList; if (_searchText.isEmpty()) { - const QMap >& groupMap = _vehicle->getParameterManager()->getGroupMap(); + const QMap >& groupMap = _vehicle->parameterManager()->getGroupMap(); foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { - newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter)); + newParameterList.append(_vehicle->parameterManager()->getParameter(_currentComponentId, parameter)); } } else { - foreach(const QString ¶meter, _autopilot->parameterNames(_vehicle->defaultComponentId())) { - Fact* fact = _vehicle->getParameterFact(_vehicle->defaultComponentId(), parameter); + foreach(const QString ¶meter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) { + Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter); if (fact->name().contains(_searchText, Qt::CaseInsensitive) || fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) || fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) { diff --git a/src/Vehicle/MultiVehicleManager.cc b/src/Vehicle/MultiVehicleManager.cc index e2125b123..b87931117 100644 --- a/src/Vehicle/MultiVehicleManager.cc +++ b/src/Vehicle/MultiVehicleManager.cc @@ -14,6 +14,7 @@ #include "QGCApplication.h" #include "FollowMe.h" #include "QGroundControlQmlGlobal.h" +#include "ParameterManager.h" #ifdef __mobile__ #include "MobileScreenMgr.h" @@ -99,7 +100,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _autopilotPluginManager, _joystickManager); connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1); - connect(vehicle->autopilotPlugin(), &AutoPilotPlugin::parametersReadyChanged, this, &MultiVehicleManager::_autopilotParametersReadyChanged); + connect(vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &MultiVehicleManager::_vehicleParametersReadyChanged); _vehicles.append(vehicle); @@ -189,7 +190,7 @@ void MultiVehicleManager::_deleteVehiclePhase2(void) if (_activeVehicle) { _activeVehicle->setActive(true); emit activeVehicleAvailableChanged(true); - if (_activeVehicle->autopilotPlugin()->parametersReady()) { + if (_activeVehicle->parameterManager()->parametersReady()) { emit parameterReadyVehicleAvailableChanged(true); } } @@ -237,23 +238,23 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void) _activeVehicleAvailable = true; emit activeVehicleAvailableChanged(true); - if (_activeVehicle->autopilotPlugin()->parametersReady()) { + if (_activeVehicle->parameterManager()->parametersReady()) { _parameterReadyVehicleAvailable = true; emit parameterReadyVehicleAvailableChanged(true); } } } -void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady) +void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady) { - AutoPilotPlugin* autopilot = dynamic_cast(sender()); + ParameterManager* paramMgr = dynamic_cast(sender()); - if (!autopilot) { + if (!paramMgr) { qWarning() << "Dynamic cast failed!"; return; } - if (autopilot->vehicle() == _activeVehicle) { + if (paramMgr->vehicle() == _activeVehicle) { _parameterReadyVehicleAvailable = parametersReady; emit parameterReadyVehicleAvailableChanged(parametersReady); } diff --git a/src/Vehicle/MultiVehicleManager.h b/src/Vehicle/MultiVehicleManager.h index 99695421c..5c6a8e3ee 100644 --- a/src/Vehicle/MultiVehicleManager.h +++ b/src/Vehicle/MultiVehicleManager.h @@ -93,7 +93,7 @@ private slots: void _deleteVehiclePhase1(Vehicle* vehicle); void _deleteVehiclePhase2(void); void _setActiveVehiclePhase2(void); - void _autopilotParametersReadyChanged(bool parametersReady); + void _vehicleParametersReadyChanged(bool parametersReady); void _sendGCSHeartbeat(void); void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType); diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index f6abb0cc4..6b73fa551 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -101,7 +101,7 @@ Vehicle::Vehicle(LinkInterface* link, , _missionManagerInitialRequestComplete(false) , _geoFenceManager(NULL) , _geoFenceManagerInitialRequestComplete(false) - , _parameterLoader(NULL) + , _parameterManager(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) @@ -156,9 +156,6 @@ Vehicle::Vehicle(LinkInterface* link, _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this); - connect(_autopilotPlugin, &AutoPilotPlugin::parametersReadyChanged, this, &Vehicle::_parametersReady); - connect(_autopilotPlugin, &AutoPilotPlugin::missingParametersChanged, this, &Vehicle::missingParametersChanged); - // connect this vehicle to the follow me handle manager connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager); @@ -199,9 +196,8 @@ Vehicle::Vehicle(LinkInterface* link, connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable); - _parameterLoader = new ParameterManager(this); - connect(_parameterLoader, &ParameterManager::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks); - connect(_parameterLoader, &ParameterManager::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress); + _parameterManager = new ParameterManager(this); + connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); // GeoFenceManager needs to access ParameterManager so make sure to create after _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); @@ -295,7 +291,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, , _missionManagerInitialRequestComplete(false) , _geoFenceManager(NULL) , _geoFenceManagerInitialRequestComplete(false) - , _parameterLoader(NULL) + , _parameterManager(NULL) , _armed(false) , _base_mode(0) , _custom_mode(0) @@ -333,7 +329,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, _missionManager = new MissionManager(this); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); - _parameterLoader = new ParameterManager(this); + _parameterManager = new ParameterManager(this); // GeoFenceManager needs to access ParameterManager so make sure to create after _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); @@ -1299,11 +1295,6 @@ void Vehicle::setHilMode(bool hilMode) sendMessageOnPriorityLink(msg); } -bool Vehicle::missingParameters(void) -{ - return _autopilotPlugin->missingParameters(); -} - void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple) { mavlink_message_t msg; @@ -1814,7 +1805,7 @@ void Vehicle::rebootVehicle() int Vehicle::defaultComponentId(void) { - return _parameterLoader->defaultComponentId(); + return _parameterManager->defaultComponentId(); } void Vehicle::setSoloFirmware(bool soloFirmware) @@ -1833,20 +1824,6 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs) } #endif -/// Returns true if the specifed parameter exists from the default component -bool Vehicle::parameterExists(int componentId, const QString& name) const -{ - return getParameterManager()->parameterExists(componentId, name); -} - -/// Returns the specified parameter Fact from the default component -/// WARNING: Returns a default Fact if parameter does not exists. If that possibility exists, check for existence first with -/// parameterExists. -Fact* Vehicle::getParameterFact(int componentId, const QString& name) -{ - return getParameterManager()->getFact(componentId, name); -} - void Vehicle::_newMissionItemsAvailable(void) { // After the initial mission request complets we ask for the geofence diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 23129217e..c799557e0 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -235,7 +235,6 @@ public: Q_PROPERTY(QStringList flightModes READ flightModes CONSTANT) Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged) Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged) - Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) Q_PROPERTY(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT) Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged) Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) @@ -295,6 +294,8 @@ public: /// true: Orbit mode is supported by this vehicle Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) + Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT) + // FactGroup object model properties Q_PROPERTY(Fact* roll READ roll CONSTANT) @@ -491,8 +492,6 @@ public: /// @param sendMultiple Send multiple time to guarantee Vehicle reception void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true); - bool missingParameters(void); - typedef enum { MessageNone, MessageNormal, @@ -544,8 +543,8 @@ public: void setConnectionLostEnabled(bool connectionLostEnabled); - ParameterManager* getParameterManager(void) { return _parameterLoader; } - ParameterManager* getParameterManager(void) const { return _parameterLoader; } + ParameterManager* parameterManager(void) { return _parameterManager; } + ParameterManager* parameterManager(void) const { return _parameterManager; } static const int cMaxRcChannels = 18; @@ -574,14 +573,6 @@ public: /// @return true: X confiuration, false: Plus configuration bool xConfigMotors(void); - /// Returns true if the specifed parameter exists from the default component - bool parameterExists(int componentId, const QString& name) const; - - /// Returns the specified parameter Fact from the default component - /// WARNING: Returns a default Fact if parameter does not exists. If that possibility exists, check for existence first with - /// parameterExists. - Fact* getParameterFact(int componentId, const QString& name); - public slots: void setLatitude(double latitude); void setLongitude(double longitude); @@ -599,7 +590,6 @@ signals: void armedChanged(bool armed); void flightModeChanged(const QString& flightMode); void hilModeChanged(bool hilMode); - void missingParametersChanged(bool missingParameters); void connectionLostChanged(bool connectionLost); void connectionLostEnabledChanged(bool connectionLostEnabled); void autoDisconnectChanged(bool autoDisconnectChanged); @@ -763,7 +753,7 @@ private: GeoFenceManager* _geoFenceManager; bool _geoFenceManagerInitialRequestComplete; - ParameterManager* _parameterLoader; + ParameterManager* _parameterManager; bool _armed; ///< true: vehicle is armed uint8_t _base_mode; ///< base_mode from HEARTBEAT diff --git a/src/VehicleSetup/SetupView.qml b/src/VehicleSetup/SetupView.qml index ab73e720c..77b678179 100644 --- a/src/VehicleSetup/SetupView.qml +++ b/src/VehicleSetup/SetupView.qml @@ -39,7 +39,7 @@ Rectangle { readonly property string _armedVehicleText: qsTr("This operation cannot be performed while vehicle is armed.") property string _messagePanelText: "missing message panel text" - property bool _fullParameterVehicleAvailable: QGroundControl.multiVehicleManager.parameterReadyVehicleAvailable && !QGroundControl.multiVehicleManager.activeVehicle.missingParameters + property bool _fullParameterVehicleAvailable: QGroundControl.multiVehicleManager.parameterReadyVehicleAvailable && !QGroundControl.multiVehicleManager.activeVehicle.parameterManager.missingParameters function showSummaryPanel() { diff --git a/src/VehicleSetup/VehicleComponent.cc b/src/VehicleSetup/VehicleComponent.cc index b68aff9a3..3bfc3c3e5 100644 --- a/src/VehicleSetup/VehicleComponent.cc +++ b/src/VehicleSetup/VehicleComponent.cc @@ -13,6 +13,7 @@ #include "VehicleComponent.h" #include "AutoPilotPlugin.h" +#include "ParameterManager.h" VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : QObject(parent), @@ -49,8 +50,8 @@ void VehicleComponent::setupTriggerSignals(void) { // Watch for changed on trigger list params foreach (const QString ¶mName, setupCompleteChangedTriggerList()) { - if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) { - Fact* fact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); + if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) { + Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName); connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); } } diff --git a/src/qgcunittest/RadioConfigTest.cc b/src/qgcunittest/RadioConfigTest.cc index 6c2d40f8b..0d8f21c67 100644 --- a/src/qgcunittest/RadioConfigTest.cc +++ b/src/qgcunittest/RadioConfigTest.cc @@ -378,7 +378,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) switchList << "RC_MAP_MODE_SW" << "RC_MAP_LOITER_SW" << "RC_MAP_RETURN_SW" << "RC_MAP_POSCTL_SW" << "RC_MAP_ACRO_SW"; foreach (const QString &switchParam, switchList) { - Q_ASSERT(_vehicle->getParameterFact(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); + Q_ASSERT(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, switchParam)->rawValue().toInt() != channel + 1); } } @@ -393,7 +393,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) if (!found) { const char* paramName = _functionInfo()[function].parameterName; if (paramName) { - _rgFunctionChannelMap[function] = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); + _rgFunctionChannelMap[function] = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); qCDebug(RadioConfigTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function]; if (_rgFunctionChannelMap[function] == 0) { _rgFunctionChannelMap[function] = -1; // -1 signals no mapping @@ -469,8 +469,8 @@ void RadioConfigTest::_validateParameters(void) const char* paramName = _functionInfo()[chanFunction].parameterName; if (paramName) { - qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); - QCOMPARE(_vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue); + qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); + QCOMPARE(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue); } } @@ -485,13 +485,13 @@ void RadioConfigTest::_validateParameters(void) int rcTrimExpected = _channelSettingsValidate()[chan].rcTrim; bool rcReversedExpected = _channelSettingsValidate()[chan].reversed; - int rcMinActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); + int rcMinActual = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, minTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcMaxActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); + int rcMaxActual = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, maxTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - int rcTrimActual = _vehicle->getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); + int rcTrimActual = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, trimTpl.arg(oneBasedChannel))->rawValue().toInt(&convertOk); QCOMPARE(convertOk, true); - float rcReversedFloat = _vehicle->getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->rawValue().toFloat(&convertOk); + float rcReversedFloat = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel))->rawValue().toFloat(&convertOk); QCOMPARE(convertOk, true); bool rcReversedActual = (rcReversedFloat == -1.0f); @@ -515,7 +515,7 @@ void RadioConfigTest::_validateParameters(void) const char* paramName = _functionInfo()[chanFunction].parameterName; if (paramName) { // qCDebug(RadioConfigTestLog) << chanFunction << expectedValue << mapParamsSet[paramName].toInt(); - QCOMPARE(_vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedValue); + QCOMPARE(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedValue); } } } diff --git a/src/ui/QGCMapRCToParamDialog.cpp b/src/ui/QGCMapRCToParamDialog.cpp index 97fa8d03f..309681c8c 100644 --- a/src/ui/QGCMapRCToParamDialog.cpp +++ b/src/ui/QGCMapRCToParamDialog.cpp @@ -13,6 +13,7 @@ #include "QGCMapRCToParamDialog.h" #include "ui_QGCMapRCToParamDialog.h" +#include "ParameterManager.h" #include #include @@ -31,7 +32,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav // refresh the parameter from onboard to make sure the current value is used Vehicle* vehicle = _multiVehicleManager->getVehicleById(mav->getUASID()); - Fact* paramFact = vehicle->getParameterFact(FactSystem::defaultComponentId, param_id); + Fact* paramFact = vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, param_id); ui->minValueDoubleSpinBox->setValue(paramFact->rawMin().toDouble()); ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble()); @@ -43,7 +44,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ui->paramIdLabel->setText(param_id); connect(paramFact, &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated); - vehicle->autopilotPlugin()->refreshParameter(FactSystem::defaultComponentId, param_id); + vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, param_id); } QGCMapRCToParamDialog::~QGCMapRCToParamDialog() diff --git a/src/ui/toolbar/MainToolBarController.cc b/src/ui/toolbar/MainToolBarController.cc index 8059731e2..50a6d298c 100644 --- a/src/ui/toolbar/MainToolBarController.cc +++ b/src/ui/toolbar/MainToolBarController.cc @@ -24,6 +24,7 @@ #include "QGCApplication.h" #include "MultiVehicleManager.h" #include "UAS.h" +#include "ParameterManager.h" MainToolBarController::MainToolBarController(QObject* parent) : QObject(parent) @@ -47,7 +48,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) { // Disconnect the previous one (if any) if (_vehicle) { - disconnect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); + disconnect(_vehicle->parameterManager(), &ParameterManager::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); _mav = NULL; _vehicle = NULL; } @@ -57,7 +58,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) { _vehicle = vehicle; _mav = vehicle->uas(); - connect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); + connect(_vehicle->parameterManager(), &ParameterManager::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); } } -- 2.22.0