Commit e92110a7 authored by Don Gagne's avatar Don Gagne

Refactor parameter apis from AutoPilotPlugin to ParameterManager

parent f776d5e7
......@@ -66,7 +66,7 @@ linux {
} else {
QMAKE_MACOSX_DEPLOYMENT_TARGET = 10.6
}
QMAKE_MAC_SDK = macosx10.11
QMAKE_MAC_SDK = macosx10.12
QMAKE_CXXFLAGS += -fvisibility=hidden
} else {
error("Unsupported Mac toolchain, only 64-bit LLVM+clang is supported")
......
......@@ -7,12 +7,9 @@
*
****************************************************************************/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "APMAirframeComponent.h"
#include "ArduCopterFirmwarePlugin.h"
#include "ParameterManager.h"
APMAirframeComponent::APMAirframeComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent)
......@@ -52,7 +49,7 @@ bool APMAirframeComponent::requiresSetup(void) const
bool APMAirframeComponent::setupComplete(void) const
{
if (_requiresFrameSetup) {
return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("FRAME"))->rawValue().toInt() >= 0;
} else {
return true;
}
......
......@@ -18,6 +18,7 @@
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include "QGCFileDownload.h"
#include "ParameterManager.h"
#include <QVariant>
#include <QQmlProperty>
......@@ -107,7 +108,7 @@ void APMAirframeComponentController::_loadParametersFromDownloadFile(const QStri
}
}
qgcApp()->restoreOverrideCursor();
_autopilot->refreshAllParameters();
_vehicle->parameterManager()->refreshAllParameters();
}
APMAirframeType::APMAirframeType(const QString& name, const QString& imageResource, int type, QObject* parent) :
......
......@@ -59,9 +59,7 @@ APMAutoPilotPlugin::~APMAutoPilotPlugin()
const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
{
if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_vehicle);
if (parametersReady()) {
if (_vehicle->parameterManager()->parametersReady()) {
_airframeComponent = new APMAirframeComponent(_vehicle, this);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
......@@ -107,7 +105,7 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
_components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent));
//-- Is there an ESP8266 Connected?
if(factExists(FactSystem::ParameterProvider, MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) {
if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) {
_esp8266Component = new ESP8266Component(_vehicle, this);
_esp8266Component->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component));
......@@ -119,25 +117,3 @@ const QVariantList& APMAutoPilotPlugin::vehicleComponents(void)
return _components;
}
/// This will perform various checks prior to signalling that the plug in ready
void APMAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{
#if 0
I believe APM has parameter version stamp, we should check that
// Check for older parameter version set
// FIXME: Firmware is moving to version stamp parameter set. Once that is complete the version stamp
// should be used instead.
if (parameterExists(FactSystem::defaultComponentId, "SENS_GYRO_XOFF")) {
_incorrectParameterVersion = true;
qgcApp()->showMessage("This version of GroundControl can only perform vehicle setup on a newer version of firmware. "
"Please perform a Firmware Upgrade if you wish to use Vehicle Setup.");
}
#endif
Q_UNUSED(missingParameters);
_parametersReady = true;
_missingParameters = false; // we apply only the parameters that do exists on the FactSystem.
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
}
......@@ -52,10 +52,6 @@ public:
APMTuningComponent* tuningComponent (void) const { return _tuningComponent; }
ESP8266Component* esp8266Component (void) const { return _esp8266Component; }
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
private:
bool _incorrectParameterVersion; ///< true: parameter version incorrect, setup not allowed
QVariantList _components;
......
......@@ -10,6 +10,7 @@
#include "APMCompassCal.h"
#include "AutoPilotPlugin.h"
#include "ParameterManager.h"
QGC_LOGGING_CATEGORY(APMCompassCalLog, "APMCompassCalLog")
......@@ -613,11 +614,11 @@ void APMCompassCal::startCalibration(void)
_calWorkerThread->rgCompassAvailable[i] = true;
const char* deviceIdParam = CalWorkerThread::rgCompassParams[i][3];
if (_vehicle->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = _vehicle->getParameterFact(-1, deviceIdParam)->rawValue().toInt() > 0;
if (_vehicle->parameterManager()->parameterExists(-1, deviceIdParam)) {
_calWorkerThread->rgCompassAvailable[i] = _vehicle->parameterManager()->getParameter(-1, deviceIdParam)->rawValue().toInt() > 0;
for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
Fact* paramFact = _vehicle->getParameterFact(-1, offsetParam);
Fact* paramFact = _vehicle->parameterManager()->getParameter(-1, offsetParam);
_rgSavedCompassOffsets[i][j] = paramFact->rawValue().toFloat();
paramFact->setRawValue(0.0);
......@@ -639,8 +640,8 @@ void APMCompassCal::cancelCalibration(void)
for (int i=0; i<3; i++) {
for (int j=0; j<3; j++) {
const char* offsetParam = CalWorkerThread::rgCompassParams[i][j];
if (_vehicle->parameterExists(-1, offsetParam)) {
_vehicle->getParameterFact(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
if (_vehicle->parameterManager()->parameterExists(-1, offsetParam)) {
_vehicle->parameterManager()->getParameter(-1, offsetParam)-> setRawValue(_rgSavedCompassOffsets[i][j]);
}
}
}
......
......@@ -11,6 +11,7 @@
#include "APMPowerComponent.h"
#include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMPowerComponent::APMPowerComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent),
......@@ -40,7 +41,7 @@ bool APMPowerComponent::requiresSetup(void) const
bool APMPowerComponent::setupComplete(void) const
{
return _vehicle->getParameterFact(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0;
return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, QStringLiteral("BATT_CAPACITY"))->rawValue().toInt() != 0;
}
QStringList APMPowerComponent::setupCompleteChangedTriggerList(void) const
......
......@@ -11,6 +11,7 @@
#include "APMRadioComponent.h"
#include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent) :
VehicleComponent(vehicle, autopilot, parent),
......@@ -19,7 +20,7 @@ APMRadioComponent::APMRadioComponent(Vehicle* vehicle, AutoPilotPlugin* autopilo
_mapParams << QStringLiteral("RCMAP_ROLL") << QStringLiteral("RCMAP_PITCH") << QStringLiteral("RCMAP_YAW") << QStringLiteral("RCMAP_THROTTLE");
foreach (const QString& mapParam, _mapParams) {
Fact* fact = _vehicle->getParameterFact(-1, mapParam);
Fact* fact = _vehicle->parameterManager()->getParameter(-1, mapParam);
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
}
......@@ -56,7 +57,7 @@ bool APMRadioComponent::setupComplete(void) const
// First check for all attitude controls mapped
for (int i=0; i<_mapParams.count(); i++) {
mapValues << _vehicle->getParameterFact(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt();
mapValues << _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, _mapParams[i])->rawValue().toInt();
if (mapValues[i] <= 0) {
return false;
}
......@@ -64,14 +65,14 @@ bool APMRadioComponent::setupComplete(void) const
// Next check RC#_MIN/MAX/TRIM all at defaults
foreach (const QString& mapParam, _mapParams) {
int channel = _vehicle->getParameterFact(-1, mapParam)->rawValue().toInt();
if (_vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
int channel = _vehicle->parameterManager()->getParameter(-1, mapParam)->rawValue().toInt();
if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_MIN").arg(channel))->rawValue().toInt() != 1100) {
return true;
}
if (_vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) {
if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_MAX").arg(channel))->rawValue().toInt() != 1900) {
return true;
}
if (_vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) {
if (_vehicle->parameterManager()->getParameter(-1, QString("RC%1_TRIM").arg(channel))->rawValue().toInt() != 1500) {
return true;
}
}
......@@ -116,17 +117,17 @@ void APMRadioComponent::_connectSetupTriggers(void)
// Get the channels for attitude controls and connect to those values for triggers
foreach (const QString& mapParam, _mapParams) {
int channel = _vehicle->getParameterFact(FactSystem::defaultComponentId, mapParam)->rawValue().toInt();
int channel = _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, mapParam)->rawValue().toInt();
Fact* fact = _vehicle->getParameterFact(-1, QString("RC%1_MIN").arg(channel));
Fact* fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_MIN").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
fact = _vehicle->getParameterFact(-1, QString("RC%1_MAX").arg(channel));
fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_MAX").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
fact = _vehicle->getParameterFact(-1, QString("RC%1_TRIM").arg(channel));
fact = _vehicle->parameterManager()->getParameter(-1, QString("RC%1_TRIM").arg(channel));
_triggerFacts << fact;
connect(fact, &Fact::valueChanged, this, &APMRadioComponent::_triggerChanged);
}
......
......@@ -12,6 +12,7 @@
#include "APMAutoPilotPlugin.h"
#include "APMSensorsComponentController.h"
#include "APMAirframeComponent.h"
#include "ParameterManager.h"
// These two list must be kept in sync
......@@ -62,7 +63,7 @@ QStringList APMSensorsComponent::setupCompleteChangedTriggerList(void) const
// Accelerometer triggers
triggers << "INS_ACCOFFS_X" << "INS_ACCOFFS_Y" << "INS_ACCOFFS_Z";
if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
triggers << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
triggers << QStringLiteral("INS_ACC2OFFS_X") << QStringLiteral("INS_ACC2OFFS_Y") << QStringLiteral("INS_ACC2OFFS_Z");
triggers << QStringLiteral("INS_ACC3OFFS_X") << QStringLiteral("INS_ACC3OFFS_Y") << QStringLiteral("INS_ACC3OFFS_Z");
......@@ -108,10 +109,10 @@ bool APMSensorsComponent::compassSetupNeeded(void) const
rgOffsets[2] << QStringLiteral("COMPASS_OFS3_X") << QStringLiteral("COMPASS_OFS3_Y") << QStringLiteral("COMPASS_OFS3_Z");
for (size_t i=0; i<cCompass; i++) {
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_vehicle->getParameterFact(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgDevicesIds[i])->rawValue().toInt() != 0 &&
_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, rgCompassUse[i])->rawValue().toInt() != 0) {
for (size_t j=0; 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;
}
}
......@@ -133,7 +134,7 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
rgOffsets.clear();
// This parameter is not available in all firmware version. Specifically missing from older Solo firmware.
if (_vehicle->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
if (_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, QStringLiteral("INS_USE"))) {
rgUse << QStringLiteral("INS_USE") << QStringLiteral("INS_USE2") << QStringLiteral("INS_USE3");
// We have usage information for the remaining accels, so we can test them sa well
......@@ -147,9 +148,9 @@ bool APMSensorsComponent::accelSetupNeeded(void) const
}
for (int i=0; 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++) {
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;
}
}
......
......@@ -13,6 +13,7 @@
#include "UAS.h"
#include "QGCApplication.h"
#include "APMAutoPilotPlugin.h"
#include "ParameterManager.h"
#include <QVariant>
#include <QQmlProperty>
......@@ -214,9 +215,7 @@ void APMSensorsComponentController::_handleUASTextMessage(int uasId, int compId,
Q_UNUSED(compId);
Q_UNUSED(severity);
UASInterface* uas = _autopilot->vehicle()->uas();
Q_ASSERT(uas);
if (uasId != uas->getUASID()) {
if (uasId != _vehicle->id()) {
return;
}
......@@ -428,12 +427,12 @@ void APMSensorsComponentController::_refreshParams(void)
fastRefreshList << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X") << QStringLiteral("COMPASS_OFS_X")
<< QStringLiteral("INS_ACCOFFS_X") << QStringLiteral("INS_ACCOFFS_Y") << QStringLiteral("INS_ACCOFFS_Z");
foreach (const QString &paramName, fastRefreshList) {
_autopilot->refreshParameter(FactSystem::defaultComponentId, paramName);
_vehicle->parameterManager()->refreshParameter(FactSystem::defaultComponentId, paramName);
}
// Now ask for all to refresh
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
_autopilot->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
_vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("COMPASS_"));
_vehicle->parameterManager()->refreshParametersPrefix(FactSystem::defaultComponentId, QStringLiteral("INS_"));
}
void APMSensorsComponentController::_updateAndEmitShowOrientationCalArea(bool show)
......
......@@ -11,6 +11,7 @@
#include "APMTuningComponent.h"
#include "APMAutoPilotPlugin.h"
#include "APMAirframeComponent.h"
#include "ParameterManager.h"
APMTuningComponent::APMTuningComponent(Vehicle* vehicle, AutoPilotPlugin* autopilot, QObject* parent)
: VehicleComponent(vehicle, autopilot, parent)
......@@ -60,7 +61,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
// Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares
if (_vehicle->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
if (_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
}
break;
......
......@@ -21,15 +21,9 @@ AutoPilotPlugin::AutoPilotPlugin(Vehicle* vehicle, QObject* parent)
: QObject(parent)
, _vehicle(vehicle)
, _firmwarePlugin(vehicle->firmwarePlugin())
, _parametersReady(false)
, _missingParameters(false)
, _setupComplete(false)
{
Q_ASSERT(vehicle);
connect(_vehicle->uas(), &UASInterface::disconnected, this, &AutoPilotPlugin::_uasDisconnected);
connect(this, &AutoPilotPlugin::parametersReadyChanged, this, &AutoPilotPlugin::_parametersReadyChanged);
}
AutoPilotPlugin::~AutoPilotPlugin()
......@@ -37,26 +31,6 @@ AutoPilotPlugin::~AutoPilotPlugin()
}
void AutoPilotPlugin::_uasDisconnected(void)
{
_parametersReady = false;
emit parametersReadyChanged(_parametersReady);
}
void AutoPilotPlugin::_parametersReadyChanged(bool parametersReady)
{
if (parametersReady) {
_recalcSetupComplete();
if (!_setupComplete) {
qgcApp()->showMessage("One or more vehicle components require setup prior to flight.");
// Take the user to Vehicle Summary
qgcApp()->showSetupView();
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
}
}
void AutoPilotPlugin::_recalcSetupComplete(void)
{
bool newSetupComplete = true;
......@@ -79,81 +53,17 @@ void AutoPilotPlugin::_recalcSetupComplete(void)
bool AutoPilotPlugin::setupComplete(void)
{
Q_ASSERT(_parametersReady);
return _setupComplete;
}
void AutoPilotPlugin::resetAllParametersToDefaults(void)
{
mavlink_message_t msg;
MAVLinkProtocol* mavlink = qgcApp()->toolbox()->mavlinkProtocol();
mavlink_msg_command_long_pack(mavlink->getSystemId(),
mavlink->getComponentId(),
&msg,
_vehicle->id(), // Target systeem
_vehicle->defaultComponentId(), // Target component
MAV_CMD_PREFLIGHT_STORAGE,
0, // Confirmation
2, // 2 = Reset params to default
-1, // -1 = No change to mission storage
0, // 0 = Ignore
0, 0, 0, 0); // Unused
_vehicle->sendMessageOnPriorityLink(msg);
}
void AutoPilotPlugin::refreshAllParameters(unsigned char componentID)
{
_vehicle->getParameterManager()->refreshAllParameters((uint8_t)componentID);
}
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{
_vehicle->getParameterManager()->refreshParameter(componentId, name);
}
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
void AutoPilotPlugin::parametersReadyPreChecks(void)
{
_vehicle->getParameterManager()->refreshParametersPrefix(componentId, namePrefix);
}
_recalcSetupComplete();
if (!_setupComplete) {
qgcApp()->showMessage("One or more vehicle components require setup prior to flight.");
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterManager()->parameterExists(componentId, name);
// Other providers will go here once they come online
// Take the user to Vehicle Summary
qgcApp()->showSetupView();
qgcApp()->processEvents(QEventLoop::ExcludeUserInputEvents);
}
Q_ASSERT(false);
return false;
}
Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, const QString& name)
{
switch (provider) {
case FactSystem::ParameterProvider:
return _vehicle->getParameterManager()->getFact(componentId, name);
// Other providers will go here once they come online
}
Q_ASSERT(false);
return NULL;
}
QStringList AutoPilotPlugin::parameterNames(int componentId)
{
return _vehicle->getParameterManager()->parameterNames(componentId);
}
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
_vehicle->getParameterManager()->writeParametersToStream(stream);
}
QString AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
return _vehicle->getParameterManager()->readParametersFromStream(stream);
}
......@@ -38,68 +38,24 @@ public:
AutoPilotPlugin(Vehicle* vehicle, QObject* parent);
~AutoPilotPlugin();
/// true: parameters are ready for use
Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged)
/// true: parameters are missing from firmware response, false: all parameters received from firmware
Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged)
/// List of VehicleComponent objects
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
/// false: One or more vehicle components require setup
Q_PROPERTY(bool setupComplete READ setupComplete NOTIFY setupCompleteChanged)
/// Reset all parameters to their default values
Q_INVOKABLE void resetAllParametersToDefaults(void);
/// Re-request the full set of parameters from the autopilot
Q_INVOKABLE void refreshAllParameters(unsigned char componentID = MAV_COMP_ID_ALL);
/// Request a refresh on the specific parameter
Q_INVOKABLE void refreshParameter(int componentId, const QString& name);
/// Request a refresh on all parameters that begin with the specified prefix
Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix);
/// Returns all parameter names
QStringList parameterNames(int componentId);
/// Writes the parameter facts to the specified stream
void writeParametersToStream(QTextStream &stream);
/// Reads the parameters from the stream and updates values
/// @return Errors during load. Empty string for no errors
QString readParametersFromStream(QTextStream &stream);
/// Returns true if the specifed fact exists
Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
/// Returns the specified Fact.
/// WARNING: Will assert if fact does not exists. If that possibility exists, check for existence first with
/// factExists.
Fact* getFact(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name
/// Called when parameters are ready for the first time. Note that parameters may still be missing.
/// Overrides must call base class.
virtual void parametersReadyPreChecks(void);
// Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0;
// Property accessors
bool parametersReady(void) { return _parametersReady; }
bool missingParameters(void) { return _missingParameters; }
bool setupComplete(void);
Vehicle* vehicle(void) { return _vehicle; }
virtual void _parametersReadyPreChecks(bool parametersReady) = 0;
signals:
void parametersReadyChanged(bool parametersReady);
void missingParametersChanged(bool missingParameters);
void setupCompleteChanged(bool setupComplete);
void parameterListProgress(float value);
protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
......@@ -107,15 +63,8 @@ protected:
Vehicle* _vehicle;
FirmwarePlugin* _firmwarePlugin;
bool _parametersReady;
bool _missingParameters;
bool _setupComplete;
private slots:
void _uasDisconnected(void);
void _parametersReadyChanged(bool parametersReady);
private:
void _recalcSetupComplete(void);
};
......
......@@ -16,6 +16,7 @@
#include "AutoPilotPluginManager.h"
#include "QGCApplication.h"
#include "UAS.h"
#include "ParameterManager.h"
#include <QHostAddress>
#include <QtEndian>
......@@ -393,7 +394,7 @@ ESP8266ComponentController::_commandAck(uint8_t compID, uint16_t command, uint8_
emit busyChanged();
qCDebug(ESP8266ComponentControllerLog) << "_commandAck for" << command;
if(command == MAV_CMD_PREFLIGHT_STORAGE) {
_autopilot->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE);
_vehicle->parameterManager()->refreshAllParameters(MAV_COMP_ID_UDP_BRIDGE);
}
}
}
......
......@@ -25,12 +25,3 @@ const QVariantList& GenericAutoPilotPlugin::vehicleComponents(void)
return emptyList;
}
/// This will perform various checks prior to signalling that the plug in ready
void GenericAutoPilotPlugin::_parametersReadyPreChecks(bool missingParameters)
{
_parametersReady = true;
_missingParameters = missingParameters;
emit missingParametersChanged(_missingParameters);
emit parametersReadyChanged(_parametersReady);
}
......@@ -27,10 +27,6 @@ public:
// Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void);
public slots:
// FIXME: This is public until we restructure AutoPilotPlugin/FirmwarePlugin/Vehicle
void _parametersReadyPreChecks(bool missingParameters);
};
#endif
......@@ -13,6 +13,7 @@
#include "AirframeComponent.h"
#include "QGCQmlWidgetHolder.h"
#include "ParameterManager.h"
#if 0
// Broken by latest mavlink module changes. Not used yet. Comment out for now.
......@@ -129,7 +130,7 @@ bool AirframeComponent::requiresSetup(void) const
bool AirframeComponent::setupComplete(void) const
{
return _vehicle->getParameterFact(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0;
return _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "SYS_AUTOSTART")->rawValue().toInt() != 0;
}
QStringList AirframeComponent::setupCompleteChangedTriggerList(void) const
......
......@@ -43,17 +43,17 @@ QString FlightModesComponent::iconResource(void) const
bool FlightModesComponent::requiresSetup(void) const
{
return _vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
return _vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1 ? false : true;
}
bool FlightModesComponent::setupComplete(void) const
{
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
return true;
}
if (_vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 ||
(_vehicle->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->getParameterFact(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
if (_vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_MODE_SW")->rawValue().toInt() != 0 ||
(_vehicle->parameterManager()->parameterExists(FactSystem::defaultComponentId, "RC_MAP_FLTMODE") && _vehicle->parameterManager()->getParameter(FactSystem::defaultComponentId, "RC_MAP_FLTMODE")->rawValue().toInt() != 0)) {
return true;
}
......@@ -81,7 +81,7 @@ QUrl FlightModesComponent::summaryQmlSource(void) const
QString FlightModesComponent::prerequisiteSetup(void) const
{
if (_vehicle->getParameterFact(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
if (_vehicle->parameterManager()->getParameter(-1, "COM_RC_IN_MODE")->rawValue().toInt() == 1) {
// No RC input
return QString();
} else {
......@@ -92,7 +92,7 @@ QString FlightModesComponent::prerequisiteSetup(void) const
return plugin->airframeComponent()->name();
} else if (!plugin->radioComponent()->setupComplete()) {
return plugin->radioComponent()->name();
} else if (!plugin->vehicle()->hilMode() && !plugin->sensorsComponent()->setupComplete()) {
} else if (!_vehicle->hilMode() && !plugin->sensorsComponent()->setupComplete()) {
return plugin->sensorsComponent()->name();
}
}
......
......@@ -52,7 +52,7 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
if (_components.count() == 0 && !_incorrectParameterVersion) {
Q_ASSERT(_vehicle);
if (parametersReady()) {
if (_vehicle->parameterManager()->parametersReady()) {
_airframeComponent = new AirframeComponent(_vehicle, this);
_airframeComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_airframeComponent));
......@@ -91,14 +91,14 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
_components.append(QVariant::fromValue((VehicleComponent*)_tuningComponent));
//-- Is there support for cameras?
if(factExists(FactSystem::ParameterProvider, _vehicle->id(), "TRIG_MODE")) {
if(_vehicle->parameterManager()->parameterExists(_vehicle->id(), "TRIG_MODE")) {
_cameraComponent = new CameraComponent(_vehicle, this);
_cameraComponent->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_cameraComponent));
}
//-- Is there an ESP8266 Connected?
if(factExists(FactSystem::ParameterProvider, MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) {
if(_vehicle->parameterManager()->parameterExists(MAV_COMP_ID_UDP_BRIDGE, "SW_VER")) {
_esp8266Component = new ESP8266Component(_vehicle, this);
_esp8266Component->setupTriggerSignals();
_components.append(QVariant::fromValue((VehicleComponent*)_esp8266Component));
......@@ -111,21 +111,18 @@ const QVariantList& PX4AutoPilotPlugin::vehicleComponents(void)
return _components;
}
/// This will perform various checks prior to signalling that the plug in ready