Commit f6a0de27 authored by Don Gagne's avatar Don Gagne

Merge pull request #1451 from DonLakeFlyer/QmlParamEdit

Parameter Editor in Qml
parents 383b4aa3 4c50595f
...@@ -599,14 +599,13 @@ INCLUDEPATH += \ ...@@ -599,14 +599,13 @@ INCLUDEPATH += \
src/VehicleSetup src/VehicleSetup
FORMS += \ FORMS += \
src/VehicleSetup/ParameterEditor.ui \
src/VehicleSetup/SetupView.ui \ src/VehicleSetup/SetupView.ui \
HEADERS+= \ HEADERS+= \
src/VehicleSetup/SetupView.h \ src/VehicleSetup/SetupView.h \
src/VehicleSetup/ParameterEditor.h \
src/VehicleSetup/VehicleComponent.h \ src/VehicleSetup/VehicleComponent.h \
src/VehicleSetup/FirmwareUpgradeController.h \ src/VehicleSetup/FirmwareUpgradeController.h \
src/VehicleSetup/ParameterEditorController.h \
src/VehicleSetup/PX4Bootloader.h \ src/VehicleSetup/PX4Bootloader.h \
src/VehicleSetup/PX4FirmwareUpgradeThread.h \ src/VehicleSetup/PX4FirmwareUpgradeThread.h \
src/AutoPilotPlugins/AutoPilotPluginManager.h \ src/AutoPilotPlugins/AutoPilotPluginManager.h \
...@@ -629,9 +628,9 @@ HEADERS+= \ ...@@ -629,9 +628,9 @@ HEADERS+= \
SOURCES += \ SOURCES += \
src/VehicleSetup/SetupView.cc \ src/VehicleSetup/SetupView.cc \
src/VehicleSetup/ParameterEditor.cc \
src/VehicleSetup/VehicleComponent.cc \ src/VehicleSetup/VehicleComponent.cc \
src/VehicleSetup/FirmwareUpgradeController.cc \ src/VehicleSetup/FirmwareUpgradeController.cc \
src/VehicleSetup/ParameterEditorController.cc \
src/VehicleSetup/PX4Bootloader.cc \ src/VehicleSetup/PX4Bootloader.cc \
src/VehicleSetup/PX4FirmwareUpgradeThread.cc \ src/VehicleSetup/PX4FirmwareUpgradeThread.cc \
src/AutoPilotPlugins/AutoPilotPluginManager.cc \ src/AutoPilotPlugins/AutoPilotPluginManager.cc \
......
<RCC> <RCC>
<qresource prefix="/unittest"> <qresource prefix="/unittest">
<file alias="MockLink.param">src/qgcunittest/MockLink.param</file> <file alias="MockLink.params">src/qgcunittest/MockLink.params</file>
<file alias="FactSystemTest.qml">src/FactSystem/FactSystemTest.qml</file> <file alias="FactSystemTest.qml">src/FactSystem/FactSystemTest.qml</file>
</qresource> </qresource>
...@@ -35,6 +35,7 @@ ...@@ -35,6 +35,7 @@
<file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file> <file alias="VehicleSummary.qml">src/VehicleSetup/VehicleSummary.qml</file>
<file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file> <file alias="FirmwareUpgrade.qml">src/VehicleSetup/FirmwareUpgrade.qml</file>
<file alias="ParameterEditor.qml">src/VehicleSetup/ParameterEditor.qml</file>
<file alias="SafetyComponent.qml">src/AutoPilotPlugins/PX4/SafetyComponent.qml</file> <file alias="SafetyComponent.qml">src/AutoPilotPlugins/PX4/SafetyComponent.qml</file>
<file alias="PowerComponent.qml">src/AutoPilotPlugins/PX4/PowerComponent.qml</file> <file alias="PowerComponent.qml">src/AutoPilotPlugins/PX4/PowerComponent.qml</file>
<file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file> <file alias="SensorsComponent.qml">src/AutoPilotPlugins/PX4/SensorsComponent.qml</file>
......
...@@ -25,6 +25,7 @@ ...@@ -25,6 +25,7 @@
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
#include "QGCUASParamManagerInterface.h"
AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) : AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) :
QObject(parent), QObject(parent),
...@@ -34,11 +35,36 @@ AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) : ...@@ -34,11 +35,36 @@ AutoPilotPlugin::AutoPilotPlugin(UASInterface* uas, QObject* parent) :
Q_ASSERT(_uas); Q_ASSERT(_uas);
} }
void AutoPilotPlugin::refreshAllParameters(void)
{
_getParameterLoader()->refreshAllParameters();
}
void AutoPilotPlugin::refreshParameter(int componentId, const QString& name)
{
_getParameterLoader()->refreshParameter(componentId, name);
}
void AutoPilotPlugin::refreshParametersPrefix(int componentId, const QString& namePrefix)
{
_getParameterLoader()->refreshParametersPrefix(componentId, namePrefix);
}
bool AutoPilotPlugin::parameterExists(const QString& name)
{
return _getParameterLoader()->parameterExists(FactSystem::defaultComponentId, name);
}
Fact* AutoPilotPlugin::getParameterFact(const QString& name)
{
return _getParameterLoader()->getFact(FactSystem::defaultComponentId, name);
}
bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name) bool AutoPilotPlugin::factExists(FactSystem::Provider_t provider, int componentId, const QString& name)
{ {
switch (provider) { switch (provider) {
case FactSystem::ParameterProvider: case FactSystem::ParameterProvider:
return getParameterLoader()->factExists(componentId, name); return _getParameterLoader()->parameterExists(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -51,7 +77,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -51,7 +77,7 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
{ {
switch (provider) { switch (provider) {
case FactSystem::ParameterProvider: case FactSystem::ParameterProvider:
return getParameterLoader()->getFact(componentId, name); return _getParameterLoader()->getFact(componentId, name);
// Other providers will go here once they come online // Other providers will go here once they come online
} }
...@@ -59,3 +85,40 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId, ...@@ -59,3 +85,40 @@ Fact* AutoPilotPlugin::getFact(FactSystem::Provider_t provider, int componentId,
Q_ASSERT(false); Q_ASSERT(false);
return NULL; return NULL;
} }
QStringList AutoPilotPlugin::parameterNames(void)
{
return _getParameterLoader()->parameterNames();
}
const QMap<int, QMap<QString, QStringList> >& AutoPilotPlugin::getGroupMap(void)
{
return _getParameterLoader()->getGroupMap();
}
void AutoPilotPlugin::writeParametersToStream(QTextStream &stream)
{
Q_ASSERT(_uas);
_uas->getParamManager()->writeOnboardParamsToStream(stream, _uas->getUASName());
}
void AutoPilotPlugin::readParametersFromStream(QTextStream &stream)
{
Q_ASSERT(_uas);
Fact* autoSaveFact = NULL;
int previousAutoSave = 0;
if (parameterExists("COM_AUTOS_PAR")) {
autoSaveFact = getParameterFact("COM_AUTOS_PAR");
previousAutoSave = autoSaveFact->value().toInt();
autoSaveFact->setValue(1);
}
_uas->getParamManager()->readPendingParamsFromStream(stream);
if (autoSaveFact) {
autoSaveFact->setValue(previousAutoSave);
}
}
...@@ -57,14 +57,32 @@ public: ...@@ -57,14 +57,32 @@ public:
Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT) Q_PROPERTY(QVariantList vehicleComponents READ vehicleComponents CONSTANT)
/// Re-request the full set of parameters from the autopilot /// Re-request the full set of parameters from the autopilot
Q_INVOKABLE void refreshAllParameters(void) { getParameterLoader()->refreshAllParameters(); } Q_INVOKABLE void refreshAllParameters(void);
/// Request a refresh on the specific parameter /// Request a refresh on the specific parameter
Q_INVOKABLE void refreshParameter(int componentId, const QString& name) { getParameterLoader()->refreshParameter(componentId, name); } Q_INVOKABLE void refreshParameter(int componentId, const QString& name);
/// Request a refresh on all parameters that begin with the specified prefix /// Request a refresh on all parameters that begin with the specified prefix
Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix) { getParameterLoader()->refreshParametersPrefix(componentId, namePrefix); } Q_INVOKABLE void refreshParametersPrefix(int componentId, const QString& namePrefix);
/// Returns true if the specifed parameter exists from the default component
Q_INVOKABLE bool parameterExists(const QString& name);
/// Returns all parameter names
/// FIXME: component id missing, generic to fact
QStringList parameterNames(void);
/// Returns the specified parameter Fact from the default component
/// WARNING: Will assert if fact does not exists. If that possibility exists, check for existince first with
/// factExists.
Fact* getParameterFact(const QString& name);
/// Writes the parameter facts to the specified stream
void writeParametersToStream(QTextStream &stream);
/// Reads the parameters from the stream and updates values
void readParametersFromStream(QTextStream &stream);
/// Returns true if the specifed fact exists /// Returns true if the specifed fact exists
Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider Q_INVOKABLE bool factExists(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component int componentId, ///< fact component, -1=default component
...@@ -76,21 +94,12 @@ public: ...@@ -76,21 +94,12 @@ public:
Fact* getFact(FactSystem::Provider_t provider, ///< fact provider Fact* getFact(FactSystem::Provider_t provider, ///< fact provider
int componentId, ///< fact component, -1=default component int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name const QString& name); ///< fact name
/// Returns true if the specifed parameter exists from the default component
Q_INVOKABLE bool parameterExists(const QString& name) { return getParameterLoader()->factExists(FactSystem::defaultComponentId, name); }
/// Returns the specified parameter Fact from the default component
/// WARNING: Will assert if fact does not exists. If that possibility exists, check for existince first with
/// factExists.
Fact* getParameterFact(const QString& name) { return getParameterLoader()->getFact(FactSystem::defaultComponentId, name); }
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
// Must be implemented by derived class // Must be implemented by derived class
virtual const QVariantList& vehicleComponents(void) = 0; virtual const QVariantList& vehicleComponents(void) = 0;
/// Returns the ParameterLoader
virtual ParameterLoader* getParameterLoader(void) = 0;
/// FIXME: Kind of hacky /// FIXME: Kind of hacky
static void clearStaticData(void); static void clearStaticData(void);
...@@ -106,6 +115,9 @@ protected: ...@@ -106,6 +115,9 @@ protected:
/// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin /// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { } AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
/// Returns the ParameterLoader
virtual ParameterLoader* _getParameterLoader(void) = 0;
UASInterface* _uas; UASInterface* _uas;
bool _pluginReady; bool _pluginReady;
}; };
......
...@@ -42,7 +42,6 @@ public: ...@@ -42,7 +42,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
virtual ParameterLoader* getParameterLoader(void) { return _parameterFacts; }
static QList<AutoPilotPluginManager::FullMode_t> getModes(void); static QList<AutoPilotPluginManager::FullMode_t> getModes(void);
static QString getShortModeText(uint8_t baseMode, uint32_t customMode); static QString getShortModeText(uint8_t baseMode, uint32_t customMode);
...@@ -52,6 +51,9 @@ private slots: ...@@ -52,6 +51,9 @@ private slots:
void _parametersReady(void); void _parametersReady(void);
private: private:
// Overrides from AutoPilotPlugin
virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; }
GenericParameterFacts* _parameterFacts; GenericParameterFacts* _parameterFacts;
}; };
......
...@@ -90,7 +90,6 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) : ...@@ -90,7 +90,6 @@ PX4AutoPilotPlugin::PX4AutoPilotPlugin(UASInterface* uas, QObject* parent) :
PX4AutoPilotPlugin::~PX4AutoPilotPlugin() PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
{ {
delete _parameterFacts; delete _parameterFacts;
PX4ParameterFacts::deleteParameterFactMetaData();
} }
QList<AutoPilotPluginManager::FullMode_t> PX4AutoPilotPlugin::getModes(void) QList<AutoPilotPluginManager::FullMode_t> PX4AutoPilotPlugin::getModes(void)
......
...@@ -51,7 +51,6 @@ public: ...@@ -51,7 +51,6 @@ public:
// Overrides from AutoPilotPlugin // Overrides from AutoPilotPlugin
virtual const QVariantList& vehicleComponents(void); virtual const QVariantList& vehicleComponents(void);
virtual ParameterLoader* getParameterLoader(void) { return _parameterFacts; }
static QList<AutoPilotPluginManager::FullMode_t> getModes(void); static QList<AutoPilotPluginManager::FullMode_t> getModes(void);
static QString getShortModeText(uint8_t baseMode, uint32_t customMode); static QString getShortModeText(uint8_t baseMode, uint32_t customMode);
...@@ -69,6 +68,9 @@ private slots: ...@@ -69,6 +68,9 @@ private slots:
void _pluginReadyPreChecks(void); void _pluginReadyPreChecks(void);
private: private:
// Overrides from AutoPilotPlugin
virtual ParameterLoader* _getParameterLoader(void) { return _parameterFacts; }
PX4ParameterFacts* _parameterFacts; PX4ParameterFacts* _parameterFacts;
QVariantList _components; QVariantList _components;
AirframeComponent* _airframeComponent; AirframeComponent* _airframeComponent;
......
...@@ -42,14 +42,6 @@ PX4ParameterFacts::PX4ParameterFacts(UASInterface* uas, QObject* parent) : ...@@ -42,14 +42,6 @@ PX4ParameterFacts::PX4ParameterFacts(UASInterface* uas, QObject* parent) :
Q_ASSERT(uas); Q_ASSERT(uas);
} }
void PX4ParameterFacts::deleteParameterFactMetaData(void)
{
foreach (QString param, _mapParameterName2FactMetaData.keys()) {
delete _mapParameterName2FactMetaData[param];
}
_mapParameterName2FactMetaData.clear();
}
/// Parse the Parameter element of parameter xml meta data /// Parse the Parameter element of parameter xml meta data
/// @param[in] xml stream reader /// @param[in] xml stream reader
/// @param[in] group fact group associated with this Param element /// @param[in] group fact group associated with this Param element
...@@ -69,6 +61,8 @@ FactMetaData* PX4ParameterFacts::_parseParameter(QXmlStreamReader& xml, const QS ...@@ -69,6 +61,8 @@ FactMetaData* PX4ParameterFacts::_parseParameter(QXmlStreamReader& xml, const QS
FactMetaData* metaData = new FactMetaData(); FactMetaData* metaData = new FactMetaData();
Q_CHECK_PTR(metaData); Q_CHECK_PTR(metaData);
metaData->group = group;
// Convert type from string to FactMetaData::ValueType_t // Convert type from string to FactMetaData::ValueType_t
struct String2Type { struct String2Type {
......
...@@ -52,7 +52,6 @@ public: ...@@ -52,7 +52,6 @@ public:
virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); }
static void loadParameterFactMetaData(void); static void loadParameterFactMetaData(void);
static void deleteParameterFactMetaData(void);
static void clearStaticData(void); static void clearStaticData(void);
private: private:
......
...@@ -107,7 +107,7 @@ QString Fact::shortDescription(void) ...@@ -107,7 +107,7 @@ QString Fact::shortDescription(void)
if (_metaData) { if (_metaData) {
return _metaData->shortDescription; return _metaData->shortDescription;
} else { } else {
return QString(); return QString("");
} }
} }
...@@ -116,7 +116,7 @@ QString Fact::longDescription(void) ...@@ -116,7 +116,7 @@ QString Fact::longDescription(void)
if (_metaData) { if (_metaData) {
return _metaData->longDescription; return _metaData->longDescription;
} else { } else {
return QString(); return QString("");
} }
} }
...@@ -125,7 +125,7 @@ QString Fact::units(void) ...@@ -125,7 +125,7 @@ QString Fact::units(void)
if (_metaData) { if (_metaData) {
return _metaData->units; return _metaData->units;
} else { } else {
return QString(); return QString("");
} }
} }
...@@ -141,6 +141,15 @@ QVariant Fact::max(void) ...@@ -141,6 +141,15 @@ QVariant Fact::max(void)
return _metaData->max; return _metaData->max;
} }
QString Fact::group(void)
{
if (_metaData) {
return _metaData->group;
} else {
return "Default Group";
}
}
void Fact::setMetaData(FactMetaData* metaData) void Fact::setMetaData(FactMetaData* metaData)
{ {
_metaData = metaData; _metaData = metaData;
......
...@@ -54,6 +54,7 @@ class Fact : public QObject ...@@ -54,6 +54,7 @@ class Fact : public QObject
Q_PROPERTY(QString units READ units CONSTANT) Q_PROPERTY(QString units READ units CONSTANT)
Q_PROPERTY(QVariant min READ min CONSTANT) Q_PROPERTY(QVariant min READ min CONSTANT)
Q_PROPERTY(QVariant max READ max CONSTANT) Q_PROPERTY(QVariant max READ max CONSTANT)
Q_PROPERTY(QString group READ group CONSTANT)
Q_ENUMS(FactMetaData::ValueType_t) Q_ENUMS(FactMetaData::ValueType_t)
...@@ -63,41 +64,19 @@ public: ...@@ -63,41 +64,19 @@ public:
// Property system methods // Property system methods
/// Read accessor for name property
QString name(void) const; QString name(void) const;
/// Read accessor for componentId property
int componentId(void) const; int componentId(void) const;
/// Read accessor for value property
QVariant value(void) const; QVariant value(void) const;
/// Read accessor for valueString property
QString valueString(void) const; QString valueString(void) const;
/// Write accessor for value property
void setValue(const QVariant& value); void setValue(const QVariant& value);
/// Read accesor for defaultValue property
QVariant defaultValue(void); QVariant defaultValue(void);
/// Read accesor for type property
FactMetaData::ValueType_t type(void); FactMetaData::ValueType_t type(void);
/// Read accesor for shortDescription property
QString shortDescription(void); QString shortDescription(void);
/// Read accesor for longDescription property
QString longDescription(void); QString longDescription(void);
/// Read accesor for units property
QString units(void); QString units(void);
/// Read accesor for min property
QVariant min(void); QVariant min(void);
QVariant max(void);
/// Read accesor for max property QString group(void);
QVariant max(void);
/// Sets the meta data associated with the Fact. /// Sets the meta data associated with the Fact.
void setMetaData(FactMetaData* metaData); void setMetaData(FactMetaData* metaData);
......
...@@ -51,6 +51,11 @@ QString FactBinder::name(void) const ...@@ -51,6 +51,11 @@ QString FactBinder::name(void) const
} }
} }
int FactBinder::componentId(void) const
{
return _componentId;
}
void FactBinder::setName(const QString& name) void FactBinder::setName(const QString& name)
{ {
if (_fact) { if (_fact) {
...@@ -59,13 +64,25 @@ void FactBinder::setName(const QString& name) ...@@ -59,13 +64,25 @@ void FactBinder::setName(const QString& name)
} }
if (!name.isEmpty()) { if (!name.isEmpty()) {
if (_autopilotPlugin->factExists(FactSystem::ParameterProvider, _componentId, name)) { QString parsedName = name;
_fact = _autopilotPlugin->getFact(FactSystem::ParameterProvider, _componentId, name);
// Component id + name combination?
if (name.contains(":")) {
QStringList parts = name.split(":");
if (parts.count() == 2) {
parsedName = parts[0];
_componentId = parts[1].toInt();
}
}
if (_autopilotPlugin->factExists(FactSystem::ParameterProvider, _componentId, parsedName)) {
_fact = _autopilotPlugin->getFact(FactSystem::ParameterProvider, _componentId, parsedName);
connect(_fact, &Fact::valueChanged, this, &FactBinder::valueChanged); connect(_fact, &Fact::valueChanged, this, &FactBinder::valueChanged);
emit valueChanged(); emit valueChanged();
emit nameChanged(); emit nameChanged();
} else { emit metaDataChanged();
} else {
qWarning() << "FAILED BINDING PARAM" << name << ": PARAM DOES NOT EXIST ON SYSTEM!"; qWarning() << "FAILED BINDING PARAM" << name << ": PARAM DOES NOT EXIST ON SYSTEM!";
Q_ASSERT(false); Q_ASSERT(false);
} }
...@@ -108,3 +125,66 @@ QString FactBinder::units(void) const ...@@ -108,3 +125,66 @@ QString FactBinder::units(void) const
return QString(); return QString();
} }
} }
QVariant FactBinder::defaultValue(void)
{
if (_fact) {
return _fact->defaultValue();
} else {
return QVariant(0);
}
}
FactMetaData::ValueType_t FactBinder::type(void)
{
if (_fact) {
return _fact->type();
} else {
return FactMetaData::valueTypeUint32;
}
}
QString FactBinder::shortDescription(void)
{
if (_fact) {
return _fact->shortDescription();
} else {
return QString();
}
}
QString FactBinder::longDescription(void)
{
if (_fact) {
return _fact->longDescription();
} else {
return QString();
}
}
QVariant FactBinder::min(void)
{
if (_fact) {
return _fact->min();
} else {
return QVariant(0);
}
}
QVariant FactBinder::max(void)
{
if (_fact) {
return _fact->max();
} else {
return QVariant(0);
}
}
QString FactBinder::group(void)
{
if (_fact) {
return _fact->group();
} else {
return QString();
}
}
...@@ -38,17 +38,23 @@ class FactBinder : public QObject ...@@ -38,17 +38,23 @@ class FactBinder : public QObject
{ {
Q_OBJECT Q_OBJECT
Q_PROPERTY(int componentId MEMBER _componentId NOTIFY componentIdChanged) Q_PROPERTY(int componentId READ componentId NOTIFY nameChanged)
Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged) Q_PROPERTY(QString name READ name WRITE setName NOTIFY nameChanged)
Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true) Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged) Q_PROPERTY(QVariant valueString READ valueString NOTIFY valueChanged)
Q_PROPERTY(QString units READ units CONSTANT) Q_PROPERTY(QString units READ units NOTIFY metaDataChanged)
Q_PROPERTY(QVariant defaultValue READ defaultValue NOTIFY metaDataChanged)
Q_PROPERTY(FactMetaData::ValueType_t type READ type NOTIFY metaDataChanged)
Q_PROPERTY(QString shortDescription READ shortDescription NOTIFY metaDataChanged)
Q_PROPERTY(QString longDescription READ longDescription NOTIFY metaDataChanged)
Q_PROPERTY(QVariant min READ min NOTIFY metaDataChanged)
Q_PROPERTY(QVariant max READ max NOTIFY metaDataChanged)
Q_PROPERTY(QString group READ group NOTIFY metaDataChanged)
public: public:
FactBinder(void); FactBinder(void);
int componentId(void) const; int componentId(void) const;
void setComponentId(int componentId);
QString name(void) const; QString name(void) const;
void setName(const QString& name); void setName(const QString& name);
...@@ -58,13 +64,19 @@ public: ...@@ -58,13 +64,19 @@ public:
QString valueString(void) const; QString valueString(void) const;
/// Read accesor for units property
QString units(void) const; QString units(void) const;
QVariant defaultValue(void);
FactMetaData::ValueType_t type(void);
QString shortDescription(void);
QString longDescription(void);
QVariant min(void);
QVariant max(void);
QString group(void);
signals: signals:
void componentIdChanged(void);
void nameChanged(void); void nameChanged(void);
void valueChanged(void); void valueChanged(void);
void metaDataChanged(void);
private: private:
AutoPilotPlugin* _autopilotPlugin; AutoPilotPlugin* _autopilotPlugin;
......
...@@ -57,7 +57,7 @@ public: ...@@ -57,7 +57,7 @@ public:
/// Initialize the meta data given only the type. /// Initialize the meta data given only the type.
void initFromTypeOnly(ValueType_t initType); void initFromTypeOnly(ValueType_t initType);
// FIXME: This needs to switch over to Q_PROPERTY mechanism QString group;
ValueType_t type; ValueType_t type;
QVariant defaultValue; QVariant defaultValue;
QString shortDescription; QString shortDescription;
......
...@@ -40,7 +40,7 @@ FactSystem::FactSystem(QObject* parent) : ...@@ -40,7 +40,7 @@ FactSystem::FactSystem(QObject* parent) :
QGCSingleton(parent) QGCSingleton(parent)
{ {
qmlRegisterType<FactBinder>(_factSystemQmlUri, 1, 0, "Fact"); qmlRegisterType<FactBinder>(_factSystemQmlUri, 1, 0, "Fact");
qmlRegisterUncreatableType<VehicleComponent>(_factSystemQmlUri, 1, 0, "VehicleComponent", "Can only reference VehicleComponent"); qmlRegisterUncreatableType<VehicleComponent>(_factSystemQmlUri, 1, 0, "VehicleComponent", "Can only reference, cannot create");
} }
FactSystem::~FactSystem() FactSystem::~FactSystem()
......
...@@ -37,7 +37,7 @@ Item { ...@@ -37,7 +37,7 @@ Item {
// Use specific component id // Use specific component id
TextInput { TextInput {
objectName: "testControl" objectName: "testControl"
Fact { id: fact2; name: "COMPONENT_51"; componentId: 51 } Fact { id: fact2; name: "COMPONENT_51:51" }
text: fact2.value text: fact2.value
onAccepted: { fact2.value = text; } onAccepted: { fact2.value = text; }
} }
......
...@@ -80,9 +80,6 @@ void ParameterLoader::_parameterUpdate(int uas, int componentId, QString paramet ...@@ -80,9 +80,6 @@ void ParameterLoader::_parameterUpdate(int uas, int componentId, QString paramet
} }
if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) { if (!_mapParameterName2Variant.contains(componentId) || !_mapParameterName2Variant[componentId].contains(parameterName)) {
// These should not get our of sync
Q_ASSERT(_mapParameterName2Variant.contains(componentId) == _mapFact2ParameterName.contains(componentId));
qCDebug(ParameterLoaderLog) << "Adding new fact (component:" << componentId << "name:" << parameterName << ")"; qCDebug(ParameterLoaderLog) << "Adding new fact (component:" << componentId << "name:" << parameterName << ")";
FactMetaData::ValueType_t factType; FactMetaData::ValueType_t factType;
...@@ -121,7 +118,6 @@ void ParameterLoader::_parameterUpdate(int uas, int componentId, QString paramet ...@@ -121,7 +118,6 @@ void ParameterLoader::_parameterUpdate(int uas, int componentId, QString paramet
setMetaData = true; setMetaData = true;
_mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact); _mapParameterName2Variant[componentId][parameterName] = QVariant::fromValue(fact);
_mapFact2ParameterName[componentId][fact] = parameterName;
// We need to know when the fact changes from QML so that we can send the new value to the parameter manager // We need to know when the fact changes from QML so that we can send the new value to the parameter manager
connect(fact, &Fact::_containerValueChanged, this, &ParameterLoader::_valueUpdated); connect(fact, &Fact::_containerValueChanged, this, &ParameterLoader::_valueUpdated);
...@@ -151,8 +147,6 @@ void ParameterLoader::_valueUpdated(const QVariant& value) ...@@ -151,8 +147,6 @@ void ParameterLoader::_valueUpdated(const QVariant& value)
int componentId = fact->componentId(); int componentId = fact->componentId();
Q_ASSERT(_paramMgr); Q_ASSERT(_paramMgr);
Q_ASSERT(_mapFact2ParameterName.contains(componentId));
Q_ASSERT(_mapFact2ParameterName[componentId].contains(fact));
QVariant typedValue; QVariant typedValue;
switch (fact->type()) { switch (fact->type()) {
...@@ -196,6 +190,7 @@ void ParameterLoader::_paramMgrParameterListUpToDate(void) ...@@ -196,6 +190,7 @@ void ParameterLoader::_paramMgrParameterListUpToDate(void)
qgcApp()->processEvents(); qgcApp()->processEvents();
_determineDefaultComponentId(); _determineDefaultComponentId();
_setupGroupMap();
// We should have all parameters now so we can signal ready // We should have all parameters now so we can signal ready
emit parametersReady(); emit parametersReady();
...@@ -254,7 +249,6 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na ...@@ -254,7 +249,6 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na
Q_ASSERT(_paramMgr); Q_ASSERT(_paramMgr);
componentId = _actualComponentId(componentId); componentId = _actualComponentId(componentId);
Q_ASSERT(_mapFact2ParameterName.contains(componentId));
foreach(QString name, _mapParameterName2Variant[componentId].keys()) { foreach(QString name, _mapParameterName2Variant[componentId].keys()) {
if (name.startsWith(namePrefix)) { if (name.startsWith(namePrefix)) {
refreshParameter(componentId, name); refreshParameter(componentId, name);
...@@ -262,7 +256,7 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na ...@@ -262,7 +256,7 @@ void ParameterLoader::refreshParametersPrefix(int componentId, const QString& na
} }
} }
bool ParameterLoader::factExists(int componentId, const QString& name) bool ParameterLoader::parameterExists(int componentId, const QString& name)
{ {
componentId = _actualComponentId(componentId); componentId = _actualComponentId(componentId);
if (_mapParameterName2Variant.contains(componentId)) { if (_mapParameterName2Variant.contains(componentId)) {
...@@ -280,3 +274,29 @@ Fact* ParameterLoader::getFact(int componentId, const QString& name) ...@@ -280,3 +274,29 @@ Fact* ParameterLoader::getFact(int componentId, const QString& name)
Q_ASSERT(fact); Q_ASSERT(fact);
return fact; return fact;
} }
QStringList ParameterLoader::parameterNames(void)
{
QStringList names;
foreach(QString paramName, _mapParameterName2Variant[_defaultComponentId].keys()) {
names << paramName;
}
return names;
}
void ParameterLoader::_setupGroupMap(void)
{
foreach (int componentId, _mapParameterName2Variant.keys()) {
foreach (QString name, _mapParameterName2Variant[componentId].keys()) {
Fact* fact = _mapParameterName2Variant[componentId][name].value<Fact*>();
_mapGroup2ParameterName[componentId][fact->group()] += name;
}
}
}
const QMap<int, QMap<QString, QStringList> >& ParameterLoader::getGroupMap(void)
{
return _mapGroup2ParameterName;
}
...@@ -60,16 +60,22 @@ public: ...@@ -60,16 +60,22 @@ 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);
/// Returns true if the specifed fact exists /// Returns true if the specifed parameter exists
bool factExists(int componentId, ///< fact component, -1=default component bool parameterExists(int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name const QString& name); ///< fact name
/// Returns all parameter names
/// FIXME: component id missing
QStringList parameterNames(void);
/// Returns the specified Fact. /// Returns the specified Fact.
/// WARNING: Will assert if fact does not exists. If that possibily exists, check for existince first with /// WARNING: Will assert if parameter does not exists. If that possibily exists, check for existince first with
/// factExists. /// parameterExists.
Fact* getFact(int componentId, ///< fact component, -1=default component Fact* getFact(int componentId, ///< fact component, -1=default component
const QString& name); ///< fact name const QString& name); ///< fact name
const QMap<int, QMap<QString, QStringList> >& getGroupMap(void);
/// Return the parameter for which the default component id is derived from. Return an empty /// Return the parameter for which the default component id is derived from. Return an empty
/// string is this is not available. /// string is this is not available.
virtual QString getDefaultComponentIdParam(void) const = 0; virtual QString getDefaultComponentIdParam(void) const = 0;
...@@ -92,11 +98,8 @@ private: ...@@ -92,11 +98,8 @@ private:
static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
int _actualComponentId(int componentId); int _actualComponentId(int componentId);
void _determineDefaultComponentId(void); void _determineDefaultComponentId(void);
void _setupGroupMap(void);
/// First mapping is by component id
/// Second mapping is parameter name, to Fact
QMap<int, QMap<Fact*, QString> > _mapFact2ParameterName;
int _uasId; ///< Id for uas which this set of Facts are associated with int _uasId; ///< Id for uas which this set of Facts are associated with
QGCUASParamManagerInterface* _paramMgr; QGCUASParamManagerInterface* _paramMgr;
...@@ -105,6 +108,10 @@ private: ...@@ -105,6 +108,10 @@ private:
/// Second mapping is parameter name, to Fact* in QVariant /// Second mapping is parameter name, to Fact* in QVariant
QMap<int, QVariantMap> _mapParameterName2Variant; QMap<int, QVariantMap> _mapParameterName2Variant;
/// First mapping is by component id
/// Second mapping is group name, to Fact
QMap<int, QMap<QString, QStringList> > _mapGroup2ParameterName;
bool _parametersReady; ///< All params received from param mgr bool _parametersReady; ///< All params received from param mgr
int _defaultComponentId; int _defaultComponentId;
QString _defaultComponentIdParam; QString _defaultComponentIdParam;
......
...@@ -28,7 +28,7 @@ import QtQuick.Controls.Styles 1.2 ...@@ -28,7 +28,7 @@ import QtQuick.Controls.Styles 1.2
import QGroundControl.Controls 1.0 import QGroundControl.Controls 1.0
import QGroundControl.FactControls 1.0 import QGroundControl.FactControls 1.0
import QGroundControl.Palette 1.0 import QGroundControl.Palette 1.0
import QGroundControl.FirmwareUpgradeController 1.0 import QGroundControl.Controllers 1.0
import QGroundControl.ScreenTools 1.0 import QGroundControl.ScreenTools 1.0
Rectangle { Rectangle {
......
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterEditor.h"
#include "ui_ParameterEditor.h"
ParameterEditor::ParameterEditor(UASInterface* uas, const QStringList& filterList, QWidget* parent) :
QWidget(parent),
_ui(new Ui::ParameterEditor)
{
_ui->setupUi(this);
_ui->paramTreeWidget->setFilterList(filterList);
_ui->paramTreeWidget->setUAS(uas);
_ui->paramTreeWidget->handleOnboardParameterListUpToDate();
_ui->pendingCommitsWidget->setUAS(uas);
_ui->pendingCommitsWidget->update();
}
ParameterEditor::~ParameterEditor()
{
delete _ui;
}
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009 - 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
import QtQuick 2.3
import QtQuick.Controls 1.2
import QtQuick.Controls.Styles 1.2
import QGroundControl.Controls 1.0
import QGroundControl.Palette 1.0
import QGroundControl.ScreenTools 1.0
import QGroundControl.Controllers 1.0
import QGroundControl.FactSystem 1.0
import QGroundControl.FactControls 1.0
Rectangle {
QGCPalette { id: qgcPal; colorGroupEnabled: true }
ScreenTools { id: screenTools }
ParameterEditorController { id: controller }
QGCLabel { id: charWidth; text: "X"; visible: false }
readonly property real leftMargin: 10
readonly property real rightMargin: 20
readonly property int maxParamChars: 16
color: qgcPal.window
// We use an ExclusiveGroup to maintain the visibility of a single editing control at a time
ExclusiveGroup {
id: exclusiveEditorGroup
}
Column {
anchors.fill:parent
QGCLabel {
text: "PARAMETER EDITOR"
font.pointSize: screenTools.dpiAdjustedPointSize(20)
}
Item {
height: 20
width: 5
}
Row {
spacing: 10
layoutDirection: Qt.RightToLeft
width: parent.width
QGCButton {
text: "Clear RC to Param"
onClicked: controller.clearRCToParam()
}
QGCButton {
text: "Save to file"
onClicked: controller.saveToFile()
}
QGCButton {
text: "Load from file"
onClicked: controller.loadFromFile()
}
QGCButton {
id: firstButton
text: "Refresh"
onClicked: controller.refresh()
}
QGCLabel {
width: firstButton.x - parent.spacing
wrapMode: Text.WordWrap
text: "Click a parameter value to modify. Right-click to set an RC to Param mapping. Use caution when modifying parameters here since the values are not checked for validity."
}
}
Item {
id: lastSpacer
height: 10
width: 5
}
ScrollView {
id : scrollView
width: parent.width
height: parent.height - (lastSpacer.y + lastSpacer.height)
Column {
Repeater {
model: controller.componentIds
Column {
id: componentColumn
property int componentId: parseInt(modelData)
QGCLabel {
text: "Component #: " + componentId.toString()
font.pointSize: screenTools.dpiAdjustedPointSize(qgcPal.defaultFontPointSize + 4);
}
Item {
height: 10
width: 10
}
Repeater {
model: controller.getGroupsForComponent(componentColumn.componentId)
Column {
Rectangle {
id: groupRect
color: qgcPal.windowShade
height: groupBlock.height
width: scrollView.viewport.width - rightMargin
Column {
id: groupBlock
Rectangle {
color: qgcPal.windowShadeDark
height: groupLabel.height
width: groupRect.width
QGCLabel {
id: groupLabel
height: contentHeight + 5
x: leftMargin
text: modelData
verticalAlignment: Text.AlignVCenter
font.pointSize: screenTools.dpiAdjustedPointSize(qgcPal.defaultFontPointSize + 2);
}
}
Repeater {
model: controller.getFactsForGroup(componentColumn.componentId, modelData)
Row {
spacing: 10
x: leftMargin
Fact { id: modelFact; name: modelData + ":" + componentColumn.componentId }
QGCLabel {
text: modelFact.name
width: charWidth.contentWidth * (maxParamChars + 2)
}
QGCLabel {
text: modelFact.valueString + " " + modelFact.units
width: charWidth.contentWidth * 20
height: contentHeight
MouseArea {
anchors.fill: parent
acceptedButtons: Qt.LeftButton | Qt.RightButton
onClicked: {
if (mouse.button == Qt.LeftButton) {
editor.checked = true
editor.focus = true
} else if (mouse.button == Qt.RightButton) {
controller.setRCToParam(modelData)
}
}
}
FactTextField {
id: editor
y: (parent.height - height) / 2
width: parent.width
visible: checked
focus: true
fact: modelFact
showUnits: true
onEditingFinished: checked = false
// We use an ExclusiveGroup to manage visibility
property bool checked: false
property ExclusiveGroup exclusiveGroup: exclusiveEditorGroup
onExclusiveGroupChanged: {
if (exclusiveGroup)
exclusiveGroup.bindCheckable(editor)
}
}
}
QGCLabel {
text: modelFact.shortDescription
}
} // Row - Fact value
} // Repeater - Facts
} // Column - Fact rows
} // Rectangle - Group
Item {
height: 10
width: 10
}
} // Column - Group
} // Repeater - Groups
Item {
height: 10
width: 10
}
} // Column - Component
} // Repeater - Components
} // Column - Component
} // ScrollView
} // Column - Outer
}
<?xml version="1.0" encoding="UTF-8"?>
<ui version="4.0">
<class>ParameterEditor</class>
<widget class="QWidget" name="ParameterEditor">
<property name="geometry">
<rect>
<x>0</x>
<y>0</y>
<width>750</width>
<height>600</height>
</rect>
</property>
<property name="sizePolicy">
<sizepolicy hsizetype="MinimumExpanding" vsizetype="MinimumExpanding">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>802</width>
<height>471</height>
</size>
</property>
<property name="windowTitle">
<string>Form</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_13">
<item>
<layout class="QHBoxLayout" name="horizontalLayout_3">
<item>
<widget class="QGroupBox" name="advancedConfigurationGroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>3</horstretch>
<verstretch>1</verstretch>
</sizepolicy>
</property>
<property name="title">
<string>Onboard Configuration</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_2">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<layout class="QVBoxLayout" name="verticalLayout_7">
<property name="leftMargin">
<number>0</number>
</property>
<property name="topMargin">
<number>0</number>
</property>
<property name="rightMargin">
<number>0</number>
</property>
<property name="bottomMargin">
<number>0</number>
</property>
<item>
<layout class="QVBoxLayout" name="advancedColumnLayout">
<item>
<widget class="QGCParamWidget" name="paramTreeWidget" native="true">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_5">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
<item>
<widget class="QGroupBox" name="pendingChangesGroupBox">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Preferred">
<horstretch>2</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="minimumSize">
<size>
<width>329</width>
<height>400</height>
</size>
</property>
<property name="title">
<string>Changes Pending</string>
</property>
<layout class="QVBoxLayout" name="verticalLayout_8">
<item>
<layout class="QVBoxLayout" name="verticalLayout_4" stretch="0">
<property name="spacing">
<number>-1</number>
</property>
<item>
<widget class="QGCPendingParamWidget" name="pendingCommitsWidget" native="true">
<property name="minimumSize">
<size>
<width>0</width>
<height>0</height>
</size>
</property>
<property name="autoFillBackground">
<bool>true</bool>
</property>
</widget>
</item>
</layout>
</item>
</layout>
</widget>
</item>
<item>
<spacer name="horizontalSpacer_13">
<property name="orientation">
<enum>Qt::Horizontal</enum>
</property>
<property name="sizeHint" stdset="0">
<size>
<width>10</width>
<height>20</height>
</size>
</property>
</spacer>
</item>
</layout>
</item>
<item>
<widget class="QLabel" name="advancedStatusLabel">
<property name="sizePolicy">
<sizepolicy hsizetype="Preferred" vsizetype="Fixed">
<horstretch>0</horstretch>
<verstretch>0</verstretch>
</sizepolicy>
</property>
<property name="text">
<string>Status</string>
</property>
</widget>
</item>
</layout>
</widget>
<customwidgets>
<customwidget>
<class>QGCPendingParamWidget</class>
<extends>QWidget</extends>
<header>ui/QGCPendingParamWidget.h</header>
<container>1</container>
</customwidget>
<customwidget>
<class>QGCParamWidget</class>
<extends>QWidget</extends>
<header>ui/QGCParamWidget.h</header>
<container>1</container>
</customwidget>
</customwidgets>
<resources/>
<connections/>
</ui>
/*=====================================================================
QGroundControl Open Source Ground Control Station
(c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project
QGROUNDCONTROL is free software: you can redistribute it and/or modify
it under the terms of the GNU General Public License as published by
the Free Software Foundation, either version 3 of the License, or
(at your option) any later version.
QGROUNDCONTROL is distributed in the hope that it will be useful,
but WITHOUT ANY WARRANTY; without even the implied warranty of
MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
GNU General Public License for more details.
You should have received a copy of the GNU General Public License
along with QGROUNDCONTROL. If not, see <http://www.gnu.org/licenses/>.
======================================================================*/
/// @file
/// @author Don Gagne <don@thegagnes.com>
#include "ParameterEditorController.h"
#include "UASManager.h"
#include "AutoPilotPluginManager.h"
#include "QGCFileDialog.h"
#include "QGCMessageBox.h"
#include "QGCMapRCToParamDialog.h"
#include "MainWindow.h"
/// @Brief Constructs a new ParameterEditorController Widget. This widget is used within the PX4VehicleConfig set of screens.
ParameterEditorController::ParameterEditorController(void) :
_uas(NULL),
_autopilot(NULL)
{
_uas = UASManager::instance()->getActiveUAS();
Q_ASSERT(_uas);
_autopilot = AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(_uas);
Q_ASSERT(_autopilot);
Q_ASSERT(_autopilot->pluginReady());
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
foreach (int componentId, groupMap.keys()) {
_componentIds += QString("%1").arg(componentId);
}
}
QStringList ParameterEditorController::getGroupsForComponent(int componentId)
{
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
return groupMap[componentId].keys();
}
QStringList ParameterEditorController::getFactsForGroup(int componentId, QString group)
{
const QMap<int, QMap<QString, QStringList> >& groupMap = _autopilot->getGroupMap();
return groupMap[componentId][group];
}
void ParameterEditorController::clearRCToParam(void)
{
Q_ASSERT(_uas);
_uas->unsetRCToParameterMap();
}
void ParameterEditorController::saveToFile(void)
{
Q_ASSERT(_autopilot);
QString msgTitle("Save Parameters");
QString fileName = QGCFileDialog::getSaveFileName(NULL,
msgTitle,
qgcApp()->savedParameterFilesLocation(),
"Parameter Files (*.params)",
"params",
true);
if (!fileName.isEmpty()) {
QFile file(fileName);
if (!file.open(QIODevice::WriteOnly | QIODevice::Text)) {
QGCMessageBox::critical(msgTitle, "Unable to create file");
return;
}
QTextStream stream(&file);
_autopilot->writeParametersToStream(stream);
file.close();
}
}
void ParameterEditorController::loadFromFile(void)
{
Q_ASSERT(_autopilot);
QString msgTitle("Load Parameters");
QString fileName = QGCFileDialog::getOpenFileName(NULL,
msgTitle,
qgcApp()->savedParameterFilesLocation(),
"Parameter Files (*.params);;All Files (*)");
if (!fileName.isEmpty()) {
QFile file(fileName);
if (!file.open(QIODevice::ReadOnly | QIODevice::Text)) {
QGCMessageBox::critical(msgTitle, "Unable to open file");
return;
}
QTextStream stream(&file);
_autopilot->readParametersFromStream(stream);
file.close();
}
}
void ParameterEditorController::refresh(void)
{
_autopilot->refreshAllParameters();
}
void ParameterEditorController::setRCToParam(const QString& paramName)
{
Q_ASSERT(_uas);
QGCMapRCToParamDialog * d = new QGCMapRCToParamDialog(paramName, _uas, MainWindow::instance());
d->exec();
}
...@@ -2,7 +2,7 @@ ...@@ -2,7 +2,7 @@
QGroundControl Open Source Ground Control Station QGroundControl Open Source Ground Control Station
(c) 2009 - 2014 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org> (c) 2009, 2015 QGROUNDCONTROL PROJECT <http://www.qgroundcontrol.org>
This file is part of the QGROUNDCONTROL project This file is part of the QGROUNDCONTROL project
...@@ -21,31 +21,42 @@ ...@@ -21,31 +21,42 @@
======================================================================*/ ======================================================================*/
#ifndef PARAMETEREDITOR_H
#define PARAMETEREDITOR_H
#include <QWidget>
#include "UASInterface.h"
/// @file /// @file
/// @brief This is the Parameter Editor widget which is used in the Parameters tab of Vehicle Setup.
/// @author Don Gagne <don@thegagnes.com> /// @author Don Gagne <don@thegagnes.com>
namespace Ui { #ifndef PARAMETEREDITORCONTROLLER_H
class ParameterEditor; #define PARAMETEREDITORCONTROLLER_H
}
#include <QObject>
#include <QList>
class ParameterEditor : public QWidget #include "AutoPilotPlugin.h"
#include "UASInterface.h"
class ParameterEditorController : public QObject
{ {
Q_OBJECT Q_OBJECT
public: public:
explicit ParameterEditor(UASInterface* uas, const QStringList& filterList, QWidget* parent = 0); ParameterEditorController(void);
~ParameterEditor();
Q_PROPERTY(QStringList componentIds MEMBER _componentIds CONSTANT)
Q_INVOKABLE QStringList getGroupsForComponent(int componentId);
Q_INVOKABLE QStringList getFactsForGroup(int componentId, QString group);
Q_INVOKABLE void clearRCToParam(void);
Q_INVOKABLE void saveToFile(void);
Q_INVOKABLE void loadFromFile(void);
Q_INVOKABLE void refresh(void);
Q_INVOKABLE void setRCToParam(const QString& paramName);
QList<QObject*> model(void);
private: private:
Ui::ParameterEditor* _ui; UASInterface* _uas;
AutoPilotPlugin* _autopilot;
QStringList _componentIds;
}; };
#endif #endif
...@@ -30,11 +30,11 @@ ...@@ -30,11 +30,11 @@
#include "UASManager.h" #include "UASManager.h"
#include "AutoPilotPluginManager.h" #include "AutoPilotPluginManager.h"
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "ParameterEditor.h"
#include "QGCQmlWidgetHolder.h" #include "QGCQmlWidgetHolder.h"
#include "MainWindow.h" #include "MainWindow.h"
#include "QGCMessageBox.h" #include "QGCMessageBox.h"
#include "FirmwareUpgradeController.h" #include "FirmwareUpgradeController.h"
#include "ParameterEditorController.h"
#include <QQmlError> #include <QQmlError>
#include <QQmlContext> #include <QQmlContext>
...@@ -54,8 +54,9 @@ SetupView::SetupView(QWidget* parent) : ...@@ -54,8 +54,9 @@ SetupView::SetupView(QWidget* parent) :
Q_UNUSED(fSucceeded); Q_UNUSED(fSucceeded);
Q_ASSERT(fSucceeded); Q_ASSERT(fSucceeded);
qmlRegisterType<FirmwareUpgradeController>("QGroundControl.FirmwareUpgradeController", 1, 0, "FirmwareUpgradeController"); qmlRegisterType<FirmwareUpgradeController>("QGroundControl.Controllers", 1, 0, "FirmwareUpgradeController");
qmlRegisterType<ParameterEditorController>("QGroundControl.Controllers", 1, 0, "ParameterEditorController");
_ui->buttonHolder->rootContext()->setContextProperty("controller", this); _ui->buttonHolder->rootContext()->setContextProperty("controller", this);
_ui->buttonHolder->setAutoPilot(NULL); _ui->buttonHolder->setAutoPilot(NULL);
_ui->buttonHolder->setSource(QUrl::fromUserInput("qrc:/qml/SetupViewButtonsDisconnected.qml")); _ui->buttonHolder->setSource(QUrl::fromUserInput("qrc:/qml/SetupViewButtonsDisconnected.qml"));
...@@ -131,8 +132,14 @@ void SetupView::firmwareButtonClicked(void) ...@@ -131,8 +132,14 @@ void SetupView::firmwareButtonClicked(void)
void SetupView::parametersButtonClicked(void) void SetupView::parametersButtonClicked(void)
{ {
ParameterEditor* setup = new ParameterEditor(_uasCurrent, QStringList(), this); QGCQmlWidgetHolder* setup = new QGCQmlWidgetHolder;
_changeSetupWidget(setup); Q_CHECK_PTR(setup);
Q_ASSERT(_autoPilotPlugin);
setup->setAutoPilot(_autoPilotPlugin);
setup->setSource(QUrl::fromUserInput("qrc:/qml/ParameterEditor.qml"));
_changeSetupWidget(setup);
} }
void SetupView::summaryButtonClicked(void) void SetupView::summaryButtonClicked(void)
......
...@@ -25,7 +25,6 @@ ...@@ -25,7 +25,6 @@
#define SETUPVIEW_H #define SETUPVIEW_H
#include "UASInterface.h" #include "UASInterface.h"
#include "ParameterEditor.h"
#include "VehicleComponent.h" #include "VehicleComponent.h"
#include "AutoPilotPlugin.h" #include "AutoPilotPlugin.h"
......
...@@ -166,7 +166,7 @@ void MockLink::_run50HzTasks(void) ...@@ -166,7 +166,7 @@ void MockLink::_run50HzTasks(void)
void MockLink::_loadParams(void) void MockLink::_loadParams(void)
{ {
QFile paramFile(":/unittest/MockLink.param"); QFile paramFile(":/unittest/MockLink.params");
bool success = paramFile.open(QFile::ReadOnly); bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success); Q_UNUSED(success);
......
...@@ -58,7 +58,7 @@ void MockQGCUASParamManager::setParameter(int component, QString parameterName, ...@@ -58,7 +58,7 @@ void MockQGCUASParamManager::setParameter(int component, QString parameterName,
void MockQGCUASParamManager::_loadParams(void) void MockQGCUASParamManager::_loadParams(void)
{ {
QFile paramFile(":/unittest/MockLink.param"); QFile paramFile(":/unittest/MockLink.params");
bool success = paramFile.open(QFile::ReadOnly); bool success = paramFile.open(QFile::ReadOnly);
Q_UNUSED(success); Q_UNUSED(success);
......
...@@ -392,7 +392,7 @@ void PX4RCCalibrationTest::_switchSelectAutoStep(const char* functionStr, PX4RCC ...@@ -392,7 +392,7 @@ void PX4RCCalibrationTest::_switchSelectAutoStep(const char* functionStr, PX4RCC
void PX4RCCalibrationTest::_fullCalibration_test(void) void PX4RCCalibrationTest::_fullCalibration_test(void)
{ {
// IMPORTANT NOTE: We used channels 1-5 for attitude mapping in the test below. // IMPORTANT NOTE: We used channels 1-5 for attitude mapping in the test below.
// MockLink.param file cannot have flight mode switches mapped to those channels. // MockLink.params file cannot have flight mode switches mapped to those channels.
// If it does it will cause errors since the stick will not be detetected where // If it does it will cause errors since the stick will not be detetected where
MockQGCUASParamManager* paramMgr = _mockUAS->getMockQGCUASParamManager(); MockQGCUASParamManager* paramMgr = _mockUAS->getMockQGCUASParamManager();
......
...@@ -21,9 +21,6 @@ QGCUASParamManager* QGCUASParamManager::initWithUAS(UASInterface* uas) ...@@ -21,9 +21,6 @@ QGCUASParamManager* QGCUASParamManager::initWithUAS(UASInterface* uas)
{ {
mav = uas; mav = uas;
// Load default values and tooltips for data model
loadParamMetaInfoCSV();
paramDataModel.setUASID(mav->getUASID()); paramDataModel.setUASID(mav->getUASID());
paramCommsMgr.initWithUAS(uas); paramCommsMgr.initWithUAS(uas);
...@@ -143,30 +140,6 @@ void QGCUASParamManager::setPendingParam(int compId, const QString& paramName, ...@@ -143,30 +140,6 @@ void QGCUASParamManager::setPendingParam(int compId, const QString& paramName,
void QGCUASParamManager::loadParamMetaInfoCSV()
{
// Load default values and tooltips
QString autopilot(mav->getAutopilotTypeName());
QDir appDir = QApplication::applicationDirPath();
appDir.cd("files");
QString fileName = QString("%1/%2/parameter_tooltips/tooltips.txt").arg(appDir.canonicalPath()).arg(autopilot.toLower());
QFile paramMetaFile(fileName);
qDebug() << "loadParamMetaInfoCSV for autopilot: " << autopilot << " from file: " << fileName;
if (!paramMetaFile.open(QIODevice::ReadOnly | QIODevice::Text)) {
qDebug() << "loadParamMetaInfoCSV couldn't open:" << fileName;
return;
}
QTextStream in(&paramMetaFile);
paramDataModel.loadParamMetaInfoFromStream(in);
paramMetaFile.close();
}
UASInterface* QGCUASParamManager::getUAS() UASInterface* QGCUASParamManager::getUAS()
{ {
return mav; return mav;
......
...@@ -65,10 +65,6 @@ public: ...@@ -65,10 +65,6 @@ public:
virtual bool parametersReady(void) { return _parametersReady; } virtual bool parametersReady(void) { return _parametersReady; }
protected: protected:
/** @brief Load parameter meta information from appropriate CSV file */
virtual void loadParamMetaInfoCSV();
void connectToModelAndComms(); void connectToModelAndComms();
......
...@@ -394,6 +394,7 @@ void UASParameterCommsMgr::updateSilenceTimer() ...@@ -394,6 +394,7 @@ void UASParameterCommsMgr::updateSilenceTimer()
else { else {
//all parameters have been received, broadcast to UI //all parameters have been received, broadcast to UI
qCDebug(UASParameterCommsMgrLog) << "emitting parameterListUpToDate"; qCDebug(UASParameterCommsMgrLog) << "emitting parameterListUpToDate";
emit parameterListProgress(0.0f);
emit parameterListUpToDate(); emit parameterListUpToDate();
resetAfterListReceive(); resetAfterListReceive();
emit _stopSilenceTimer(); // Stop timer on our thread; emit _stopSilenceTimer(); // Stop timer on our thread;
......
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