Commit e92110a7 authored by Don Gagne's avatar Don Gagne

Refactor parameter apis from AutoPilotPlugin to ParameterManager

parent f776d5e7
...@@ -66,7 +66,7 @@ linux { ...@@ -66,7 +66,7 @@ linux {
} else { } else {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6 QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
} }
QMAKE_MAC_SDK = macosx10.11 QMAKE_MAC_SDK = macosx10.12
QMAKE_CXXFLAGS += -fvisibility=hidden QMAKE_CXXFLAGS += -fvisibility=hidden
} else { } else {
error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported") error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported")
......
...@@ -7,12 +7,9 @@ ...@@ -7,12 +7,9 @@
* *
****************************************************************************/ ****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "ArduCopterFirmwarePlugin.h" #include "ArduCopterFirmwarePlugin.h"
#include "ParameterManager.h"
APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent) : VehicleComponent(vehicle, autopilot, parent)
...@@ -52,7 +49,7 @@ bool APMAirframeComponent::requiresSetup(void) const ...@@ -52,7 +49,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const bool APMAirframeComponent::setupComplete(void) const
{ {
if (_requiresFrameSetup) { if (_requiresFrameSetup) {
return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0; return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
} else { } else {
return true; return true;
} }
......
...@@ -18,6 +18,7 @@ ...@@ -18,6 +18,7 @@
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCFileDownload.h" #include "QGCFileDownload.h"
#include "ParameterManager.h"
#include <QVariant> #include <QVariant>
#include <QQmlProperty> #include <QQmlProperty>
...@@ -107,7 +108,7 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri ...@@ -107,7 +108,7 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri
} }
} }
qgcApp()->restoreOverrideCursor(); qgcApp()->restoreOverrideCursor();
_autopilot->refreshAllParameters(); _vehicle->parameterManager()->refreshAllParameters();
} }
APMAirframeType::APMAirframeType(const QString& name, const QString& imageResource, int type, QObject* parent) : APMAirframeType::APMAirframeType(const QString& name, const QString& imageResource, int type, QObject* parent) :
......
...@@ -59,9 +59,7 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin() ...@@ -59,9 +59,7 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin()
const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
{ {
if (_components.count() == 0 && !_incorrectParameterVersion) { if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_vehicle); if (_vehicle->parameterManager()->parametersReady()) {
if (parametersReady()) {
_airframeComponent = new APMAirframeComponent(_vehicle, this); _airframeComponent = new APMAirframeComponent(_vehicle, this);
_airframeComponent->setupTriggerSignals(); _airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
...@@ -107,7 +105,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -107,7 +105,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent));
//-- Is there an ESP8266 Connected? //-- 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 = new ESP8266Component(_vehicle, this);
_esp8266Component->setupTriggerSignals(); _esp8266Component->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component));
...@@ -119,25 +117,3 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void) ...@@ -119,25 +117,3 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
return _components; 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);
}
...@@ -52,10 +52,6 @@ public: ...@@ -52,10 +52,6 @@ public:
APMTuningComponent* tuningComponent (void) const { return _tuningComponent; } APMTuningComponent* tuningComponent (void) const { return _tuningComponent; }
ESP8266Component* esp8266Component (void) const { return _esp8266Component; } ESP8266Component* esp8266Component (void) const { return _esp8266Component; }
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
private: private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
QVariantList _components; QVariantList _components;
......
...@@ -10,6 +10,7 @@ ...@@ -10,6 +10,7 @@
#include "APMCompassCal.h" #include "APMCompassCal.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "ParameterManager.h"
QGC_LOGGING_CATEGORY(APMCompassCalLog, "APMCompassCalLog") QGC_LOGGING_CATEGORY(APMCompassCalLog, "APMCompassCalLog")
...@@ -613,11 +614,11 @@ void APMCompassCal::startCalibration(void) ...@@ -613,11 +614,11 @@ void APMCompassCal::startCalibration(void)
_calWorkerThread->rgCompassAvailable[i] = true; _calWorkerThread->rgCompassAvailable[i] = true;
const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3]; const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3];
if (_vehicle->parameterExists(-1, deviceIdParam)) { if (_vehicle->parameterManager()->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = _vehicle->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0; _calWorkerThread->rgCompassAvailable[i] = _vehicle->parameterManager()->getParameter(-1, deviceIdParam)->rawValue().toInt() > 0;
for (int j=0; j<3; j++) { for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][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(); _rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat();
paramFact->setRawValue(0.0); paramFact->setRawValue(0.0);
...@@ -639,8 +640,8 @@ void APMCompassCal::cancelCalibration(void) ...@@ -639,8 +640,8 @@ void APMCompassCal::cancelCalibration(void)
for (int i=0; i<3; i++) { for (int i=0; i<3; i++) {
for (int j=0; j<3; j++) { for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j]; const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
if (_vehicle->parameterExists(-1, offsetParam)) { if (_vehicle->parameterManager()->parameterExists(-1, offsetParam)) {
_vehicle->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]); _vehicle->parameterManager()->getParameter(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
} }
} }
} }
......
...@@ -11,6 +11,7 @@ ...@@ -11,6 +11,7 @@
#include "APMPowerComponent.h" #include "APMPowerComponent.h"
#include "APMAutoPilotPlugin.h" #include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMPowerComponent::APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) APMPowerComponent::APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent), : VehicleComponent(vehicle, autopilot, parent),
...@@ -40,7 +41,7 @@ bool APMPowerComponent::requiresSetup(void) const ...@@ -40,7 +41,7 @@ bool APMPowerComponent::requiresSetup(void) const
bool APMPowerComponent::setupComplete(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 QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -11,6 +11,7 @@ ...@@ -11,6 +11,7 @@
#include "APMRadioComponent.h" #include "APMRadioComponent.h"
#include "APMAutoPilotPlugin.h" #include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(vehicle, autopilot, parent), VehicleComponent(vehicle, autopilot, parent),
...@@ -19,7 +20,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo ...@@ -19,7 +20,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo
_mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE"); _mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE");
foreach (const QString& mapParam, _mapParams) { 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); connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
} }
...@@ -56,7 +57,7 @@ bool APMRadioComponent::setupComplete(void) const ...@@ -56,7 +57,7 @@ bool APMRadioComponent::setupComplete(void) const
// First check for all attitude controls mapped // First check for all attitude controls mapped
for (int i=0; i<_mapParams.count(); i++) { 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) { if (mapValues[i] <= 0) {
return false; return false;
} }
...@@ -64,14 +65,14 @@ bool APMRadioComponent::setupComplete(void) const ...@@ -64,14 +65,14 @@ bool APMRadioComponent::setupComplete(void) const
// Next check RC#_MIN/MAX/TRIM all at defaults // Next check RC#_MIN/MAX/TRIM all at defaults
foreach (const QString& mapParam, _mapParams) { foreach (const QString& mapParam, _mapParams) {
int channel = _vehicle->getParameterFact(-1, mapParam)->rawValue().toInt(); int channel = _vehicle->parameterManager()->getParameter(-1, mapParam)->rawValue().toInt();
if (_vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) { if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
return true; 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; 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; return true;
} }
} }
...@@ -116,17 +117,17 @@ void APMRadioComponent::_connectSetupTriggers(void) ...@@ -116,17 +117,17 @@ void APMRadioComponent::_connectSetupTriggers(void)
// Get the channels for attitude controls and connect to those values for triggers // Get the channels for attitude controls and connect to those values for triggers
foreach (const QString& mapParam, _mapParams) { 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); 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; _triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged); connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
} }
......
...@@ -12,6 +12,7 @@ ...@@ -12,6 +12,7 @@
#include "APMAutoPilotPlugin.h" #include "APMAutoPilotPlugin.h"
#include "APMSensorsComponentController.h" #include "APMSensorsComponentController.h"
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "ParameterManager.h"
// These two list must be kept in sync // These two list must be kept in sync
...@@ -62,7 +63,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const ...@@ -62,7 +63,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const
// Accelerometer triggers // Accelerometer triggers
triggers << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z"; 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_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
triggers << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z"); 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"); triggers << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z");
...@@ -108,10 +109,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const ...@@ -108,10 +109,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z"); rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z");
for (size_t i=0; i<cCompass; i++) { for (size_t i=0; i<cCompass; i++) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 && if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) { _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
for (size_t j=0; j<cOffset; j++) { for (size_t j=0; j<cOffset; j++) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) { if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgOffsets[i][j])->rawValue().toFloat() == 0.0f) {
return true; return true;
} }
} }
...@@ -133,7 +134,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const ...@@ -133,7 +134,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
rgOffsets.clear(); rgOffsets.clear();
// This parameter is not available in all firmware version. Specifically missing from older Solo firmware. // 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"); 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 // We have usage information for the remaining accels, so we can test them sa well
...@@ -147,9 +148,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const ...@@ -147,9 +148,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
} }
for (int i=0; i<rgAccels.count(); i++) { for (int i=0; i<rgAccels.count(); i++) {
if (rgUse.count() == 0 || _vehicle->getParameterFact(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; j<rgAccels[0].count(); j++) { for (int j=0; j<rgAccels[0].count(); j++) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) { if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgAccels[i][j])->rawValue().toFloat() == 0.0f) {
return true; return true;
} }
} }
......
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include "UAS.h" #include "UAS.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "APMAutoPilotPlugin.h" #include "APMAutoPilotPlugin.h"
#include "ParameterManager.h"
#include <QVariant> #include <QVariant>
#include <QQmlProperty> #include <QQmlProperty>
...@@ -214,9 +215,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId, ...@@ -214,9 +215,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
Q_UNUSED(compId); Q_UNUSED(compId);
Q_UNUSED(severity); Q_UNUSED(severity);
UASInterface* uas = _autopilot->vehicle()->uas(); if (uasId != _vehicle->id()) {
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
return; return;
} }
...@@ -428,12 +427,12 @@ void APMSensorsComponentController::_refreshParams(void) ...@@ -428,12 +427,12 @@ void APMSensorsComponentController::_refreshParams(void)
fastRefreshList << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") 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"); << QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
foreach (const QString &paramName, fastRefreshList) { foreach (const QString &paramName, fastRefreshList) {
_autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); _vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, paramName);
} }
// Now ask for all to refresh // Now ask for all to refresh
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_")); _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_")); _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
} }
void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
......
...@@ -11,6 +11,7 @@ ...@@ -11,6 +11,7 @@
#include "APMTuningComponent.h" #include "APMTuningComponent.h"
#include "APMAutoPilotPlugin.h" #include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h" #include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMTuningComponent::APMTuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) APMTuningComponent::APMTuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent) : VehicleComponent(vehicle, autopilot, parent)
...@@ -60,7 +61,7 @@ QUrl APMTuningComponent::setupSource(void) const ...@@ -60,7 +61,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_OCTOROTOR: case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER: case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares // 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"); qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
} }
break; break;
......
...@@ -21,15 +21,9 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent) ...@@ -21,15 +21,9 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: QObject(parent) : QObject(parent)
, _vehicle(vehicle) , _vehicle(vehicle)
, _firmwarePlugin(vehicle->firmwarePlugin()) , _firmwarePlugin(vehicle->firmwarePlugin())
, _parametersReady(false)
, _missingParameters(false)
, _setupComplete(false) , _setupComplete(false)
{ {
Q_ASSERT(vehicle);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(this, &AutoPilotPlugin::parametersReadyChanged, this, &AutoPilotPlugin::_parametersReadyChanged);
} }
AutoPilotPlugin::~AutoPilotPlugin() AutoPilotPlugin::~AutoPilotPlugin()
...@@ -37,26 +31,6 @@ 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) void AutoPilotPlugin::_recalcSetupComplete(void)
{ {
bool newSetupComplete = true; bool newSetupComplete = true;
...@@ -79,81 +53,17 @@ void AutoPilotPlugin::_recalcSetupComplete(void) ...@@ -79,81 +53,17 @@ void AutoPilotPlugin::_recalcSetupComplete(void)
bool AutoPilotPlugin::setupComplete(void) bool AutoPilotPlugin::setupComplete(void)
{ {
Q_ASSERT(_parametersReady);
return _setupComplete; return _setupComplete;
} }
void AutoPilotPlugin::resetAllParametersToDefaults(void) void AutoPilotPlugin::parametersReadyPreChecks(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)
{ {
_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
}
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 // Take the user to Vehicle Summary
qgcApp()->showSetupView();
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
} }
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);
} }
...@@ -38,68 +38,24 @@ public: ...@@ -38,68 +38,24 @@ public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent); AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin(); ~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 /// List of VehicleComponent objects
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT) Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
/// false: One or more vehicle components require setup /// false: One or more vehicle components require setup
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged) Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
/// Reset all parameters to their default values /// Called when parameters are ready for the first time. Note that parameters may still be missing.
Q_INVOKABLE void resetAllParametersToDefaults(void); /// Overrides must call base class.
virtual void parametersReadyPreChecks(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
// Must be implemented by derived class // Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0; virtual const QVariantList& vehicleComponents(void) = 0;
// Property accessors // Property accessors
bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; }
bool setupComplete(void); bool setupComplete(void);
Vehicle* vehicle(void) { return _vehicle; }
virtual void _parametersReadyPreChecks(bool parametersReady) = 0;
signals: signals:
void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete); void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
protected: protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
...@@ -107,15 +63,8 @@ protected: ...@@ -107,15 +63,8 @@ protected:
Vehicle* _vehicle; Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin; FirmwarePlugin* _firmwarePlugin;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete; bool _setupComplete;
private slots:
void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady);
private: private:
void _recalcSetupComplete(void); void _recalcSetupComplete(void);
}; };
......
...@@ -16,6 +16,7 @@ ...@@ -16,6 +16,7 @@
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "UAS.h" #include "UAS.h"
#include "ParameterManager.h"
#include <QHostAddress> #include <QHostAddress>
#include <QtEndian> #include <QtEndian>
...@@ -393,7 +394,7 @@ ESP8266ComponentController::_commandAck(uint8_t compID, uint16_t command, uint8_ ...@@ -393,7 +394,7 @@ ESP8266ComponentController::_commandAck(uint8_t compID, uint16_t command, uint8_
emit busyChanged(); emit busyChanged();
qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command; qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command;
if(command == MAV_CMD_PREFLIGHT_STORAGE) { if(command == MAV_CMD_PREFLIGHT_STORAGE) {
_autopilot->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE); _vehicle->parameterManager()->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE);
} }
} }
} }
......
...@@ -25,12 +25,3 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void) ...@@ -25,12 +25,3 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void)
return emptyList; 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);
}
...@@ -27,10 +27,6 @@ public: ...@@ -27,10 +27,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
}; };
#endif #endif
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include "AirframeComponent.h" #include "AirframeComponent.h"
#include "QGCQmlWidgetHolder.h" #include "QGCQmlWidgetHolder.h"
#include "ParameterManager.h"
#if 0 #if 0
// Broken by latest mavlink module changes. Not used yet. Comment out for now. // Broken by latest mavlink module changes. Not used yet. Comment out for now.
...@@ -129,7 +130,7 @@ bool AirframeComponent::requiresSetup(void) const ...@@ -129,7 +130,7 @@ bool AirframeComponent::requiresSetup(void) const
bool AirframeComponent::setupComplete(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 QStringList AirframeComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const ...@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const
bool FlightModesComponent::requiresSetup(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 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; return true;
} }
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 || if (_vehicle->parameterManager()->getParameter(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)) { (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
return true; return true;
} }
...@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const ...@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const
QString FlightModesComponent::prerequisiteSetup(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 // No RC input
return QString(); return QString();
} else { } else {
...@@ -92,7 +92,7 @@ QString FlightModesComponent::prerequisiteSetup(void) const ...@@ -92,7 +92,7 @@ QString FlightModesComponent::prerequisiteSetup(void) const
return plugin->airframeComponent()->name(); return plugin->airframeComponent()->name();
} else if (!plugin->radioComponent()->setupComplete()) { } else if (!plugin->radioComponent()->setupComplete()) {
return plugin->radioComponent()->name(); return plugin->radioComponent()->name();
} else if (!plugin->vehicle()->hilMode() && !plugin->sensorsComponent()->setupComplete()) { } else if (!_vehicle->hilMode() && !plugin->sensorsComponent()->setupComplete()) {
return plugin->sensorsComponent()->name(); return plugin->sensorsComponent()->name();
} }
} }
......
...@@ -52,7 +52,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) ...@@ -52,7 +52,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
if (_components.count() == 0 && !_incorrectParameterVersion) { if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_vehicle); Q_ASSERT(_vehicle);
if (parametersReady()) { if (_vehicle->parameterManager()->parametersReady()) {
_airframeComponent = new AirframeComponent(_vehicle, this); _airframeComponent = new AirframeComponent(_vehicle, this);
_airframeComponent->setupTriggerSignals(); _airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
...@@ -91,14 +91,14 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) ...@@ -91,14 +91,14 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent));
//-- Is there support for cameras? //-- 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 = new CameraComponent(_vehicle, this);
_cameraComponent->setupTriggerSignals(); _cameraComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent)); _components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent));
} }
//-- Is there an ESP8266 Connected? //-- 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 = new ESP8266Component(_vehicle, this);
_esp8266Component->setupTriggerSignals(); _esp8266Component->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component)); _components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component));
...@@ -111,21 +111,18 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void) ...@@ -111,21 +111,18 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
return _components; return _components;
} }
/// This will perform various checks prior to signalling that the plug in ready void PX4AutoPilotPlugin::parametersReadyPreChecks(void)
void PX4AutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{ {
// Base class must be called
AutoPilotPlugin::parametersReadyPreChecks();
// Check for older parameter version set // Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp // FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
// should be used instead. // should be used instead.
if (_vehicle->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") || if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF") ||
_vehicle->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) { _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "COM_DL_LOSS_EN")) {
_incorrectParameterVersion = true; _incorrectParameterVersion = true;
qgcApp()->showMessage("This version of GroundControl can only perform vehicle setup on a newer version of firmware. " 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."); "Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
} }
_parametersReady = true;
_missingParameters = missingParameters;
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
} }
...@@ -40,7 +40,8 @@ public: ...@@ -40,7 +40,8 @@ public:
~PX4AutoPilotPlugin(); ~PX4AutoPilotPlugin();
// Overrides from AutoPilotPlugin // 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 // These methods should only be used by objects within the plugin
AirframeComponent* airframeComponent(void) { return _airframeComponent; } AirframeComponent* airframeComponent(void) { return _airframeComponent; }
...@@ -54,10 +55,6 @@ public: ...@@ -54,10 +55,6 @@ public:
MotorComponent* motorComponent(void) { return _motorComponent; } MotorComponent* motorComponent(void) { return _motorComponent; }
PX4TuningComponent* tuningComponent(void) { return _tuningComponent; } PX4TuningComponent* tuningComponent(void) { return _tuningComponent; }
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
private: private:
PX4AirframeLoader* _airframeFacts; PX4AirframeLoader* _airframeFacts;
QVariantList _components; QVariantList _components;
......
...@@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const ...@@ -35,18 +35,18 @@ QString PX4RadioComponent::iconResource(void) const
bool PX4RadioComponent::requiresSetup(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 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 // The best we can do to detect the need for a radio calibration is look for attitude
// controls to be mapped. // controls to be mapped.
QStringList attitudeMappings; QStringList attitudeMappings;
attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE"; attitudeMappings << "RC_MAP_ROLL" << "RC_MAP_PITCH" << "RC_MAP_YAW" << "RC_MAP_THROTTLE";
foreach(const QString &mapParam, attitudeMappings) { 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; return false;
} }
} }
...@@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const ...@@ -76,7 +76,7 @@ QUrl PX4RadioComponent::summaryQmlSource(void) const
QString PX4RadioComponent::prerequisiteSetup(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<PX4AutoPilotPlugin*>(_autopilot); PX4AutoPilotPlugin* plugin = dynamic_cast<PX4AutoPilotPlugin*>(_autopilot);
if (!plugin->airframeComponent()->setupComplete()) { if (!plugin->airframeComponent()->setupComplete()) {
......
...@@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const ...@@ -44,9 +44,9 @@ bool PowerComponent::requiresSetup(void) const
bool PowerComponent::setupComplete(void) const bool PowerComponent::setupComplete(void) const
{ {
QVariant cvalue, evalue, nvalue; QVariant cvalue, evalue, nvalue;
return _vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f && return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_CHARGED")->rawValue().toFloat() != 0.0f &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_V_EMPTY")->rawValue().toFloat() != 0.0f &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0; _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "BAT_N_CELLS")->rawValue().toInt() != 0;
} }
QStringList PowerComponent::setupCompleteChangedTriggerList(void) const QStringList PowerComponent::setupCompleteChangedTriggerList(void) const
......
...@@ -58,9 +58,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int ...@@ -58,9 +58,7 @@ void PowerComponentController::_handleUASTextMessage(int uasId, int compId, int
Q_UNUSED(compId); Q_UNUSED(compId);
Q_UNUSED(severity); Q_UNUSED(severity);
UASInterface* uas = _autopilot->vehicle()->uas(); if (uasId != _vehicle->id()) {
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
return; return;
} }
......
...@@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const ...@@ -49,14 +49,14 @@ bool SensorsComponent::requiresSetup(void) const
bool SensorsComponent::setupComplete(void) const bool SensorsComponent::setupComplete(void) const
{ {
foreach (const QString &triggerParam, _deviceIds) { 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; return false;
} }
} }
if (_vehicle->fixedWing() || _vehicle->vtol()) { if (_vehicle->fixedWing() || _vehicle->vtol()) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) { if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedBreaker)->rawValue().toInt() != 162128) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) { if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _airspeedCal)->rawValue().toFloat() == 0.0f) {
return false; return false;
} }
} }
......
...@@ -15,6 +15,7 @@ ...@@ -15,6 +15,7 @@
#include "QGCMAVLink.h" #include "QGCMAVLink.h"
#include "UAS.h" #include "UAS.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterManager.h"
#include <QVariant> #include <QVariant>
#include <QQmlProperty> #include <QQmlProperty>
...@@ -219,9 +220,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in ...@@ -219,9 +220,7 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
Q_UNUSED(compId); Q_UNUSED(compId);
Q_UNUSED(severity); Q_UNUSED(severity);
UASInterface* uas = _autopilot->vehicle()->uas(); if (uasId != _vehicle->id()) {
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
return; return;
} }
...@@ -306,9 +305,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in ...@@ -306,9 +305,9 @@ void SensorsComponentController::_handleUASTextMessage(int uasId, int compId, in
// Work out what the autopilot is configured to // Work out what the autopilot is configured to
int sides = 0; 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 // 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 { } else {
// There is no valid setting, default to all six sides // There is no valid setting, default to all six sides
sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0); sides = (1 << 5) | (1 << 4) | (1 << 3) | (1 << 2) | (1 << 1) | (1 << 0);
...@@ -449,12 +448,12 @@ void SensorsComponentController::_refreshParams(void) ...@@ -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 // 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"; fastRefreshList << "CAL_MAG0_ID" << "CAL_MAG1_ID" << "CAL_MAG2_ID" << "CAL_MAG0_ROT" << "CAL_MAG1_ROT" << "CAL_MAG2_ROT";
foreach (const QString &paramName, fastRefreshList) { foreach (const QString &paramName, fastRefreshList) {
_autopilot->refreshParameter(FactSystem::defaultComponentId, paramName); _vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, paramName);
} }
// Now ask for all to refresh // Now ask for all to refresh
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_"); _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, "CAL_");
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_"); _vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, "SENS_");
} }
void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show) void SensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
......
...@@ -7,11 +7,11 @@ ...@@ -7,11 +7,11 @@
* *
****************************************************************************/ ****************************************************************************/
#include "FactPanelController.h" #include "FactPanelController.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "UAS.h" #include "UAS.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "ParameterManager.h"
#include <QQmlEngine> #include <QQmlEngine>
...@@ -104,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name ...@@ -104,7 +104,7 @@ bool FactPanelController::_allParametersExists(int componentId, QStringList name
bool noMissingFacts = true; bool noMissingFacts = true;
foreach (const QString &name, names) { foreach (const QString &name, names) {
if (_vehicle && !_vehicle->parameterExists(componentId, name)) { if (_vehicle && !_vehicle->parameterManager()->parameterExists(componentId, name)) {
_reportMissingParameter(componentId, name); _reportMissingParameter(componentId, name);
noMissingFacts = false; noMissingFacts = false;
} }
...@@ -122,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void) ...@@ -122,8 +122,8 @@ void FactPanelController::_checkForMissingFactPanel(void)
Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing) Fact* FactPanelController::getParameterFact(int componentId, const QString& name, bool reportMissing)
{ {
if (_vehicle && _vehicle->parameterExists(componentId, name)) { if (_vehicle && _vehicle->parameterManager()->parameterExists(componentId, name)) {
Fact* fact = _vehicle->getParameterFact(componentId, name); Fact* fact = _vehicle->parameterManager()->getParameter(componentId, name);
QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership); QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership);
return fact; return fact;
} else { } else {
...@@ -135,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name ...@@ -135,7 +135,7 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name
bool FactPanelController::parameterExists(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) void FactPanelController::_showInternalError(const QString& errorMsg)
......
...@@ -19,6 +19,7 @@ ...@@ -19,6 +19,7 @@
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "QGCQuickWidget.h" #include "QGCQuickWidget.h"
#include "ParameterManager.h"
#include <QQuickItem> #include <QQuickItem>
...@@ -46,8 +47,8 @@ void FactSystemTestBase::_cleanup(void) ...@@ -46,8 +47,8 @@ void FactSystemTestBase::_cleanup(void)
/// Basic test of parameter values in Fact System /// Basic test of parameter values in Fact System
void FactSystemTestBase::_parameter_default_component_id_test(void) void FactSystemTestBase::_parameter_default_component_id_test(void)
{ {
QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE")); QVERIFY(_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_THROTTLE"));
Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, FactSystem::defaultComponentId, "RC_MAP_THROTTLE"); Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL); QVERIFY(fact != NULL);
QVariant factValue = fact->rawValue(); QVariant factValue = fact->rawValue();
QCOMPARE(factValue.isValid(), true); QCOMPARE(factValue.isValid(), true);
...@@ -57,8 +58,8 @@ void FactSystemTestBase::_parameter_default_component_id_test(void) ...@@ -57,8 +58,8 @@ void FactSystemTestBase::_parameter_default_component_id_test(void)
void FactSystemTestBase::_parameter_specific_component_id_test(void) void FactSystemTestBase::_parameter_specific_component_id_test(void)
{ {
QVERIFY(_plugin->factExists(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE")); QVERIFY(_vehicle->parameterManager()->parameterExists(50, "RC_MAP_THROTTLE"));
Fact* fact = _plugin->getFact(FactSystem::ParameterProvider, 50, "RC_MAP_THROTTLE"); Fact* fact = _vehicle->parameterManager()->getParameter(50, "RC_MAP_THROTTLE");
QVERIFY(fact != NULL); QVERIFY(fact != NULL);
QVariant factValue = fact->rawValue(); QVariant factValue = fact->rawValue();
QCOMPARE(factValue.isValid(), true); QCOMPARE(factValue.isValid(), true);
...@@ -96,7 +97,7 @@ void FactSystemTestBase::_qmlUpdate_test(void) ...@@ -96,7 +97,7 @@ void FactSystemTestBase::_qmlUpdate_test(void)
// Change the value // Change the value
QVariant paramValue = 12; 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 QTest::qWait(500); // Let the signals flow through
......
This diff is collapsed.
...@@ -38,17 +38,22 @@ class ParameterManager : public QObject ...@@ -38,17 +38,22 @@ class ParameterManager : public QObject
public: public:
/// @param uas Uas which this set of facts is associated with /// @param uas Uas which this set of facts is associated with
ParameterManager(Vehicle* vehicle); ParameterManager(Vehicle* vehicle);
~ParameterManager(); ~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 /// @return Directory of parameter caches
static QDir parameterCacheDir(); static QDir parameterCacheDir();
/// @return Location of parameter cache file /// @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 /// Re-request the full set of parameters from the autopilot
void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL); void refreshAllParameters(uint8_t componentID = MAV_COMP_ID_ALL);
...@@ -59,18 +64,21 @@ public: ...@@ -59,18 +64,21 @@ public:
/// Request a refresh on all parameters that begin with the specified prefix /// Request a refresh on all parameters that begin with the specified prefix
void refreshParametersPrefix(int componentId, const QString& namePrefix); void refreshParametersPrefix(int componentId, const QString& namePrefix);
void resetAllParametersToDefaults(void);
/// Returns true if the specifed parameter exists /// Returns true if the specifed parameter exists
bool parameterExists(int componentId, ///< fact component, -1=default component /// @param componentId Component id or FactSystem::defaultComponentId
const QString& name); ///< fact name /// @param name Parameter name
bool parameterExists(int componentId, const QString& name);
/// Returns all parameter names /// Returns all parameter names
QStringList parameterNames(int componentId); QStringList parameterNames(int componentId);
/// Returns the specified Fact. /// Returns the specified Parameter. Returns a default empty fact is parameter does not exists. Also will pop
/// WARNING: Will assert if parameter does not exists. If that possibily exists, check for existence first with /// a missing parameter error to user if parameter does not exist.
/// parameterExists. /// @param componentId Component id or FactSystem::defaultComponentId
Fact* getFact(int componentId, ///< fact component, -1=default component /// @param name Parameter name
const QString& name); ///< fact name Fact* getParameter(int componentId, const QString& name);
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void); const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
...@@ -107,9 +115,11 @@ public: ...@@ -107,9 +115,11 @@ public:
/// @return true: success, false: failure (errorString set) /// @return true: success, false: failure (errorString set)
bool loadFromJson(const QJsonObject& json, bool required, QString& errorString); bool loadFromJson(const QJsonObject& json, bool required, QString& errorString);
Vehicle* vehicle(void) { return _vehicle; }
signals: signals:
/// Signalled when the full set of facts are ready void parametersReadyChanged(bool parametersReady);
void parametersReady(bool missingParameters); void missingParametersChanged(bool missingParameters);
/// Signalled to update progress of full parameter list request /// Signalled to update progress of full parameter list request
void parameterListProgress(float value); void parameterListProgress(float value);
...@@ -121,7 +131,7 @@ protected: ...@@ -121,7 +131,7 @@ protected:
Vehicle* _vehicle; Vehicle* _vehicle;
MAVLinkProtocol* _mavlink; 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 _valueUpdated(const QVariant& value);
void _restartWaitingParamTimer(void); void _restartWaitingParamTimer(void);
void _waitingParamTimeout(void); void _waitingParamTimeout(void);
...@@ -135,8 +145,8 @@ private: ...@@ -135,8 +145,8 @@ private:
void _setupGroupMap(void); void _setupGroupMap(void);
void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); void _readParameterRaw(int componentId, const QString& paramName, int paramIndex);
void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value);
void _writeLocalParamCache(int uasId, int componentId); void _writeLocalParamCache(int vehicleId, int componentId);
void _tryCacheHashLoad(int uasId, int componentId, QVariant hash_value); void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value);
void _addMetaDataToDefaultComponent(void); void _addMetaDataToDefaultComponent(void);
QString _remapParamNameToVersion(const QString& paramName); QString _remapParamNameToVersion(const QString& paramName);
void _loadOfflineEditingParams(void); void _loadOfflineEditingParams(void);
...@@ -156,7 +166,8 @@ private: ...@@ -156,7 +166,8 @@ private:
/// Second mapping is group name, to Fact /// Second mapping is group name, to Fact
QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName; QMap<int, QMap<QString, QStringList> > _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 _initialLoadComplete; ///< true: Initial load of all parameters complete, whether successful or not
bool _waitingForDefaultComponent; ///< true: last chance wait for default component params bool _waitingForDefaultComponent; ///< true: last chance wait for default component params
bool _saveRequired; ///< true: _saveToEEPROM should be called bool _saveRequired; ///< true: _saveToEEPROM should be called
......
...@@ -34,7 +34,7 @@ void ParameterManagerTest::_noFailureWorker(MockConfiguration::FailureMode_t fai ...@@ -34,7 +34,7 @@ void ParameterManagerTest::_noFailureWorker(MockConfiguration::FailureMode_t fai
QVERIFY(vehicle); QVERIFY(vehicle);
// We should get progress bar updates during load // 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); QCOMPARE(spyProgress.wait(2000), true);
arguments = spyProgress.takeFirst(); arguments = spyProgress.takeFirst();
QCOMPARE(arguments.count(), 1); QCOMPARE(arguments.count(), 1);
...@@ -85,7 +85,7 @@ void ParameterManagerTest::_requestListNoResponse(void) ...@@ -85,7 +85,7 @@ void ParameterManagerTest::_requestListNoResponse(void)
QVERIFY(vehicle); QVERIFY(vehicle);
QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); 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 // We should not get any progress bar updates, nor a parameter ready signal
QCOMPARE(spyProgress.wait(500), false); QCOMPARE(spyProgress.wait(500), false);
...@@ -120,7 +120,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void) ...@@ -120,7 +120,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void)
QVERIFY(vehicle); QVERIFY(vehicle);
QSignalSpy spyParamsReady(vehicleMgr, SIGNAL(parameterReadyVehicleAvailableChanged(bool))); 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 // We will get progress bar updates, since it will fail after getting partially through the request
QCOMPARE(spyProgress.wait(2000), true); QCOMPARE(spyProgress.wait(2000), true);
...@@ -130,7 +130,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void) ...@@ -130,7 +130,7 @@ void ParameterManagerTest::_requestListMissingParamFail(void)
// We should get a parameters ready signal, but Vehicle should indicate missing params // We should get a parameters ready signal, but Vehicle should indicate missing params
QCOMPARE(spyParamsReady.wait(40000), true); QCOMPARE(spyParamsReady.wait(40000), true);
QCOMPARE(vehicle->missingParameters(), true); QCOMPARE(vehicle->parameterManager()->missingParameters(), true);
// User should have been notified // User should have been notified
checkExpectedMessageBox(); checkExpectedMessageBox();
......
...@@ -30,9 +30,9 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle) ...@@ -30,9 +30,9 @@ APMGeoFenceManager::APMGeoFenceManager(Vehicle* vehicle)
, _fenceTypeFact(NULL) , _fenceTypeFact(NULL)
{ {
connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived); connect(_vehicle, &Vehicle::mavlinkMessageReceived, this, &APMGeoFenceManager::_mavlinkMessageReceived);
connect(_vehicle->getParameterManager(), &ParameterManager::parametersReady, this, &APMGeoFenceManager::_parametersReady); connect(_vehicle->parameterManager(), &ParameterManager::parametersReadyChanged, this, &APMGeoFenceManager::_parametersReady);
if (_vehicle->getParameterManager()->parametersAreReady()) { if (_vehicle->parameterManager()->parametersReady()) {
_parametersReady(); _parametersReady();
} }
} }
...@@ -75,13 +75,13 @@ void APMGeoFenceManager::sendToVehicle(const QGeoCoordinate& breachReturn, const ...@@ -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. // 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. // Unfortunately the param to do this with differs between plane and copter.
const char* enableParam = _vehicle->fixedWing() ? _fenceActionParam : _fenceEnableParam; 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(); QVariant savedEnableState = fenceEnableFact->rawValue();
fenceEnableFact->setRawValue(0); fenceEnableFact->setRawValue(0);
// Total point count, +1 polygon close in last index, +1 for breach in index 0 // Total point count, +1 polygon close in last index, +1 for breach in index 0
_cWriteFencePoints = (validatedPolygonCount ? (validatedPolygonCount + 1) : 0) + 1 ; _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 // FIXME: No validation of correct fence received
for (uint8_t index=0; index<_cWriteFencePoints; index++) { for (uint8_t index=0; index<_cWriteFencePoints; index++) {
...@@ -108,7 +108,7 @@ void APMGeoFenceManager::loadFromVehicle(void) ...@@ -108,7 +108,7 @@ void APMGeoFenceManager::loadFromVehicle(void)
// Point 0: Breach return point (ArduPlane only) // Point 0: Breach return point (ArduPlane only)
// Point [1,N]: Polygon points // Point [1,N]: Polygon points
// Point N+1: Close polygon point (same as point 1) // 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; int minFencePoints = 6;
qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints; qCDebug(GeoFenceManagerLog) << "APMGeoFenceManager::loadFromVehicle" << cFencePoints;
if (cFencePoints == 0) { if (cFencePoints == 0) {
...@@ -224,8 +224,8 @@ bool APMGeoFenceManager::_geoFenceSupported(void) ...@@ -224,8 +224,8 @@ bool APMGeoFenceManager::_geoFenceSupported(void)
return false; return false;
} }
if (!_vehicle->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) || if (!_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceTotalParam) ||
!_vehicle->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) { !_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, _fenceActionParam)) {
return false; return false;
} else { } else {
return true; return true;
...@@ -243,20 +243,20 @@ void APMGeoFenceManager::_parametersReady(void) ...@@ -243,20 +243,20 @@ void APMGeoFenceManager::_parametersReady(void)
if (!_firstParamLoadComplete) { if (!_firstParamLoadComplete) {
_firstParamLoadComplete = true; _firstParamLoadComplete = true;
_fenceSupported = _vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION")); _fenceSupported = _vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("FENCE_ACTION"));
if (_fenceSupported) { if (_fenceSupported) {
QStringList paramNames; QStringList paramNames;
QStringList paramLabels; QStringList paramLabels;
if (_vehicle->multiRotor()) { if (_vehicle->multiRotor()) {
_fenceEnableFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FENCE_ENABLE")); _fenceEnableFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_ENABLE"));
_fenceTypeFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE")); _fenceTypeFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FENCE_TYPE"));
connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags); connect(_fenceEnableFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_updateSupportedFlags);
connect(_fenceTypeFact, &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); connect(_circleRadiusFact, &Fact::rawValueChanged, this, &APMGeoFenceManager::_circleRadiusRawValueChanged);
emit circleRadiusChanged(circleRadius()); emit circleRadiusChanged(circleRadius());
...@@ -275,8 +275,8 @@ void APMGeoFenceManager::_parametersReady(void) ...@@ -275,8 +275,8 @@ void APMGeoFenceManager::_parametersReady(void)
_paramLabels.clear(); _paramLabels.clear();
for (int i=0; i<paramNames.count(); i++) { for (int i=0; i<paramNames.count(); i++) {
QString paramName = paramNames[i]; QString paramName = paramNames[i];
if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) { if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* paramFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
_params << QVariant::fromValue(paramFact); _params << QVariant::fromValue(paramFact);
_paramLabels << paramLabels[i]; _paramLabels << paramLabels[i];
} }
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include "ArduCopterFirmwarePlugin.h" #include "ArduCopterFirmwarePlugin.h"
#include "QGCApplication.h" #include "QGCApplication.h"
#include "MissionManager.h" #include "MissionManager.h"
#include "ParameterManager.h"
bool ArduCopterFirmwarePlugin::_remapParamNameIntialized = false; bool ArduCopterFirmwarePlugin::_remapParamNameIntialized = false;
FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remapParamName; FirmwarePlugin::remapParamNameMajorVersionMap_t ArduCopterFirmwarePlugin::_remapParamName;
...@@ -210,7 +211,7 @@ bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle) ...@@ -210,7 +211,7 @@ bool ArduCopterFirmwarePlugin::multiRotorCoaxialMotors(Vehicle* vehicle)
bool ArduCopterFirmwarePlugin::multiRotorXConfig(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) QString ArduCopterFirmwarePlugin::geoFenceRadiusParam(Vehicle* vehicle)
......
...@@ -17,9 +17,9 @@ PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle) ...@@ -17,9 +17,9 @@ PX4GeoFenceManager::PX4GeoFenceManager(Vehicle* vehicle)
, _firstParamLoadComplete(false) , _firstParamLoadComplete(false)
, _circleRadiusFact(NULL) , _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(); _parametersReady();
} }
} }
...@@ -34,7 +34,7 @@ void PX4GeoFenceManager::_parametersReady(void) ...@@ -34,7 +34,7 @@ void PX4GeoFenceManager::_parametersReady(void)
if (!_firstParamLoadComplete) { if (!_firstParamLoadComplete) {
_firstParamLoadComplete = true; _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); connect(_circleRadiusFact, &Fact::rawValueChanged, this, &PX4GeoFenceManager::_circleRadiusRawValueChanged);
emit circleRadiusChanged(circleRadius()); emit circleRadiusChanged(circleRadius());
...@@ -48,8 +48,8 @@ void PX4GeoFenceManager::_parametersReady(void) ...@@ -48,8 +48,8 @@ void PX4GeoFenceManager::_parametersReady(void)
_paramLabels.clear(); _paramLabels.clear();
for (int i=0; i<paramNames.count(); i++) { for (int i=0; i<paramNames.count(); i++) {
QString paramName = paramNames[i]; QString paramName = paramNames[i];
if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) { if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* paramFact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); Fact* paramFact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
_params << QVariant::fromValue(paramFact); _params << QVariant::fromValue(paramFact);
_paramLabels << paramLabels[i]; _paramLabels << paramLabels[i];
} }
......
...@@ -128,7 +128,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr ...@@ -128,7 +128,7 @@ bool GeoFenceController::_loadJsonFile(QJsonDocument& jsonDoc, QString& errorStr
return false; return false;
} }
if (!_activeVehicle->getParameterManager()->loadFromJson(json, false /* required */, errorString)) { if (!_activeVehicle->parameterManager()->loadFromJson(json, false /* required */, errorString)) {
return false; return false;
} }
...@@ -274,7 +274,7 @@ void GeoFenceController::saveToFile(const QString& filename) ...@@ -274,7 +274,7 @@ void GeoFenceController::saveToFile(const QString& filename)
fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue; fenceFileObject[JsonHelper::jsonGroundStationKey] = JsonHelper::jsonGroundStationValue;
QStringList paramNames; QStringList paramNames;
ParameterManager* paramMgr = _activeVehicle->getParameterManager(); ParameterManager* paramMgr = _activeVehicle->parameterManager();
GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager(); GeoFenceManager* fenceMgr = _activeVehicle->geoFenceManager();
QVariantList params = fenceMgr->params(); QVariantList params = fenceMgr->params();
...@@ -322,21 +322,21 @@ void GeoFenceController::removeAll(void) ...@@ -322,21 +322,21 @@ void GeoFenceController::removeAll(void)
void GeoFenceController::loadFromVehicle(void) void GeoFenceController::loadFromVehicle(void)
{ {
if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
_activeVehicle->geoFenceManager()->loadFromVehicle(); _activeVehicle->geoFenceManager()->loadFromVehicle();
} else { } 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) void GeoFenceController::sendToVehicle(void)
{ {
if (_activeVehicle->getParameterManager()->parametersAreReady() && !syncInProgress()) { if (_activeVehicle->parameterManager()->parametersReady() && !syncInProgress()) {
setDirty(false); setDirty(false);
_polygon.setDirty(false); _polygon.setDirty(false);
_activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList()); _activeVehicle->geoFenceManager()->sendToVehicle(_breachReturnPoint, _polygon.coordinateList());
} else { } 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();
} }
} }
......
...@@ -1052,7 +1052,7 @@ void MissionController::_activeVehicleSet(void) ...@@ -1052,7 +1052,7 @@ void MissionController::_activeVehicleSet(void)
connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged); connect(_activeVehicle, &Vehicle::homePositionAvailableChanged, this, &MissionController::_activeVehicleHomePositionAvailableChanged);
connect(_activeVehicle, &Vehicle::homePositionChanged, this, &MissionController::_activeVehicleHomePositionChanged); 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 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. // We don't request mission items for new vehicles since that will happen autamatically.
loadFromVehicle(); loadFromVehicle();
......
...@@ -95,6 +95,7 @@ ...@@ -95,6 +95,7 @@
#include "MissionCommandTree.h" #include "MissionCommandTree.h"
#include "GeoFenceController.h" #include "GeoFenceController.h"
#include "QGCMapPolygon.h" #include "QGCMapPolygon.h"
#include "ParameterManager.h"
#ifndef __ios__ #ifndef __ios__
#include "SerialLink.h" #include "SerialLink.h"
...@@ -379,6 +380,7 @@ void QGCApplication::_initCommon(void) ...@@ -379,6 +380,7 @@ void QGCApplication::_initCommon(void)
qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only"); qmlRegisterUncreatableType<Vehicle> ("QGroundControl.Vehicle", 1, 0, "Vehicle", "Reference only");
qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Reference only"); qmlRegisterUncreatableType<MissionItem> ("QGroundControl.Vehicle", 1, 0, "MissionItem", "Reference only");
qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only"); qmlRegisterUncreatableType<MissionManager> ("QGroundControl.Vehicle", 1, 0, "MissionManager", "Reference only");
qmlRegisterUncreatableType<ParameterManager> ("QGroundControl.Vehicle", 1, 0, "ParameterManager", "Reference only");
qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only"); qmlRegisterUncreatableType<JoystickManager> ("QGroundControl.JoystickManager", 1, 0, "JoystickManager", "Reference only");
qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only"); qmlRegisterUncreatableType<Joystick> ("QGroundControl.JoystickManager", 1, 0, "Joystick", "Reference only");
qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only"); qmlRegisterUncreatableType<QGCPositionManager> ("QGroundControl.QGCPositionManager", 1, 0, "QGCPositionManager", "Reference only");
......
...@@ -29,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void) ...@@ -29,7 +29,7 @@ ParameterEditorController::ParameterEditorController(void)
: _currentComponentId(_vehicle->defaultComponentId()) : _currentComponentId(_vehicle->defaultComponentId())
, _parameters(new QmlObjectListModel(this)) , _parameters(new QmlObjectListModel(this))
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->parameterManager()->getGroupMap();
foreach (int componentId, groupMap.keys()) { foreach (int componentId, groupMap.keys()) {
_componentIds += QString("%1").arg(componentId); _componentIds += QString("%1").arg(componentId);
} }
...@@ -49,14 +49,14 @@ ParameterEditorController::~ParameterEditorController() ...@@ -49,14 +49,14 @@ ParameterEditorController::~ParameterEditorController()
QStringList ParameterEditorController::getGroupsForComponent(int componentId) QStringList ParameterEditorController::getGroupsForComponent(int componentId)
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->parameterManager()->getGroupMap();
return groupMap[componentId].keys(); return groupMap[componentId].keys();
} }
QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group) QStringList ParameterEditorController::getParametersForGroup(int componentId, QString group)
{ {
const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->parameterManager()->getGroupMap();
return groupMap[componentId][group]; return groupMap[componentId][group];
} }
...@@ -65,11 +65,11 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen ...@@ -65,11 +65,11 @@ QStringList ParameterEditorController::searchParametersForComponent(int componen
{ {
QStringList list; QStringList list;
foreach(const QString &paramName, _autopilot->parameterNames(componentId)) { foreach(const QString &paramName, _vehicle->parameterManager()->parameterNames(componentId)) {
if (searchText.isEmpty()) { if (searchText.isEmpty()) {
list += paramName; list += paramName;
} else { } else {
Fact* fact = _vehicle->getParameterFact(componentId, paramName); Fact* fact = _vehicle->parameterManager()->getParameter(componentId, paramName);
if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) { if (searchInName && fact->name().contains(searchText, Qt::CaseInsensitive)) {
list += paramName; list += paramName;
...@@ -105,7 +105,7 @@ void ParameterEditorController::saveToFile(const QString& filename) ...@@ -105,7 +105,7 @@ void ParameterEditorController::saveToFile(const QString& filename)
} }
QTextStream stream(&file); QTextStream stream(&file);
_autopilot->writeParametersToStream(stream); _vehicle->parameterManager()->writeParametersToStream(stream);
file.close(); file.close();
} }
} }
...@@ -141,7 +141,7 @@ void ParameterEditorController::loadFromFile(const QString& filename) ...@@ -141,7 +141,7 @@ void ParameterEditorController::loadFromFile(const QString& filename)
} }
QTextStream stream(&file); QTextStream stream(&file);
errors = _autopilot->readParametersFromStream(stream); errors = _vehicle->parameterManager()->readParametersFromStream(stream);
file.close(); file.close();
if (!errors.isEmpty()) { if (!errors.isEmpty()) {
...@@ -163,12 +163,12 @@ void ParameterEditorController::loadFromFilePicker(void) ...@@ -163,12 +163,12 @@ void ParameterEditorController::loadFromFilePicker(void)
void ParameterEditorController::refresh(void) void ParameterEditorController::refresh(void)
{ {
_autopilot->refreshAllParameters(); _vehicle->parameterManager()->refreshAllParameters();
} }
void ParameterEditorController::resetAllToDefaults(void) void ParameterEditorController::resetAllToDefaults(void)
{ {
_autopilot->resetAllParametersToDefaults(); _vehicle->parameterManager()->resetAllParametersToDefaults();
refresh(); refresh();
} }
...@@ -188,13 +188,13 @@ void ParameterEditorController::_updateParameters(void) ...@@ -188,13 +188,13 @@ void ParameterEditorController::_updateParameters(void)
QObjectList newParameterList; QObjectList newParameterList;
if (_searchText.isEmpty()) { if (_searchText.isEmpty()) {
const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->getParameterManager()->getGroupMap(); const QMap<int, QMap<QString, QStringList> >& groupMap = _vehicle->parameterManager()->getGroupMap();
foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) { foreach (const QString& parameter, groupMap[_currentComponentId][_currentGroup]) {
newParameterList.append(_vehicle->getParameterFact(_currentComponentId, parameter)); newParameterList.append(_vehicle->parameterManager()->getParameter(_currentComponentId, parameter));
} }
} else { } else {
foreach(const QString &parameter, _autopilot->parameterNames(_vehicle->defaultComponentId())) { foreach(const QString &parameter, _vehicle->parameterManager()->parameterNames(_vehicle->defaultComponentId())) {
Fact* fact = _vehicle->getParameterFact(_vehicle->defaultComponentId(), parameter); Fact* fact = _vehicle->parameterManager()->getParameter(_vehicle->defaultComponentId(), parameter);
if (fact->name().contains(_searchText, Qt::CaseInsensitive) || if (fact->name().contains(_searchText, Qt::CaseInsensitive) ||
fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) || fact->shortDescription().contains(_searchText, Qt::CaseInsensitive) ||
fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) { fact->longDescription().contains(_searchText, Qt::CaseInsensitive)) {
......
...@@ -14,6 +14,7 @@ ...@@ -14,6 +14,7 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "FollowMe.h" #include "FollowMe.h"
#include "QGroundControlQmlGlobal.h" #include "QGroundControlQmlGlobal.h"
#include "ParameterManager.h"
#ifdef __mobile__ #ifdef __mobile__
#include "MobileScreenMgr.h" #include "MobileScreenMgr.h"
...@@ -99,7 +100,7 @@ void MultiVehicleManager::_vehicleHeartbeatInfo(LinkInterface* link, int vehicle ...@@ -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); Vehicle* vehicle = new Vehicle(link, vehicleId, (MAV_AUTOPILOT)vehicleFirmwareType, (MAV_TYPE)vehicleType, _firmwarePluginManager, _autopilotPluginManager, _joystickManager);
connect(vehicle, &Vehicle::allLinksInactive, this, &MultiVehicleManager::_deleteVehiclePhase1); 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); _vehicles.append(vehicle);
...@@ -189,7 +190,7 @@ void MultiVehicleManager::_deleteVehiclePhase2(void) ...@@ -189,7 +190,7 @@ void MultiVehicleManager::_deleteVehiclePhase2(void)
if (_activeVehicle) { if (_activeVehicle) {
_activeVehicle->setActive(true); _activeVehicle->setActive(true);
emit activeVehicleAvailableChanged(true); emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->parametersReady()) { if (_activeVehicle->parameterManager()->parametersReady()) {
emit parameterReadyVehicleAvailableChanged(true); emit parameterReadyVehicleAvailableChanged(true);
} }
} }
...@@ -237,23 +238,23 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void) ...@@ -237,23 +238,23 @@ void MultiVehicleManager::_setActiveVehiclePhase2(void)
_activeVehicleAvailable = true; _activeVehicleAvailable = true;
emit activeVehicleAvailableChanged(true); emit activeVehicleAvailableChanged(true);
if (_activeVehicle->autopilotPlugin()->parametersReady()) { if (_activeVehicle->parameterManager()->parametersReady()) {
_parameterReadyVehicleAvailable = true; _parameterReadyVehicleAvailable = true;
emit parameterReadyVehicleAvailableChanged(true); emit parameterReadyVehicleAvailableChanged(true);
} }
} }
} }
void MultiVehicleManager::_autopilotParametersReadyChanged(bool parametersReady) void MultiVehicleManager::_vehicleParametersReadyChanged(bool parametersReady)
{ {
AutoPilotPlugin* autopilot = dynamic_cast<AutoPilotPlugin*>(sender()); ParameterManager* paramMgr = dynamic_cast<ParameterManager*>(sender());
if (!autopilot) { if (!paramMgr) {
qWarning() << "Dynamic cast failed!"; qWarning() << "Dynamic cast failed!";
return; return;
} }
if (autopilot->vehicle() == _activeVehicle) { if (paramMgr->vehicle() == _activeVehicle) {
_parameterReadyVehicleAvailable = parametersReady; _parameterReadyVehicleAvailable = parametersReady;
emit parameterReadyVehicleAvailableChanged(parametersReady); emit parameterReadyVehicleAvailableChanged(parametersReady);
} }
......
...@@ -93,7 +93,7 @@ private slots: ...@@ -93,7 +93,7 @@ private slots:
void _deleteVehiclePhase1(Vehicle* vehicle); void _deleteVehiclePhase1(Vehicle* vehicle);
void _deleteVehiclePhase2(void); void _deleteVehiclePhase2(void);
void _setActiveVehiclePhase2(void); void _setActiveVehiclePhase2(void);
void _autopilotParametersReadyChanged(bool parametersReady); void _vehicleParametersReadyChanged(bool parametersReady);
void _sendGCSHeartbeat(void); void _sendGCSHeartbeat(void);
void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType); void _vehicleHeartbeatInfo(LinkInterface* link, int vehicleId, int vehicleMavlinkVersion, int vehicleFirmwareType, int vehicleType);
......
...@@ -101,7 +101,7 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -101,7 +101,7 @@ Vehicle::Vehicle(LinkInterface* link,
, _missionManagerInitialRequestComplete(false) , _missionManagerInitialRequestComplete(false)
, _geoFenceManager(NULL) , _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestComplete(false) , _geoFenceManagerInitialRequestComplete(false)
, _parameterLoader(NULL) , _parameterManager(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -156,9 +156,6 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -156,9 +156,6 @@ Vehicle::Vehicle(LinkInterface* link,
_firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType); _firmwarePlugin = _firmwarePluginManager->firmwarePluginForAutopilot(_firmwareType, _vehicleType);
_autopilotPlugin = _autopilotPluginManager->newAutopilotPluginForVehicle(this); _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 to the follow me handle manager
connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager); connect(this, &Vehicle::flightModeChanged,qgcApp()->toolbox()->followMe(), &FollowMe::followMeHandleManager);
...@@ -199,9 +196,8 @@ Vehicle::Vehicle(LinkInterface* link, ...@@ -199,9 +196,8 @@ Vehicle::Vehicle(LinkInterface* link,
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError);
connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable); connect(_missionManager, &MissionManager::newMissionItemsAvailable, this, &Vehicle::_newMissionItemsAvailable);
_parameterLoader = new ParameterManager(this); _parameterManager = new ParameterManager(this);
connect(_parameterLoader, &ParameterManager::parametersReady, _autopilotPlugin, &AutoPilotPlugin::_parametersReadyPreChecks); connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady);
connect(_parameterLoader, &ParameterManager::parameterListProgress, _autopilotPlugin, &AutoPilotPlugin::parameterListProgress);
// GeoFenceManager needs to access ParameterManager so make sure to create after // GeoFenceManager needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
...@@ -295,7 +291,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -295,7 +291,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
, _missionManagerInitialRequestComplete(false) , _missionManagerInitialRequestComplete(false)
, _geoFenceManager(NULL) , _geoFenceManager(NULL)
, _geoFenceManagerInitialRequestComplete(false) , _geoFenceManagerInitialRequestComplete(false)
, _parameterLoader(NULL) , _parameterManager(NULL)
, _armed(false) , _armed(false)
, _base_mode(0) , _base_mode(0)
, _custom_mode(0) , _custom_mode(0)
...@@ -333,7 +329,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType, ...@@ -333,7 +329,7 @@ Vehicle::Vehicle(MAV_AUTOPILOT firmwareType,
_missionManager = new MissionManager(this); _missionManager = new MissionManager(this);
connect(_missionManager, &MissionManager::error, this, &Vehicle::_missionManagerError); 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 needs to access ParameterManager so make sure to create after
_geoFenceManager = _firmwarePlugin->newGeoFenceManager(this); _geoFenceManager = _firmwarePlugin->newGeoFenceManager(this);
...@@ -1299,11 +1295,6 @@ void Vehicle::setHilMode(bool hilMode) ...@@ -1299,11 +1295,6 @@ void Vehicle::setHilMode(bool hilMode)
sendMessageOnPriorityLink(msg); sendMessageOnPriorityLink(msg);
} }
bool Vehicle::missingParameters(void)
{
return _autopilotPlugin->missingParameters();
}
void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple) void Vehicle::requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple)
{ {
mavlink_message_t msg; mavlink_message_t msg;
...@@ -1814,7 +1805,7 @@ void Vehicle::rebootVehicle() ...@@ -1814,7 +1805,7 @@ void Vehicle::rebootVehicle()
int Vehicle::defaultComponentId(void) int Vehicle::defaultComponentId(void)
{ {
return _parameterLoader->defaultComponentId(); return _parameterManager->defaultComponentId();
} }
void Vehicle::setSoloFirmware(bool soloFirmware) void Vehicle::setSoloFirmware(bool soloFirmware)
...@@ -1833,20 +1824,6 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs) ...@@ -1833,20 +1824,6 @@ void Vehicle::motorTest(int motor, int percent, int timeoutSecs)
} }
#endif #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) void Vehicle::_newMissionItemsAvailable(void)
{ {
// After the initial mission request complets we ask for the geofence // After the initial mission request complets we ask for the geofence
......
...@@ -235,7 +235,6 @@ public: ...@@ -235,7 +235,6 @@ public:
Q_PROPERTY(QStringList flightModes READ flightModes CONSTANT) Q_PROPERTY(QStringList flightModes READ flightModes CONSTANT)
Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged) Q_PROPERTY(QString flightMode READ flightMode WRITE setFlightMode NOTIFY flightModeChanged)
Q_PROPERTY(bool hilMode READ hilMode WRITE setHilMode NOTIFY hilModeChanged) 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(QmlObjectListModel* trajectoryPoints READ trajectoryPoints CONSTANT)
Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged) Q_PROPERTY(float latitude READ latitude NOTIFY coordinateChanged)
Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged) Q_PROPERTY(float longitude READ longitude NOTIFY coordinateChanged)
...@@ -295,6 +294,8 @@ public: ...@@ -295,6 +294,8 @@ public:
/// true: Orbit mode is supported by this vehicle /// true: Orbit mode is supported by this vehicle
Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT) Q_PROPERTY(bool orbitModeSupported READ orbitModeSupported CONSTANT)
Q_PROPERTY(ParameterManager* parameterManager READ parameterManager CONSTANT)
// FactGroup object model properties // FactGroup object model properties
Q_PROPERTY(Fact* roll READ roll CONSTANT) Q_PROPERTY(Fact* roll READ roll CONSTANT)
...@@ -491,8 +492,6 @@ public: ...@@ -491,8 +492,6 @@ public:
/// @param sendMultiple Send multiple time to guarantee Vehicle reception /// @param sendMultiple Send multiple time to guarantee Vehicle reception
void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true); void requestDataStream(MAV_DATA_STREAM stream, uint16_t rate, bool sendMultiple = true);
bool missingParameters(void);
typedef enum { typedef enum {
MessageNone, MessageNone,
MessageNormal, MessageNormal,
...@@ -544,8 +543,8 @@ public: ...@@ -544,8 +543,8 @@ public:
void setConnectionLostEnabled(bool connectionLostEnabled); void setConnectionLostEnabled(bool connectionLostEnabled);
ParameterManager* getParameterManager(void) { return _parameterLoader; } ParameterManager* parameterManager(void) { return _parameterManager; }
ParameterManager* getParameterManager(void) const { return _parameterLoader; } ParameterManager* parameterManager(void) const { return _parameterManager; }
static const int cMaxRcChannels = 18; static const int cMaxRcChannels = 18;
...@@ -574,14 +573,6 @@ public: ...@@ -574,14 +573,6 @@ public:
/// @return true: X confiuration, false: Plus configuration /// @return true: X confiuration, false: Plus configuration
bool xConfigMotors(void); 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: public slots:
void setLatitude(double latitude); void setLatitude(double latitude);
void setLongitude(double longitude); void setLongitude(double longitude);
...@@ -599,7 +590,6 @@ signals: ...@@ -599,7 +590,6 @@ signals:
void armedChanged(bool armed); void armedChanged(bool armed);
void flightModeChanged(const QString& flightMode); void flightModeChanged(const QString& flightMode);
void hilModeChanged(bool hilMode); void hilModeChanged(bool hilMode);
void missingParametersChanged(bool missingParameters);
void connectionLostChanged(bool connectionLost); void connectionLostChanged(bool connectionLost);
void connectionLostEnabledChanged(bool connectionLostEnabled); void connectionLostEnabledChanged(bool connectionLostEnabled);
void autoDisconnectChanged(bool autoDisconnectChanged); void autoDisconnectChanged(bool autoDisconnectChanged);
...@@ -763,7 +753,7 @@ private: ...@@ -763,7 +753,7 @@ private:
GeoFenceManager* _geoFenceManager; GeoFenceManager* _geoFenceManager;
bool _geoFenceManagerInitialRequestComplete; bool _geoFenceManagerInitialRequestComplete;
ParameterManager* _parameterLoader; ParameterManager* _parameterManager;
bool _armed; ///< true: vehicle is armed bool _armed; ///< true: vehicle is armed
uint8_t _base_mode; ///< base_mode from HEARTBEAT uint8_t _base_mode; ///< base_mode from HEARTBEAT
......
...@@ -39,7 +39,7 @@ Rectangle { ...@@ -39,7 +39,7 @@ Rectangle {
readonly property string _armedVehicleText: qsTr("This operation cannot be performed while vehicle is armed.") readonly property string _armedVehicleText: qsTr("This operation cannot be performed while vehicle is armed.")
property string _messagePanelText: "missing message panel text" 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() function showSummaryPanel()
{ {
......
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "ParameterManager.h"
VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) : VehicleComponent::VehicleComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
QObject(parent), QObject(parent),
...@@ -49,8 +50,8 @@ void VehicleComponent::setupTriggerSignals(void) ...@@ -49,8 +50,8 @@ void VehicleComponent::setupTriggerSignals(void)
{ {
// Watch for changed on trigger list params // Watch for changed on trigger list params
foreach (const QString &paramName, setupCompleteChangedTriggerList()) { foreach (const QString &paramName, setupCompleteChangedTriggerList()) {
if (_vehicle->parameterExists(FactSystem::defaultComponentId, paramName)) { if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, paramName)) {
Fact* fact = _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName); Fact* fact = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName);
connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated); connect(fact, &Fact::valueChanged, this, &VehicleComponent::_triggerUpdated);
} }
} }
......
...@@ -378,7 +378,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType) ...@@ -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"; 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) { 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) ...@@ -393,7 +393,7 @@ void RadioConfigTest::_fullCalibrationWorker(MAV_AUTOPILOT firmwareType)
if (!found) { if (!found) {
const char* paramName = _functionInfo()[function].parameterName; const char* paramName = _functionInfo()[function].parameterName;
if (paramName) { 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]; qCDebug(RadioConfigTestLog) << "Assigning switch" << function << _rgFunctionChannelMap[function];
if (_rgFunctionChannelMap[function] == 0) { if (_rgFunctionChannelMap[function] == 0) {
_rgFunctionChannelMap[function] = -1; // -1 signals no mapping _rgFunctionChannelMap[function] = -1; // -1 signals no mapping
...@@ -469,8 +469,8 @@ void RadioConfigTest::_validateParameters(void) ...@@ -469,8 +469,8 @@ void RadioConfigTest::_validateParameters(void)
const char* paramName = _functionInfo()[chanFunction].parameterName; const char* paramName = _functionInfo()[chanFunction].parameterName;
if (paramName) { if (paramName) {
qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(); qCDebug(RadioConfigTestLog) << "Validate" << chanFunction << _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt();
QCOMPARE(_vehicle->getParameterFact(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue); QCOMPARE(_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, paramName)->rawValue().toInt(), expectedParameterValue);
} }
} }
...@@ -485,13 +485,13 @@ void RadioConfigTest::_validateParameters(void) ...@@ -485,13 +485,13 @@ void RadioConfigTest::_validateParameters(void)
int rcTrimExpected = _channelSettingsValidate()[chan].rcTrim; int rcTrimExpected = _channelSettingsValidate()[chan].rcTrim;
bool rcReversedExpected = _channelSettingsValidate()[chan].reversed; 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); 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); 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); 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); QCOMPARE(convertOk, true);
bool rcReversedActual = (rcReversedFloat == -1.0f); bool rcReversedActual = (rcReversedFloat == -1.0f);
...@@ -515,7 +515,7 @@ void RadioConfigTest::_validateParameters(void) ...@@ -515,7 +515,7 @@ void RadioConfigTest::_validateParameters(void)
const char* paramName = _functionInfo()[chanFunction].parameterName; const char* paramName = _functionInfo()[chanFunction].parameterName;
if (paramName) { if (paramName) {
// qCDebug(RadioConfigTestLog) << chanFunction << expectedValue << mapParamsSet[paramName].toInt(); // 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);
} }
} }
} }
......
...@@ -13,6 +13,7 @@ ...@@ -13,6 +13,7 @@
#include "QGCMapRCToParamDialog.h" #include "QGCMapRCToParamDialog.h"
#include "ui_QGCMapRCToParamDialog.h" #include "ui_QGCMapRCToParamDialog.h"
#include "ParameterManager.h"
#include <QDebug> #include <QDebug>
#include <QTimer> #include <QTimer>
...@@ -31,7 +32,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ...@@ -31,7 +32,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav
// refresh the parameter from onboard to make sure the current value is used // refresh the parameter from onboard to make sure the current value is used
Vehicle* vehicle = _multiVehicleManager->getVehicleById(mav->getUASID()); 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->minValueDoubleSpinBox->setValue(paramFact->rawMin().toDouble());
ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble()); ui->maxValueDoubleSpinBox->setValue(paramFact->rawMax().toDouble());
...@@ -43,7 +44,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav ...@@ -43,7 +44,7 @@ QGCMapRCToParamDialog::QGCMapRCToParamDialog(QString param_id, UASInterface *mav
ui->paramIdLabel->setText(param_id); ui->paramIdLabel->setText(param_id);
connect(paramFact, &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated); connect(paramFact, &Fact::valueChanged, this, &QGCMapRCToParamDialog::_parameterUpdated);
vehicle->autopilotPlugin()->refreshParameter(FactSystem::defaultComponentId, param_id); vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, param_id);
} }
QGCMapRCToParamDialog::~QGCMapRCToParamDialog() QGCMapRCToParamDialog::~QGCMapRCToParamDialog()
......
...@@ -24,6 +24,7 @@ ...@@ -24,6 +24,7 @@
#include "QGCApplication.h" #include "QGCApplication.h"
#include "MultiVehicleManager.h" #include "MultiVehicleManager.h"
#include "UAS.h" #include "UAS.h"
#include "ParameterManager.h"
MainToolBarController::MainToolBarController(QObject* parent) MainToolBarController::MainToolBarController(QObject* parent)
: QObject(parent) : QObject(parent)
...@@ -47,7 +48,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) ...@@ -47,7 +48,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{ {
// Disconnect the previous one (if any) // Disconnect the previous one (if any)
if (_vehicle) { if (_vehicle) {
disconnect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); disconnect(_vehicle->parameterManager(), &ParameterManager::parameterListProgress, this, &MainToolBarController::_setProgressBarValue);
_mav = NULL; _mav = NULL;
_vehicle = NULL; _vehicle = NULL;
} }
...@@ -57,7 +58,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle) ...@@ -57,7 +58,7 @@ void MainToolBarController::_activeVehicleChanged(Vehicle* vehicle)
{ {
_vehicle = vehicle; _vehicle = vehicle;
_mav = vehicle->uas(); _mav = vehicle->uas();
connect(_vehicle->autopilotPlugin(), &AutoPilotPlugin::parameterListProgress, this, &MainToolBarController::_setProgressBarValue); connect(_vehicle->parameterManager(), &ParameterManager::parameterListProgress, this, &MainToolBarController::_setProgressBarValue);
} }
} }
......
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment