diff --git a/QGCSetup.pri b/QGCSetup.pri
index 9ca615b..76db02a 100644
--- a/QGCSetup.pri
+++ b/QGCSetup.pri
@@ -175,6 +175,7 @@ WindowsBuild {
$$DLL_DIR\\Qt5PrintSupport$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Qml$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Quick$${DLL_QT_DEBUGCHAR}.dll \
+ $$DLL_DIR\\Qt5QuickWidgets$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5Sensors$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5SerialPort$${DLL_QT_DEBUGCHAR}.dll \
$$DLL_DIR\\Qt5OpenGL$${DLL_QT_DEBUGCHAR}.dll \
diff --git a/files/qml/FactTextInput.qml b/files/qml/FactTextInput.qml
new file mode 100644
index 0000000..560ff0d
--- /dev/null
+++ b/files/qml/FactTextInput.qml
@@ -0,0 +1,13 @@
+import QtQuick 2.0
+import QtQuick.Controls 1.2
+import QGroundControl.FactSystem 1.0
+
+TextInput {
+ property Fact fact
+ text: fact.value
+ font.family: "Helvetica"
+ font.pointSize: 24
+ color: "red"
+ focus: true
+ onAccepted: { fact.value = text; }
+}
diff --git a/files/qml/qmldir b/files/qml/qmldir
new file mode 100644
index 0000000..3450add
--- /dev/null
+++ b/files/qml/qmldir
@@ -0,0 +1,2 @@
+Module QGroundControl.FactControls
+FactTextInput 1.0 FactTextInput.qml
\ No newline at end of file
diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro
index 7d3cab5..4db5dd4 100644
--- a/qgroundcontrol.pro
+++ b/qgroundcontrol.pro
@@ -111,7 +111,8 @@ QT += network \
serialport \
sql \
printsupport \
- quick
+ quick \
+ quickwidgets
!contains(DEFINES, DISABLE_GOOGLE_EARTH) {
QT += webkit webkitwidgets
@@ -479,7 +480,8 @@ HEADERS += \
src/QGCFileDialog.h \
src/QGCMessageBox.h \
src/QGCComboBox.h \
- src/QGCTemporaryFile.h
+ src/QGCTemporaryFile.h \
+ src/QGCQuickWidget.h
SOURCES += \
src/main.cc \
@@ -618,8 +620,8 @@ SOURCES += \
src/uas/QGXPX4UAS.cc \
src/QGCFileDialog.cc \
src/QGCComboBox.cc \
- src/QGCTemporaryFile.cc
-
+ src/QGCTemporaryFile.cc \
+ src/QGCQuickWidget.cc
#
# Unit Test specific configuration goes here
@@ -709,7 +711,8 @@ HEADERS+= \
src/AutoPilotPlugins/PX4/FlightModesComponent.h \
src/AutoPilotPlugins/PX4/FlightModeConfig.h \
src/AutoPilotPlugins/PX4/AirframeComponent.h \
- src/AutoPilotPlugins/PX4/SensorsComponent.h
+ src/AutoPilotPlugins/PX4/SensorsComponent.h \
+ src/AutoPilotPlugins/PX4/PX4ParameterFacts.h \
SOURCES += \
src/VehicleSetup/SetupView.cc \
@@ -724,4 +727,22 @@ SOURCES += \
src/AutoPilotPlugins/PX4/FlightModesComponent.cc \
src/AutoPilotPlugins/PX4/FlightModeConfig.cc \
src/AutoPilotPlugins/PX4/AirframeComponent.cc \
- src/AutoPilotPlugins/PX4/SensorsComponent.cc
+ src/AutoPilotPlugins/PX4/SensorsComponent.cc \
+ src/AutoPilotPlugins/PX4/PX4ParameterFacts.cc \
+
+# Fact System code
+
+INCLUDEPATH += \
+ src/FactSystem
+
+HEADERS += \
+ src/FactSystem/FactSystem.h \
+ src/FactSystem/Fact.h \
+ src/FactSystem/FactMetaData.h \
+ src/FactSystem/FactValidator.h \
+
+SOURCES += \
+ src/FactSystem/FactSystem.cc \
+ src/FactSystem/Fact.cc \
+ src/FactSystem/FactMetaData.cc \
+ src/FactSystem/FactValidator.cc \
diff --git a/qgroundcontrol.qrc b/qgroundcontrol.qrc
index d1ba57b..30f19bf 100644
--- a/qgroundcontrol.qrc
+++ b/qgroundcontrol.qrc
@@ -234,4 +234,11 @@
files/QLoggingCategory/qtlogging.ini
+
+ files/qml/qmldir
+ files/qml/FactTextInput.qml
+
+
+ src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
+
diff --git a/src/AutoPilotPlugins/AutoPilotPlugin.h b/src/AutoPilotPlugins/AutoPilotPlugin.h
index 1c7532f..9fe0bb9 100644
--- a/src/AutoPilotPlugins/AutoPilotPlugin.h
+++ b/src/AutoPilotPlugins/AutoPilotPlugin.h
@@ -27,9 +27,11 @@
#include
#include
#include
+#include
#include "UASInterface.h"
#include "VehicleComponent.h"
+#include "FactSystem.h"
/// @file
/// @brief The AutoPilotPlugin class is an abstract base class which represent the methods and objects
@@ -57,6 +59,9 @@ public:
/// @brief Returns a human readable short description for the specified mode.
virtual QString getShortModeText(uint8_t baseMode, uint32_t customMode) const = 0;
+ /// @brief Adds the FactSystem properties associated with this AutoPilot to the Qml context.
+ virtual void addFactsToQmlContext(QQmlContext* context, UASInterface* uas) const = 0;
+
protected:
// All access to AutoPilotPugin objects is through getInstanceForAutoPilotPlugin
AutoPilotPlugin(QObject* parent = NULL) : QObject(parent) { }
diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
index 65f2ada..5170edc 100644
--- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
+++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.cc
@@ -85,3 +85,11 @@ QString GenericAutoPilotPlugin::getShortModeText(uint8_t baseMode, uint32_t cust
return mode;
}
+void GenericAutoPilotPlugin::addFactsToQmlContext(QQmlContext* context, UASInterface* uas) const
+{
+ Q_UNUSED(context);
+ Q_UNUSED(uas);
+
+ // Qml not yet supported for Generic
+ Q_ASSERT(false);
+}
diff --git a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h
index 1e16d0b..e151373 100644
--- a/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h
+++ b/src/AutoPilotPlugins/Generic/GenericAutoPilotPlugin.h
@@ -38,9 +38,11 @@ class GenericAutoPilotPlugin : public AutoPilotPlugin
public:
GenericAutoPilotPlugin(QObject* parent = NULL);
+ // Overrides from AutoPilotPlugin
virtual QList getVehicleComponents(UASInterface* uas) const ;
virtual QList getModes(void) const;
virtual QString getShortModeText(uint8_t baseMode, uint32_t customMode) const;
+ virtual void addFactsToQmlContext(QQmlContext* context, UASInterface* uas) const;
};
#endif
diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc
index 0cd5363..b8dd70c 100644
--- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc
+++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.cc
@@ -27,6 +27,9 @@
#include "SensorsComponent.h"
#include "FlightModesComponent.h"
#include "AutoPilotPluginManager.h"
+#include "UASManager.h"
+#include "QGCUASParamManagerInterface.h"
+#include "PX4ParameterFacts.h"
/// @file
/// @brief This is the AutoPilotPlugin implementatin for the MAV_AUTOPILOT_PX4 type.
@@ -65,7 +68,24 @@ union px4_custom_mode {
PX4AutoPilotPlugin::PX4AutoPilotPlugin(QObject* parent) :
AutoPilotPlugin(parent)
{
+ UASManagerInterface* uasMgr = UASManager::instance();
+ Q_ASSERT(uasMgr);
+ // We need to track uas coming and going so that we can create PX4ParameterFacts instances for each uas
+ connect(uasMgr, &UASManagerInterface::UASCreated, this, &PX4AutoPilotPlugin::_uasCreated);
+ connect(uasMgr, &UASManagerInterface::UASDeleted, this, &PX4AutoPilotPlugin::_uasDeleted);
+
+ PX4ParameterFacts::loadParameterFactMetaData();
+}
+
+PX4AutoPilotPlugin::~PX4AutoPilotPlugin()
+{
+ PX4ParameterFacts::deleteParameterFactMetaData();
+
+ foreach(UASInterface* uas, _mapUas2ParameterFacts.keys()) {
+ delete _mapUas2ParameterFacts[uas];
+ }
+ _mapUas2ParameterFacts.clear();
}
QList PX4AutoPilotPlugin::getVehicleComponents(UASInterface* uas) const
@@ -172,3 +192,46 @@ QString PX4AutoPilotPlugin::getShortModeText(uint8_t baseMode, uint32_t customMo
return mode;
}
+
+void PX4AutoPilotPlugin::addFactsToQmlContext(QQmlContext* context, UASInterface* uas) const
+{
+ Q_ASSERT(context);
+ Q_ASSERT(uas);
+
+ QGCUASParamManagerInterface* paramMgr = uas->getParamManager();
+ Q_UNUSED(paramMgr);
+ Q_ASSERT(paramMgr);
+ Q_ASSERT(paramMgr->parametersReady());
+
+ PX4ParameterFacts* facts = _parameterFactsForUas(uas);
+ Q_ASSERT(facts);
+
+ context->setContextProperty("parameterFacts", facts);
+}
+
+/// @brief When a new uas is create we add a new set of parameter facts for it
+void PX4AutoPilotPlugin::_uasCreated(UASInterface* uas)
+{
+ Q_ASSERT(uas);
+ Q_ASSERT(!_mapUas2ParameterFacts.contains(uas));
+
+ // Each uas has it's own set of parameter facts
+ PX4ParameterFacts* facts = new PX4ParameterFacts(uas, this);
+ Q_CHECK_PTR(facts);
+ _mapUas2ParameterFacts[uas] = facts;
+}
+
+/// @brief When the uas is deleted we remove the parameter facts for it from the system
+void PX4AutoPilotPlugin::_uasDeleted(UASInterface* uas)
+{
+ delete _parameterFactsForUas(uas);
+ _mapUas2ParameterFacts.remove(uas);
+}
+
+PX4ParameterFacts* PX4AutoPilotPlugin::_parameterFactsForUas(UASInterface* uas) const
+{
+ Q_ASSERT(uas);
+ Q_ASSERT(_mapUas2ParameterFacts.contains(uas));
+
+ return _mapUas2ParameterFacts[uas];
+}
diff --git a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h
index df7ae18..1b9a067 100644
--- a/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h
+++ b/src/AutoPilotPlugins/PX4/PX4AutoPilotPlugin.h
@@ -25,6 +25,8 @@
#define PX4AUTOPILOT_H
#include "AutoPilotPlugin.h"
+#include "UASInterface.h"
+#include "PX4ParameterFacts.h"
/// @file
/// @brief This is the PX4 specific implementation of the AutoPilot class.
@@ -36,10 +38,22 @@ class PX4AutoPilotPlugin : public AutoPilotPlugin
public:
PX4AutoPilotPlugin(QObject* parent);
-
+ ~PX4AutoPilotPlugin();
+
+ // Overrides from AutoPilotPlugin
virtual QList getVehicleComponents(UASInterface* uas) const ;
virtual QList getModes(void) const;
virtual QString getShortModeText(uint8_t baseMode, uint32_t customMode) const;
+ virtual void addFactsToQmlContext(QQmlContext* context, UASInterface* uas) const;
+
+private slots:
+ void _uasCreated(UASInterface* uas);
+ void _uasDeleted(UASInterface* uas);
+
+private:
+ PX4ParameterFacts* _parameterFactsForUas(UASInterface* uas) const;
+
+ QMap _mapUas2ParameterFacts;
};
#endif
diff --git a/src/AutoPilotPlugins/PX4/PX4ParameterFacts.cc b/src/AutoPilotPlugins/PX4/PX4ParameterFacts.cc
new file mode 100644
index 0000000..fe9b023
--- /dev/null
+++ b/src/AutoPilotPlugins/PX4/PX4ParameterFacts.cc
@@ -0,0 +1,349 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#include "PX4ParameterFacts.h"
+
+#include
+#include
+
+Q_LOGGING_CATEGORY(PX4ParameterFactsLog, "PX4ParameterFactsLog")
+Q_LOGGING_CATEGORY(PX4ParameterFactsMetaDataLog, "PX4ParameterFactsMetaDataLog")
+
+QMap PX4ParameterFacts::_mapParameterName2FactMetaData;
+
+PX4ParameterFacts::PX4ParameterFacts(UASInterface* uas, QObject* parent) :
+ QObject(parent),
+ _lastSeenComponent(-1),
+ _paramMgr(NULL)
+{
+ Q_ASSERT(uas);
+
+ _uasId = uas->getUASID();
+
+ _paramMgr = uas->getParamManager();
+ Q_ASSERT(_paramMgr);
+
+ // UASInterface::parameterChanged has multiple overrides so we need to use SIGNAL/SLOT style connect
+ connect(uas, SIGNAL(parameterChanged(int, int, QString, QVariant)), this, SLOT(_parameterChanged(int, int, QString, QVariant)));
+
+ // Fact meta data should already be loaded
+ Q_ASSERT(_mapParameterName2FactMetaData.count() != 0);
+}
+
+PX4ParameterFacts::~PX4ParameterFacts()
+{
+ foreach(Fact* fact, _mapFact2ParameterName.keys()) {
+ delete fact;
+ }
+ _mapParameterName2Fact.clear();
+ _mapFact2ParameterName.clear();
+}
+
+void PX4ParameterFacts::deleteParameterFactMetaData(void)
+{
+ foreach (QString param, _mapParameterName2FactMetaData.keys()) {
+ delete _mapParameterName2FactMetaData[param];
+ }
+ _mapParameterName2FactMetaData.clear();
+}
+
+/// Connected to QGCUASParmManager::parameterChanged
+///
+/// When a new parameter is seen it is added to the system. If the parameter is already known it is updated.
+void PX4ParameterFacts::_parameterChanged(int uas, int component, QString parameterName, QVariant value)
+{
+ // Is this for our uas?
+ if (uas != _uasId) {
+ return;
+ }
+
+ if (_lastSeenComponent == -1) {
+ _lastSeenComponent = component;
+ } else {
+ // Code cannot handle parameters coming form different components yets
+ Q_ASSERT(component == _lastSeenComponent);
+ }
+
+ // If we don't have meta data for the parameter it can't be part of the FactSystem
+ if (!_mapParameterName2FactMetaData.contains(parameterName)) {
+ // FIXME: Debug or Warning. Warning will fail TC
+ qCDebug(PX4ParameterFactsLog) << "FactSystem meta data out of date. Missing parameter:" << parameterName;
+ return;
+ }
+
+ if (!_mapParameterName2Fact.contains(parameterName)) {
+ Fact* fact = new Fact(this);
+
+ fact->setMetaData(_mapParameterName2FactMetaData[parameterName]);
+
+ // We need to know when the fact changes so that we can send the new value to the parameter managers
+ connect(fact, &Fact::valueUpdated, this, &PX4ParameterFacts::_valueUpdated);
+
+ _mapParameterName2Fact[parameterName] = fact;
+ _mapFact2ParameterName[fact] = parameterName;
+ }
+ _mapParameterName2Fact[parameterName]->updateValue(value);
+}
+
+/// Connected to Fact::valueUpdated
+///
+/// Sets the new value into the Parameter Manager. Paramter is persisted after send.
+void PX4ParameterFacts::_valueUpdated(QVariant& value)
+{
+ Fact* fact = qobject_cast(sender());
+ Q_ASSERT(fact);
+
+ Q_ASSERT(_lastSeenComponent != -1);
+ Q_ASSERT(_paramMgr);
+ Q_ASSERT(_mapFact2ParameterName.contains(fact));
+
+ QVariant typedValue;
+ switch (fact->type()) {
+ case FactMetaData::valueTypeInt8:
+ case FactMetaData::valueTypeInt16:
+ case FactMetaData::valueTypeInt32:
+ typedValue = QVariant(value.value());
+
+ case FactMetaData::valueTypeUint8:
+ case FactMetaData::valueTypeUint16:
+ case FactMetaData::valueTypeUint32:
+ typedValue = QVariant(value.value());
+ break;
+
+ case FactMetaData::valueTypeFloat:
+ typedValue = QVariant(value.toFloat());
+ break;
+
+ case FactMetaData::valueTypeDouble:
+ typedValue = QVariant(value.toDouble());
+ break;
+ }
+
+ _paramMgr->setParameter(_lastSeenComponent, _mapFact2ParameterName[fact], typedValue);
+ _paramMgr->sendPendingParameters(true /* persistAfterSend */, false /* forceSend */);
+}
+
+/// Parse the Parameter element of parameter xml meta data
+/// @param[in] xml stream reader
+/// @param[in] group fact group associated with this Param element
+/// @return Returns the meta data object for this parameter
+FactMetaData* PX4ParameterFacts::_parseParameter(QXmlStreamReader& xml, const QString& group)
+{
+ Q_UNUSED(group);
+
+ QString name = xml.attributes().value("name").toString();
+ QString type = xml.attributes().value("type").toString();
+
+ qCDebug(PX4ParameterFactsMetaDataLog) << "Parsed parameter: " << name << type;
+
+ Q_ASSERT(!name.isEmpty());
+ Q_ASSERT(!type.isEmpty());
+
+ FactMetaData* metaData = new FactMetaData();
+ Q_CHECK_PTR(metaData);
+
+ // Convert type from string to FactMetaData::ValueType_t
+
+ struct String2Type {
+ const char* strType;
+ FactMetaData::ValueType_t type;
+ };
+
+ static const struct String2Type rgString2Type[] = {
+ { "FLOAT", FactMetaData::valueTypeFloat },
+ { "INT32", FactMetaData::valueTypeInt32 },
+ };
+ static const size_t crgString2Type = sizeof(rgString2Type) / sizeof(rgString2Type[0]);
+
+ bool found = false;
+ for (size_t i=0; istrType) {
+ found = true;
+ metaData->type = info->type;
+ break;
+ }
+ }
+ Q_UNUSED(found);
+ Q_ASSERT(found);
+
+ _initMetaData(metaData);
+
+ // FIXME: Change to change the parameter build scheme in Firmware to get rid of ifdef dup problem
+ if (!_mapParameterName2FactMetaData.contains(name)) {
+ _mapParameterName2FactMetaData[name] = metaData;
+ }
+
+ return metaData;
+}
+
+/// This will fill in missing meta data such as range info
+void PX4ParameterFacts::_initMetaData(FactMetaData* metaData)
+{
+ switch (metaData->type) {
+ case FactMetaData::valueTypeUint8:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeInt8:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeUint16:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeInt16:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeUint32:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeInt32:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeFloat:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ case FactMetaData::valueTypeDouble:
+ metaData->min = QVariant(std::numeric_limits::min());
+ metaData->max = QVariant(std::numeric_limits::max());
+ break;
+ }
+}
+
+/// Converts a string to a typed QVariant
+/// @param type Type for Fact which dictates the QVariant type as well
+/// @param failOk - true: Don't assert if convert fails
+/// @return Returns the correctly type QVariant
+QVariant PX4ParameterFacts::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk)
+{
+ QVariant var(string);
+ bool convertOk;
+
+ Q_UNUSED(convertOk);
+
+ switch (type) {
+ case FactMetaData::valueTypeUint8:
+ case FactMetaData::valueTypeUint16:
+ case FactMetaData::valueTypeUint32:
+ convertOk = var.convert(QVariant::UInt);
+ if (!failOk) {
+ Q_ASSERT(convertOk);
+ }
+ break;
+ case FactMetaData::valueTypeInt8:
+ case FactMetaData::valueTypeInt16:
+ case FactMetaData::valueTypeInt32:
+ convertOk = var.convert(QVariant::Int);
+ if (!failOk) {
+ Q_ASSERT(convertOk);
+ }
+ break;
+ case FactMetaData::valueTypeFloat:
+ case FactMetaData::valueTypeDouble:
+ convertOk = var.convert(QVariant::Double);
+ if (!failOk) {
+ Q_ASSERT(convertOk);
+ }
+ break;
+ }
+
+ return var;
+}
+
+/// Load Parameter Fact meta data
+///
+/// The meta data comes from firmware parameters.xml file.
+void PX4ParameterFacts::loadParameterFactMetaData(void)
+{
+ qCDebug(PX4ParameterFactsMetaDataLog) << "Loading PX4 parameter fact meta data";
+
+ Q_ASSERT(_mapParameterName2FactMetaData.count() == 0);
+
+ QFile xmlFile(":/AutoPilotPlugins/PX4/ParameterFactMetaData.xml");
+
+ Q_ASSERT(xmlFile.exists());
+
+ bool success = xmlFile.open(QIODevice::ReadOnly);
+ Q_UNUSED(success);
+ Q_ASSERT(success);
+
+ QXmlStreamReader xml(xmlFile.readAll());
+ xmlFile.close();
+
+ QString factGroup;
+ FactMetaData* metaData = NULL;
+
+ while (!xml.atEnd()) {
+ if (xml.isStartElement()) {
+ QString elementName = xml.name().toString();
+ if (elementName == "parameters") {
+ // Just move to next state
+ } else if (elementName == "group") {
+ factGroup = xml.attributes().value("name").toString();
+ qCDebug(PX4ParameterFactsLog) << "Found group: " << factGroup;
+ } else if (elementName == "parameter") {
+ metaData = _parseParameter(xml, factGroup);
+ } else if (elementName == "short_desc") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ metaData->shortDescription = text;
+ } else if (elementName == "long_desc") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ metaData->longDescription = text;
+ } else if (elementName == "default") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ // FIXME: failOk=true Is a hack to handle enum values in default value. Need
+ // to implement enums in the meta data.
+ metaData->defaultValue = _stringToTypedVariant(text, metaData->type, true /* failOk */);
+ } else if (elementName == "min") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ metaData->min = _stringToTypedVariant(text, metaData->type);
+ } else if (elementName == "max") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ metaData->max = _stringToTypedVariant(text, metaData->type);
+ metaData->shortDescription = text;
+ } else if (elementName == "unit") {
+ Q_ASSERT(metaData);
+ QString text = xml.readElementText();
+ metaData->units = text;
+ }
+ } else if (xml.isEndElement() && xml.name() == "parameter") {
+ metaData = NULL;
+ }
+ xml.readNext();
+ }
+}
diff --git a/src/AutoPilotPlugins/PX4/PX4ParameterFacts.h b/src/AutoPilotPlugins/PX4/PX4ParameterFacts.h
new file mode 100644
index 0000000..67deb98
--- /dev/null
+++ b/src/AutoPilotPlugins/PX4/PX4ParameterFacts.h
@@ -0,0 +1,523 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+#ifndef PX4ParameterFacts_h
+#define PX4ParameterFacts_h
+
+#include
+#include
+#include
+#include
+
+#include "Fact.h"
+#include "UASInterface.h"
+
+/// @file
+/// @author Don Gagne
+
+// FIXME: This file should be auto-generated from the Parameter XML file.
+
+Q_DECLARE_LOGGING_CATEGORY(PX4ParameterFactsLog)
+Q_DECLARE_LOGGING_CATEGORY(PX4ParameterFactsMetaDataLog)
+
+/// Collection of Parameter Facts for PX4 AutoPilot
+///
+/// These Facts are available for binding within QML code. For example:
+/// @code{.unparsed}
+/// TextInput {
+/// text: parameterFacts.RC_MAP_THROTTLE.value
+/// }
+/// @endcode
+
+class PX4ParameterFacts : public QObject
+{
+ Q_OBJECT
+
+ Q_PROPERTY(Fact* ATT_ACC_COMP READ getATT_ACC_COMP CONSTANT) Fact* getATT_ACC_COMP(void) { return _mapParameterName2Fact["ATT_ACC_COMP"]; }
+ Q_PROPERTY(Fact* ATT_MAG_DECL READ getATT_MAG_DECL CONSTANT) Fact* getATT_MAG_DECL(void) { return _mapParameterName2Fact["ATT_MAG_DECL"]; }
+ Q_PROPERTY(Fact* BAT_CAPACITY READ getBAT_CAPACITY CONSTANT) Fact* getBAT_CAPACITY(void) { return _mapParameterName2Fact["BAT_CAPACITY"]; }
+ Q_PROPERTY(Fact* BAT_C_SCALING READ getBAT_C_SCALING CONSTANT) Fact* getBAT_C_SCALING(void) { return _mapParameterName2Fact["BAT_C_SCALING"]; }
+ Q_PROPERTY(Fact* BAT_N_CELLS READ getBAT_N_CELLS CONSTANT) Fact* getBAT_N_CELLS(void) { return _mapParameterName2Fact["BAT_N_CELLS"]; }
+ Q_PROPERTY(Fact* BAT_V_CHARGED READ getBAT_V_CHARGED CONSTANT) Fact* getBAT_V_CHARGED(void) { return _mapParameterName2Fact["BAT_V_CHARGED"]; }
+ Q_PROPERTY(Fact* BAT_V_EMPTY READ getBAT_V_EMPTY CONSTANT) Fact* getBAT_V_EMPTY(void) { return _mapParameterName2Fact["BAT_V_EMPTY"]; }
+ Q_PROPERTY(Fact* BAT_V_LOAD_DROP READ getBAT_V_LOAD_DROP CONSTANT) Fact* getBAT_V_LOAD_DROP(void) { return _mapParameterName2Fact["BAT_V_LOAD_DROP"]; }
+ Q_PROPERTY(Fact* BAT_V_SCALE_IO READ getBAT_V_SCALE_IO CONSTANT) Fact* getBAT_V_SCALE_IO(void) { return _mapParameterName2Fact["BAT_V_SCALE_IO"]; }
+ Q_PROPERTY(Fact* BAT_V_SCALING READ getBAT_V_SCALING CONSTANT) Fact* getBAT_V_SCALING(void) { return _mapParameterName2Fact["BAT_V_SCALING"]; }
+ Q_PROPERTY(Fact* BD_GPROPERTIES READ getBD_GPROPERTIES CONSTANT) Fact* getBD_GPROPERTIES(void) { return _mapParameterName2Fact["BD_GPROPERTIES"]; }
+ Q_PROPERTY(Fact* BD_OBJ_CD READ getBD_OBJ_CD CONSTANT) Fact* getBD_OBJ_CD(void) { return _mapParameterName2Fact["BD_OBJ_CD"]; }
+ Q_PROPERTY(Fact* BD_OBJ_MASS READ getBD_OBJ_MASS CONSTANT) Fact* getBD_OBJ_MASS(void) { return _mapParameterName2Fact["BD_OBJ_MASS"]; }
+ Q_PROPERTY(Fact* BD_OBJ_SURFACE READ getBD_OBJ_SURFACE CONSTANT) Fact* getBD_OBJ_SURFACE(void) { return _mapParameterName2Fact["BD_OBJ_SURFACE"]; }
+ Q_PROPERTY(Fact* BD_PRECISION READ getBD_PRECISION CONSTANT) Fact* getBD_PRECISION(void) { return _mapParameterName2Fact["BD_PRECISION"]; }
+ Q_PROPERTY(Fact* BD_TURNRADIUS READ getBD_TURNRADIUS CONSTANT) Fact* getBD_TURNRADIUS(void) { return _mapParameterName2Fact["BD_TURNRADIUS"]; }
+ Q_PROPERTY(Fact* CBRK_AIRSPD_CHK READ getCBRK_AIRSPD_CHK CONSTANT) Fact* getCBRK_AIRSPD_CHK(void) { return _mapParameterName2Fact["CBRK_AIRSPD_CHK"]; }
+ Q_PROPERTY(Fact* CBRK_ENGINEFAIL READ getCBRK_ENGINEFAIL CONSTANT) Fact* getCBRK_ENGINEFAIL(void) { return _mapParameterName2Fact["CBRK_ENGINEFAIL"]; }
+ Q_PROPERTY(Fact* CBRK_FLIGHTTERM READ getCBRK_FLIGHTTERM CONSTANT) Fact* getCBRK_FLIGHTTERM(void) { return _mapParameterName2Fact["CBRK_FLIGHTTERM"]; }
+ Q_PROPERTY(Fact* CBRK_GPSFAIL READ getCBRK_GPSFAIL CONSTANT) Fact* getCBRK_GPSFAIL(void) { return _mapParameterName2Fact["CBRK_GPSFAIL"]; }
+ Q_PROPERTY(Fact* CBRK_IO_SAFETY READ getCBRK_IO_SAFETY CONSTANT) Fact* getCBRK_IO_SAFETY(void) { return _mapParameterName2Fact["CBRK_IO_SAFETY"]; }
+ Q_PROPERTY(Fact* CBRK_NO_VISION READ getCBRK_NO_VISION CONSTANT) Fact* getCBRK_NO_VISION(void) { return _mapParameterName2Fact["CBRK_NO_VISION"]; }
+ Q_PROPERTY(Fact* CBRK_RATE_CTRL READ getCBRK_RATE_CTRL CONSTANT) Fact* getCBRK_RATE_CTRL(void) { return _mapParameterName2Fact["CBRK_RATE_CTRL"]; }
+ Q_PROPERTY(Fact* CBRK_SUPPLY_CHK READ getCBRK_SUPPLY_CHK CONSTANT) Fact* getCBRK_SUPPLY_CHK(void) { return _mapParameterName2Fact["CBRK_SUPPLY_CHK"]; }
+ Q_PROPERTY(Fact* COM_DL_LOSS_EN READ getCOM_DL_LOSS_EN CONSTANT) Fact* getCOM_DL_LOSS_EN(void) { return _mapParameterName2Fact["COM_DL_LOSS_EN"]; }
+ Q_PROPERTY(Fact* COM_DL_LOSS_T READ getCOM_DL_LOSS_T CONSTANT) Fact* getCOM_DL_LOSS_T(void) { return _mapParameterName2Fact["COM_DL_LOSS_T"]; }
+ Q_PROPERTY(Fact* COM_DL_REG_T READ getCOM_DL_REG_T CONSTANT) Fact* getCOM_DL_REG_T(void) { return _mapParameterName2Fact["COM_DL_REG_T"]; }
+ Q_PROPERTY(Fact* COM_EF_C2T READ getCOM_EF_C2T CONSTANT) Fact* getCOM_EF_C2T(void) { return _mapParameterName2Fact["COM_EF_C2T"]; }
+ Q_PROPERTY(Fact* COM_EF_THROT READ getCOM_EF_THROT CONSTANT) Fact* getCOM_EF_THROT(void) { return _mapParameterName2Fact["COM_EF_THROT"]; }
+ Q_PROPERTY(Fact* COM_EF_TIME READ getCOM_EF_TIME CONSTANT) Fact* getCOM_EF_TIME(void) { return _mapParameterName2Fact["COM_EF_TIME"]; }
+ Q_PROPERTY(Fact* COM_RC_LOSS_T READ getCOM_RC_LOSS_T CONSTANT) Fact* getCOM_RC_LOSS_T(void) { return _mapParameterName2Fact["COM_RC_LOSS_T"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V3_Q0 READ getEKF_ATT_V3_Q0 CONSTANT) Fact* getEKF_ATT_V3_Q0(void) { return _mapParameterName2Fact["EKF_ATT_V3_Q0"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V3_Q1 READ getEKF_ATT_V3_Q1 CONSTANT) Fact* getEKF_ATT_V3_Q1(void) { return _mapParameterName2Fact["EKF_ATT_V3_Q1"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V3_Q2 READ getEKF_ATT_V3_Q2 CONSTANT) Fact* getEKF_ATT_V3_Q2(void) { return _mapParameterName2Fact["EKF_ATT_V3_Q2"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V3_Q3 READ getEKF_ATT_V3_Q3 CONSTANT) Fact* getEKF_ATT_V3_Q3(void) { return _mapParameterName2Fact["EKF_ATT_V3_Q3"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V3_Q4 READ getEKF_ATT_V3_Q4 CONSTANT) Fact* getEKF_ATT_V3_Q4(void) { return _mapParameterName2Fact["EKF_ATT_V3_Q4"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V4_R0 READ getEKF_ATT_V4_R0 CONSTANT) Fact* getEKF_ATT_V4_R0(void) { return _mapParameterName2Fact["EKF_ATT_V4_R0"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V4_R1 READ getEKF_ATT_V4_R1 CONSTANT) Fact* getEKF_ATT_V4_R1(void) { return _mapParameterName2Fact["EKF_ATT_V4_R1"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V4_R2 READ getEKF_ATT_V4_R2 CONSTANT) Fact* getEKF_ATT_V4_R2(void) { return _mapParameterName2Fact["EKF_ATT_V4_R2"]; }
+ Q_PROPERTY(Fact* EKF_ATT_V4_R3 READ getEKF_ATT_V4_R3 CONSTANT) Fact* getEKF_ATT_V4_R3(void) { return _mapParameterName2Fact["EKF_ATT_V4_R3"]; }
+ Q_PROPERTY(Fact* FPE_DEBUG READ getFPE_DEBUG CONSTANT) Fact* getFPE_DEBUG(void) { return _mapParameterName2Fact["FPE_DEBUG"]; }
+ Q_PROPERTY(Fact* FPE_LO_THRUST READ getFPE_LO_THRUST CONSTANT) Fact* getFPE_LO_THRUST(void) { return _mapParameterName2Fact["FPE_LO_THRUST"]; }
+ Q_PROPERTY(Fact* FPE_SONAR_LP_L READ getFPE_SONAR_LP_L CONSTANT) Fact* getFPE_SONAR_LP_L(void) { return _mapParameterName2Fact["FPE_SONAR_LP_L"]; }
+ Q_PROPERTY(Fact* FPE_SONAR_LP_U READ getFPE_SONAR_LP_U CONSTANT) Fact* getFPE_SONAR_LP_U(void) { return _mapParameterName2Fact["FPE_SONAR_LP_U"]; }
+ Q_PROPERTY(Fact* FW_AIRSPD_MAX READ getFW_AIRSPD_MAX CONSTANT) Fact* getFW_AIRSPD_MAX(void) { return _mapParameterName2Fact["FW_AIRSPD_MAX"]; }
+ Q_PROPERTY(Fact* FW_AIRSPD_MIN READ getFW_AIRSPD_MIN CONSTANT) Fact* getFW_AIRSPD_MIN(void) { return _mapParameterName2Fact["FW_AIRSPD_MIN"]; }
+ Q_PROPERTY(Fact* FW_AIRSPD_TRIM READ getFW_AIRSPD_TRIM CONSTANT) Fact* getFW_AIRSPD_TRIM(void) { return _mapParameterName2Fact["FW_AIRSPD_TRIM"]; }
+ Q_PROPERTY(Fact* FW_ATT_TC READ getFW_ATT_TC CONSTANT) Fact* getFW_ATT_TC(void) { return _mapParameterName2Fact["FW_ATT_TC"]; }
+ Q_PROPERTY(Fact* FW_CLMBOUT_DIFF READ getFW_CLMBOUT_DIFF CONSTANT) Fact* getFW_CLMBOUT_DIFF(void) { return _mapParameterName2Fact["FW_CLMBOUT_DIFF"]; }
+ Q_PROPERTY(Fact* FW_FLARE_PMAX READ getFW_FLARE_PMAX CONSTANT) Fact* getFW_FLARE_PMAX(void) { return _mapParameterName2Fact["FW_FLARE_PMAX"]; }
+ Q_PROPERTY(Fact* FW_FLARE_PMIN READ getFW_FLARE_PMIN CONSTANT) Fact* getFW_FLARE_PMIN(void) { return _mapParameterName2Fact["FW_FLARE_PMIN"]; }
+ Q_PROPERTY(Fact* FW_L1_DAMPING READ getFW_L1_DAMPING CONSTANT) Fact* getFW_L1_DAMPING(void) { return _mapParameterName2Fact["FW_L1_DAMPING"]; }
+ Q_PROPERTY(Fact* FW_L1_PERIOD READ getFW_L1_PERIOD CONSTANT) Fact* getFW_L1_PERIOD(void) { return _mapParameterName2Fact["FW_L1_PERIOD"]; }
+ Q_PROPERTY(Fact* FW_LND_ANG READ getFW_LND_ANG CONSTANT) Fact* getFW_LND_ANG(void) { return _mapParameterName2Fact["FW_LND_ANG"]; }
+ Q_PROPERTY(Fact* FW_LND_FLALT READ getFW_LND_FLALT CONSTANT) Fact* getFW_LND_FLALT(void) { return _mapParameterName2Fact["FW_LND_FLALT"]; }
+ Q_PROPERTY(Fact* FW_LND_HHDIST READ getFW_LND_HHDIST CONSTANT) Fact* getFW_LND_HHDIST(void) { return _mapParameterName2Fact["FW_LND_HHDIST"]; }
+ Q_PROPERTY(Fact* FW_LND_HVIRT READ getFW_LND_HVIRT CONSTANT) Fact* getFW_LND_HVIRT(void) { return _mapParameterName2Fact["FW_LND_HVIRT"]; }
+ Q_PROPERTY(Fact* FW_LND_TLALT READ getFW_LND_TLALT CONSTANT) Fact* getFW_LND_TLALT(void) { return _mapParameterName2Fact["FW_LND_TLALT"]; }
+ Q_PROPERTY(Fact* FW_LND_USETER READ getFW_LND_USETER CONSTANT) Fact* getFW_LND_USETER(void) { return _mapParameterName2Fact["FW_LND_USETER"]; }
+ Q_PROPERTY(Fact* FW_MAN_P_MAX READ getFW_MAN_P_MAX CONSTANT) Fact* getFW_MAN_P_MAX(void) { return _mapParameterName2Fact["FW_MAN_P_MAX"]; }
+ Q_PROPERTY(Fact* FW_MAN_R_MAX READ getFW_MAN_R_MAX CONSTANT) Fact* getFW_MAN_R_MAX(void) { return _mapParameterName2Fact["FW_MAN_R_MAX"]; }
+ Q_PROPERTY(Fact* FW_PR_FF READ getFW_PR_FF CONSTANT) Fact* getFW_PR_FF(void) { return _mapParameterName2Fact["FW_PR_FF"]; }
+ Q_PROPERTY(Fact* FW_PR_I READ getFW_PR_I CONSTANT) Fact* getFW_PR_I(void) { return _mapParameterName2Fact["FW_PR_I"]; }
+ Q_PROPERTY(Fact* FW_PR_IMAX READ getFW_PR_IMAX CONSTANT) Fact* getFW_PR_IMAX(void) { return _mapParameterName2Fact["FW_PR_IMAX"]; }
+ Q_PROPERTY(Fact* FW_PR_P READ getFW_PR_P CONSTANT) Fact* getFW_PR_P(void) { return _mapParameterName2Fact["FW_PR_P"]; }
+ Q_PROPERTY(Fact* FW_PSP_OFF READ getFW_PSP_OFF CONSTANT) Fact* getFW_PSP_OFF(void) { return _mapParameterName2Fact["FW_PSP_OFF"]; }
+ Q_PROPERTY(Fact* FW_P_LIM_MAX READ getFW_P_LIM_MAX CONSTANT) Fact* getFW_P_LIM_MAX(void) { return _mapParameterName2Fact["FW_P_LIM_MAX"]; }
+ Q_PROPERTY(Fact* FW_P_LIM_MIN READ getFW_P_LIM_MIN CONSTANT) Fact* getFW_P_LIM_MIN(void) { return _mapParameterName2Fact["FW_P_LIM_MIN"]; }
+ Q_PROPERTY(Fact* FW_P_RMAX_NEG READ getFW_P_RMAX_NEG CONSTANT) Fact* getFW_P_RMAX_NEG(void) { return _mapParameterName2Fact["FW_P_RMAX_NEG"]; }
+ Q_PROPERTY(Fact* FW_P_RMAX_POS READ getFW_P_RMAX_POS CONSTANT) Fact* getFW_P_RMAX_POS(void) { return _mapParameterName2Fact["FW_P_RMAX_POS"]; }
+ Q_PROPERTY(Fact* FW_P_ROLLFF READ getFW_P_ROLLFF CONSTANT) Fact* getFW_P_ROLLFF(void) { return _mapParameterName2Fact["FW_P_ROLLFF"]; }
+ Q_PROPERTY(Fact* FW_RR_FF READ getFW_RR_FF CONSTANT) Fact* getFW_RR_FF(void) { return _mapParameterName2Fact["FW_RR_FF"]; }
+ Q_PROPERTY(Fact* FW_RR_I READ getFW_RR_I CONSTANT) Fact* getFW_RR_I(void) { return _mapParameterName2Fact["FW_RR_I"]; }
+ Q_PROPERTY(Fact* FW_RR_IMAX READ getFW_RR_IMAX CONSTANT) Fact* getFW_RR_IMAX(void) { return _mapParameterName2Fact["FW_RR_IMAX"]; }
+ Q_PROPERTY(Fact* FW_RR_P READ getFW_RR_P CONSTANT) Fact* getFW_RR_P(void) { return _mapParameterName2Fact["FW_RR_P"]; }
+ Q_PROPERTY(Fact* FW_RSP_OFF READ getFW_RSP_OFF CONSTANT) Fact* getFW_RSP_OFF(void) { return _mapParameterName2Fact["FW_RSP_OFF"]; }
+ Q_PROPERTY(Fact* FW_R_LIM READ getFW_R_LIM CONSTANT) Fact* getFW_R_LIM(void) { return _mapParameterName2Fact["FW_R_LIM"]; }
+ Q_PROPERTY(Fact* FW_R_RMAX READ getFW_R_RMAX CONSTANT) Fact* getFW_R_RMAX(void) { return _mapParameterName2Fact["FW_R_RMAX"]; }
+ Q_PROPERTY(Fact* FW_THR_CRUISE READ getFW_THR_CRUISE CONSTANT) Fact* getFW_THR_CRUISE(void) { return _mapParameterName2Fact["FW_THR_CRUISE"]; }
+ Q_PROPERTY(Fact* FW_THR_LND_MAX READ getFW_THR_LND_MAX CONSTANT) Fact* getFW_THR_LND_MAX(void) { return _mapParameterName2Fact["FW_THR_LND_MAX"]; }
+ Q_PROPERTY(Fact* FW_THR_MAX READ getFW_THR_MAX CONSTANT) Fact* getFW_THR_MAX(void) { return _mapParameterName2Fact["FW_THR_MAX"]; }
+ Q_PROPERTY(Fact* FW_THR_MIN READ getFW_THR_MIN CONSTANT) Fact* getFW_THR_MIN(void) { return _mapParameterName2Fact["FW_THR_MIN"]; }
+ Q_PROPERTY(Fact* FW_THR_SLEW_MAX READ getFW_THR_SLEW_MAX CONSTANT) Fact* getFW_THR_SLEW_MAX(void) { return _mapParameterName2Fact["FW_THR_SLEW_MAX"]; }
+ Q_PROPERTY(Fact* FW_T_CLMB_MAX READ getFW_T_CLMB_MAX CONSTANT) Fact* getFW_T_CLMB_MAX(void) { return _mapParameterName2Fact["FW_T_CLMB_MAX"]; }
+ Q_PROPERTY(Fact* FW_T_HGT_OMEGA READ getFW_T_HGT_OMEGA CONSTANT) Fact* getFW_T_HGT_OMEGA(void) { return _mapParameterName2Fact["FW_T_HGT_OMEGA"]; }
+ Q_PROPERTY(Fact* FW_T_HRATE_FF READ getFW_T_HRATE_FF CONSTANT) Fact* getFW_T_HRATE_FF(void) { return _mapParameterName2Fact["FW_T_HRATE_FF"]; }
+ Q_PROPERTY(Fact* FW_T_HRATE_P READ getFW_T_HRATE_P CONSTANT) Fact* getFW_T_HRATE_P(void) { return _mapParameterName2Fact["FW_T_HRATE_P"]; }
+ Q_PROPERTY(Fact* FW_T_INTEG_GAIN READ getFW_T_INTEG_GAIN CONSTANT) Fact* getFW_T_INTEG_GAIN(void) { return _mapParameterName2Fact["FW_T_INTEG_GAIN"]; }
+ Q_PROPERTY(Fact* FW_T_PTCH_DAMP READ getFW_T_PTCH_DAMP CONSTANT) Fact* getFW_T_PTCH_DAMP(void) { return _mapParameterName2Fact["FW_T_PTCH_DAMP"]; }
+ Q_PROPERTY(Fact* FW_T_RLL2THR READ getFW_T_RLL2THR CONSTANT) Fact* getFW_T_RLL2THR(void) { return _mapParameterName2Fact["FW_T_RLL2THR"]; }
+ Q_PROPERTY(Fact* FW_T_SINK_MAX READ getFW_T_SINK_MAX CONSTANT) Fact* getFW_T_SINK_MAX(void) { return _mapParameterName2Fact["FW_T_SINK_MAX"]; }
+ Q_PROPERTY(Fact* FW_T_SINK_MIN READ getFW_T_SINK_MIN CONSTANT) Fact* getFW_T_SINK_MIN(void) { return _mapParameterName2Fact["FW_T_SINK_MIN"]; }
+ Q_PROPERTY(Fact* FW_T_SPDWEIGHT READ getFW_T_SPDWEIGHT CONSTANT) Fact* getFW_T_SPDWEIGHT(void) { return _mapParameterName2Fact["FW_T_SPDWEIGHT"]; }
+ Q_PROPERTY(Fact* FW_T_SPD_OMEGA READ getFW_T_SPD_OMEGA CONSTANT) Fact* getFW_T_SPD_OMEGA(void) { return _mapParameterName2Fact["FW_T_SPD_OMEGA"]; }
+ Q_PROPERTY(Fact* FW_T_SRATE_P READ getFW_T_SRATE_P CONSTANT) Fact* getFW_T_SRATE_P(void) { return _mapParameterName2Fact["FW_T_SRATE_P"]; }
+ Q_PROPERTY(Fact* FW_T_THRO_CONST READ getFW_T_THRO_CONST CONSTANT) Fact* getFW_T_THRO_CONST(void) { return _mapParameterName2Fact["FW_T_THRO_CONST"]; }
+ Q_PROPERTY(Fact* FW_T_THR_DAMP READ getFW_T_THR_DAMP CONSTANT) Fact* getFW_T_THR_DAMP(void) { return _mapParameterName2Fact["FW_T_THR_DAMP"]; }
+ Q_PROPERTY(Fact* FW_T_TIME_CONST READ getFW_T_TIME_CONST CONSTANT) Fact* getFW_T_TIME_CONST(void) { return _mapParameterName2Fact["FW_T_TIME_CONST"]; }
+ Q_PROPERTY(Fact* FW_T_VERT_ACC READ getFW_T_VERT_ACC CONSTANT) Fact* getFW_T_VERT_ACC(void) { return _mapParameterName2Fact["FW_T_VERT_ACC"]; }
+ Q_PROPERTY(Fact* FW_YCO_VMIN READ getFW_YCO_VMIN CONSTANT) Fact* getFW_YCO_VMIN(void) { return _mapParameterName2Fact["FW_YCO_VMIN"]; }
+ Q_PROPERTY(Fact* FW_YR_FF READ getFW_YR_FF CONSTANT) Fact* getFW_YR_FF(void) { return _mapParameterName2Fact["FW_YR_FF"]; }
+ Q_PROPERTY(Fact* FW_YR_I READ getFW_YR_I CONSTANT) Fact* getFW_YR_I(void) { return _mapParameterName2Fact["FW_YR_I"]; }
+ Q_PROPERTY(Fact* FW_YR_IMAX READ getFW_YR_IMAX CONSTANT) Fact* getFW_YR_IMAX(void) { return _mapParameterName2Fact["FW_YR_IMAX"]; }
+ Q_PROPERTY(Fact* FW_YR_P READ getFW_YR_P CONSTANT) Fact* getFW_YR_P(void) { return _mapParameterName2Fact["FW_YR_P"]; }
+ Q_PROPERTY(Fact* FW_Y_RMAX READ getFW_Y_RMAX CONSTANT) Fact* getFW_Y_RMAX(void) { return _mapParameterName2Fact["FW_Y_RMAX"]; }
+ Q_PROPERTY(Fact* GF_ALTMODE READ getGF_ALTMODE CONSTANT) Fact* getGF_ALTMODE(void) { return _mapParameterName2Fact["GF_ALTMODE"]; }
+ Q_PROPERTY(Fact* GF_COUNT READ getGF_COUNT CONSTANT) Fact* getGF_COUNT(void) { return _mapParameterName2Fact["GF_COUNT"]; }
+ Q_PROPERTY(Fact* GF_ON READ getGF_ON CONSTANT) Fact* getGF_ON(void) { return _mapParameterName2Fact["GF_ON"]; }
+ Q_PROPERTY(Fact* GF_SOURCE READ getGF_SOURCE CONSTANT) Fact* getGF_SOURCE(void) { return _mapParameterName2Fact["GF_SOURCE"]; }
+ Q_PROPERTY(Fact* INAV_DELAY_GPS READ getINAV_DELAY_GPS CONSTANT) Fact* getINAV_DELAY_GPS(void) { return _mapParameterName2Fact["INAV_DELAY_GPS"]; }
+ Q_PROPERTY(Fact* INAV_FLOW_K READ getINAV_FLOW_K CONSTANT) Fact* getINAV_FLOW_K(void) { return _mapParameterName2Fact["INAV_FLOW_K"]; }
+ Q_PROPERTY(Fact* INAV_FLOW_Q_MIN READ getINAV_FLOW_Q_MIN CONSTANT) Fact* getINAV_FLOW_Q_MIN(void) { return _mapParameterName2Fact["INAV_FLOW_Q_MIN"]; }
+ Q_PROPERTY(Fact* INAV_LAND_DISP READ getINAV_LAND_DISP CONSTANT) Fact* getINAV_LAND_DISP(void) { return _mapParameterName2Fact["INAV_LAND_DISP"]; }
+ Q_PROPERTY(Fact* INAV_LAND_T READ getINAV_LAND_T CONSTANT) Fact* getINAV_LAND_T(void) { return _mapParameterName2Fact["INAV_LAND_T"]; }
+ Q_PROPERTY(Fact* INAV_LAND_THR READ getINAV_LAND_THR CONSTANT) Fact* getINAV_LAND_THR(void) { return _mapParameterName2Fact["INAV_LAND_THR"]; }
+ Q_PROPERTY(Fact* INAV_SONAR_ERR READ getINAV_SONAR_ERR CONSTANT) Fact* getINAV_SONAR_ERR(void) { return _mapParameterName2Fact["INAV_SONAR_ERR"]; }
+ Q_PROPERTY(Fact* INAV_SONAR_FILT READ getINAV_SONAR_FILT CONSTANT) Fact* getINAV_SONAR_FILT(void) { return _mapParameterName2Fact["INAV_SONAR_FILT"]; }
+ Q_PROPERTY(Fact* INAV_W_ACC_BIAS READ getINAV_W_ACC_BIAS CONSTANT) Fact* getINAV_W_ACC_BIAS(void) { return _mapParameterName2Fact["INAV_W_ACC_BIAS"]; }
+ Q_PROPERTY(Fact* INAV_W_GPS_FLOW READ getINAV_W_GPS_FLOW CONSTANT) Fact* getINAV_W_GPS_FLOW(void) { return _mapParameterName2Fact["INAV_W_GPS_FLOW"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_FLOW READ getINAV_W_XY_FLOW CONSTANT) Fact* getINAV_W_XY_FLOW(void) { return _mapParameterName2Fact["INAV_W_XY_FLOW"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_GPS_P READ getINAV_W_XY_GPS_P CONSTANT) Fact* getINAV_W_XY_GPS_P(void) { return _mapParameterName2Fact["INAV_W_XY_GPS_P"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_GPS_V READ getINAV_W_XY_GPS_V CONSTANT) Fact* getINAV_W_XY_GPS_V(void) { return _mapParameterName2Fact["INAV_W_XY_GPS_V"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_RES_V READ getINAV_W_XY_RES_V CONSTANT) Fact* getINAV_W_XY_RES_V(void) { return _mapParameterName2Fact["INAV_W_XY_RES_V"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_VIS_P READ getINAV_W_XY_VIS_P CONSTANT) Fact* getINAV_W_XY_VIS_P(void) { return _mapParameterName2Fact["INAV_W_XY_VIS_P"]; }
+ Q_PROPERTY(Fact* INAV_W_XY_VIS_V READ getINAV_W_XY_VIS_V CONSTANT) Fact* getINAV_W_XY_VIS_V(void) { return _mapParameterName2Fact["INAV_W_XY_VIS_V"]; }
+ Q_PROPERTY(Fact* INAV_W_Z_BARO READ getINAV_W_Z_BARO CONSTANT) Fact* getINAV_W_Z_BARO(void) { return _mapParameterName2Fact["INAV_W_Z_BARO"]; }
+ Q_PROPERTY(Fact* INAV_W_Z_GPS_P READ getINAV_W_Z_GPS_P CONSTANT) Fact* getINAV_W_Z_GPS_P(void) { return _mapParameterName2Fact["INAV_W_Z_GPS_P"]; }
+ Q_PROPERTY(Fact* INAV_W_Z_SONAR READ getINAV_W_Z_SONAR CONSTANT) Fact* getINAV_W_Z_SONAR(void) { return _mapParameterName2Fact["INAV_W_Z_SONAR"]; }
+ Q_PROPERTY(Fact* INAV_W_Z_VIS_P READ getINAV_W_Z_VIS_P CONSTANT) Fact* getINAV_W_Z_VIS_P(void) { return _mapParameterName2Fact["INAV_W_Z_VIS_P"]; }
+ Q_PROPERTY(Fact* LAUN_ALL_ON READ getLAUN_ALL_ON CONSTANT) Fact* getLAUN_ALL_ON(void) { return _mapParameterName2Fact["LAUN_ALL_ON"]; }
+ Q_PROPERTY(Fact* LAUN_CAT_A READ getLAUN_CAT_A CONSTANT) Fact* getLAUN_CAT_A(void) { return _mapParameterName2Fact["LAUN_CAT_A"]; }
+ Q_PROPERTY(Fact* LAUN_CAT_MDEL READ getLAUN_CAT_MDEL CONSTANT) Fact* getLAUN_CAT_MDEL(void) { return _mapParameterName2Fact["LAUN_CAT_MDEL"]; }
+ Q_PROPERTY(Fact* LAUN_CAT_PMAX READ getLAUN_CAT_PMAX CONSTANT) Fact* getLAUN_CAT_PMAX(void) { return _mapParameterName2Fact["LAUN_CAT_PMAX"]; }
+ Q_PROPERTY(Fact* LAUN_CAT_T READ getLAUN_CAT_T CONSTANT) Fact* getLAUN_CAT_T(void) { return _mapParameterName2Fact["LAUN_CAT_T"]; }
+ Q_PROPERTY(Fact* LAUN_THR_PRE READ getLAUN_THR_PRE CONSTANT) Fact* getLAUN_THR_PRE(void) { return _mapParameterName2Fact["LAUN_THR_PRE"]; }
+ Q_PROPERTY(Fact* MAV_COMP_ID READ getMAV_COMP_ID CONSTANT) Fact* getMAV_COMP_ID(void) { return _mapParameterName2Fact["MAV_COMP_ID"]; }
+ Q_PROPERTY(Fact* MAV_FWDEXTSP READ getMAV_FWDEXTSP CONSTANT) Fact* getMAV_FWDEXTSP(void) { return _mapParameterName2Fact["MAV_FWDEXTSP"]; }
+ Q_PROPERTY(Fact* MAV_SYS_ID READ getMAV_SYS_ID CONSTANT) Fact* getMAV_SYS_ID(void) { return _mapParameterName2Fact["MAV_SYS_ID"]; }
+ Q_PROPERTY(Fact* MAV_TYPE READ getMAV_TYPE CONSTANT) Fact* getMAV_TYPE(void) { return _mapParameterName2Fact["MAV_TYPE"]; }
+ Q_PROPERTY(Fact* MAV_USEHILGPS READ getMAV_USEHILGPS CONSTANT) Fact* getMAV_USEHILGPS(void) { return _mapParameterName2Fact["MAV_USEHILGPS"]; }
+ Q_PROPERTY(Fact* MC_ACRO_P_MAX READ getMC_ACRO_P_MAX CONSTANT) Fact* getMC_ACRO_P_MAX(void) { return _mapParameterName2Fact["MC_ACRO_P_MAX"]; }
+ Q_PROPERTY(Fact* MC_ACRO_R_MAX READ getMC_ACRO_R_MAX CONSTANT) Fact* getMC_ACRO_R_MAX(void) { return _mapParameterName2Fact["MC_ACRO_R_MAX"]; }
+ Q_PROPERTY(Fact* MC_ACRO_Y_MAX READ getMC_ACRO_Y_MAX CONSTANT) Fact* getMC_ACRO_Y_MAX(void) { return _mapParameterName2Fact["MC_ACRO_Y_MAX"]; }
+ Q_PROPERTY(Fact* MC_MAN_P_MAX READ getMC_MAN_P_MAX CONSTANT) Fact* getMC_MAN_P_MAX(void) { return _mapParameterName2Fact["MC_MAN_P_MAX"]; }
+ Q_PROPERTY(Fact* MC_MAN_R_MAX READ getMC_MAN_R_MAX CONSTANT) Fact* getMC_MAN_R_MAX(void) { return _mapParameterName2Fact["MC_MAN_R_MAX"]; }
+ Q_PROPERTY(Fact* MC_MAN_Y_MAX READ getMC_MAN_Y_MAX CONSTANT) Fact* getMC_MAN_Y_MAX(void) { return _mapParameterName2Fact["MC_MAN_Y_MAX"]; }
+ Q_PROPERTY(Fact* MC_PITCHRATE_D READ getMC_PITCHRATE_D CONSTANT) Fact* getMC_PITCHRATE_D(void) { return _mapParameterName2Fact["MC_PITCHRATE_D"]; }
+ Q_PROPERTY(Fact* MC_PITCHRATE_I READ getMC_PITCHRATE_I CONSTANT) Fact* getMC_PITCHRATE_I(void) { return _mapParameterName2Fact["MC_PITCHRATE_I"]; }
+ Q_PROPERTY(Fact* MC_PITCHRATE_P READ getMC_PITCHRATE_P CONSTANT) Fact* getMC_PITCHRATE_P(void) { return _mapParameterName2Fact["MC_PITCHRATE_P"]; }
+ Q_PROPERTY(Fact* MC_PITCH_P READ getMC_PITCH_P CONSTANT) Fact* getMC_PITCH_P(void) { return _mapParameterName2Fact["MC_PITCH_P"]; }
+ Q_PROPERTY(Fact* MC_ROLLRATE_D READ getMC_ROLLRATE_D CONSTANT) Fact* getMC_ROLLRATE_D(void) { return _mapParameterName2Fact["MC_ROLLRATE_D"]; }
+ Q_PROPERTY(Fact* MC_ROLLRATE_I READ getMC_ROLLRATE_I CONSTANT) Fact* getMC_ROLLRATE_I(void) { return _mapParameterName2Fact["MC_ROLLRATE_I"]; }
+ Q_PROPERTY(Fact* MC_ROLLRATE_P READ getMC_ROLLRATE_P CONSTANT) Fact* getMC_ROLLRATE_P(void) { return _mapParameterName2Fact["MC_ROLLRATE_P"]; }
+ Q_PROPERTY(Fact* MC_ROLL_P READ getMC_ROLL_P CONSTANT) Fact* getMC_ROLL_P(void) { return _mapParameterName2Fact["MC_ROLL_P"]; }
+ Q_PROPERTY(Fact* MC_YAWRATE_D READ getMC_YAWRATE_D CONSTANT) Fact* getMC_YAWRATE_D(void) { return _mapParameterName2Fact["MC_YAWRATE_D"]; }
+ Q_PROPERTY(Fact* MC_YAWRATE_I READ getMC_YAWRATE_I CONSTANT) Fact* getMC_YAWRATE_I(void) { return _mapParameterName2Fact["MC_YAWRATE_I"]; }
+ Q_PROPERTY(Fact* MC_YAWRATE_MAX READ getMC_YAWRATE_MAX CONSTANT) Fact* getMC_YAWRATE_MAX(void) { return _mapParameterName2Fact["MC_YAWRATE_MAX"]; }
+ Q_PROPERTY(Fact* MC_YAWRATE_P READ getMC_YAWRATE_P CONSTANT) Fact* getMC_YAWRATE_P(void) { return _mapParameterName2Fact["MC_YAWRATE_P"]; }
+ Q_PROPERTY(Fact* MC_YAW_FF READ getMC_YAW_FF CONSTANT) Fact* getMC_YAW_FF(void) { return _mapParameterName2Fact["MC_YAW_FF"]; }
+ Q_PROPERTY(Fact* MC_YAW_P READ getMC_YAW_P CONSTANT) Fact* getMC_YAW_P(void) { return _mapParameterName2Fact["MC_YAW_P"]; }
+ Q_PROPERTY(Fact* MIS_ALTMODE READ getMIS_ALTMODE CONSTANT) Fact* getMIS_ALTMODE(void) { return _mapParameterName2Fact["MIS_ALTMODE"]; }
+ Q_PROPERTY(Fact* MIS_DIST_1WP READ getMIS_DIST_1WP CONSTANT) Fact* getMIS_DIST_1WP(void) { return _mapParameterName2Fact["MIS_DIST_1WP"]; }
+ Q_PROPERTY(Fact* MIS_ONBOARD_EN READ getMIS_ONBOARD_EN CONSTANT) Fact* getMIS_ONBOARD_EN(void) { return _mapParameterName2Fact["MIS_ONBOARD_EN"]; }
+ Q_PROPERTY(Fact* MIS_TAKEOFF_ALT READ getMIS_TAKEOFF_ALT CONSTANT) Fact* getMIS_TAKEOFF_ALT(void) { return _mapParameterName2Fact["MIS_TAKEOFF_ALT"]; }
+ Q_PROPERTY(Fact* MPC_LAND_SPEED READ getMPC_LAND_SPEED CONSTANT) Fact* getMPC_LAND_SPEED(void) { return _mapParameterName2Fact["MPC_LAND_SPEED"]; }
+ Q_PROPERTY(Fact* MPC_THR_MAX READ getMPC_THR_MAX CONSTANT) Fact* getMPC_THR_MAX(void) { return _mapParameterName2Fact["MPC_THR_MAX"]; }
+ Q_PROPERTY(Fact* MPC_THR_MIN READ getMPC_THR_MIN CONSTANT) Fact* getMPC_THR_MIN(void) { return _mapParameterName2Fact["MPC_THR_MIN"]; }
+ Q_PROPERTY(Fact* MPC_TILTMAX_AIR READ getMPC_TILTMAX_AIR CONSTANT) Fact* getMPC_TILTMAX_AIR(void) { return _mapParameterName2Fact["MPC_TILTMAX_AIR"]; }
+ Q_PROPERTY(Fact* MPC_TILTMAX_LND READ getMPC_TILTMAX_LND CONSTANT) Fact* getMPC_TILTMAX_LND(void) { return _mapParameterName2Fact["MPC_TILTMAX_LND"]; }
+ Q_PROPERTY(Fact* MPC_XY_FF READ getMPC_XY_FF CONSTANT) Fact* getMPC_XY_FF(void) { return _mapParameterName2Fact["MPC_XY_FF"]; }
+ Q_PROPERTY(Fact* MPC_XY_P READ getMPC_XY_P CONSTANT) Fact* getMPC_XY_P(void) { return _mapParameterName2Fact["MPC_XY_P"]; }
+ Q_PROPERTY(Fact* MPC_XY_VEL_D READ getMPC_XY_VEL_D CONSTANT) Fact* getMPC_XY_VEL_D(void) { return _mapParameterName2Fact["MPC_XY_VEL_D"]; }
+ Q_PROPERTY(Fact* MPC_XY_VEL_I READ getMPC_XY_VEL_I CONSTANT) Fact* getMPC_XY_VEL_I(void) { return _mapParameterName2Fact["MPC_XY_VEL_I"]; }
+ Q_PROPERTY(Fact* MPC_XY_VEL_MAX READ getMPC_XY_VEL_MAX CONSTANT) Fact* getMPC_XY_VEL_MAX(void) { return _mapParameterName2Fact["MPC_XY_VEL_MAX"]; }
+ Q_PROPERTY(Fact* MPC_XY_VEL_P READ getMPC_XY_VEL_P CONSTANT) Fact* getMPC_XY_VEL_P(void) { return _mapParameterName2Fact["MPC_XY_VEL_P"]; }
+ Q_PROPERTY(Fact* MPC_Z_FF READ getMPC_Z_FF CONSTANT) Fact* getMPC_Z_FF(void) { return _mapParameterName2Fact["MPC_Z_FF"]; }
+ Q_PROPERTY(Fact* MPC_Z_P READ getMPC_Z_P CONSTANT) Fact* getMPC_Z_P(void) { return _mapParameterName2Fact["MPC_Z_P"]; }
+ Q_PROPERTY(Fact* MPC_Z_VEL_D READ getMPC_Z_VEL_D CONSTANT) Fact* getMPC_Z_VEL_D(void) { return _mapParameterName2Fact["MPC_Z_VEL_D"]; }
+ Q_PROPERTY(Fact* MPC_Z_VEL_I READ getMPC_Z_VEL_I CONSTANT) Fact* getMPC_Z_VEL_I(void) { return _mapParameterName2Fact["MPC_Z_VEL_I"]; }
+ Q_PROPERTY(Fact* MPC_Z_VEL_MAX READ getMPC_Z_VEL_MAX CONSTANT) Fact* getMPC_Z_VEL_MAX(void) { return _mapParameterName2Fact["MPC_Z_VEL_MAX"]; }
+ Q_PROPERTY(Fact* MPC_Z_VEL_P READ getMPC_Z_VEL_P CONSTANT) Fact* getMPC_Z_VEL_P(void) { return _mapParameterName2Fact["MPC_Z_VEL_P"]; }
+ Q_PROPERTY(Fact* MT_ACC_D READ getMT_ACC_D CONSTANT) Fact* getMT_ACC_D(void) { return _mapParameterName2Fact["MT_ACC_D"]; }
+ Q_PROPERTY(Fact* MT_ACC_D_LP READ getMT_ACC_D_LP CONSTANT) Fact* getMT_ACC_D_LP(void) { return _mapParameterName2Fact["MT_ACC_D_LP"]; }
+ Q_PROPERTY(Fact* MT_ACC_MAX READ getMT_ACC_MAX CONSTANT) Fact* getMT_ACC_MAX(void) { return _mapParameterName2Fact["MT_ACC_MAX"]; }
+ Q_PROPERTY(Fact* MT_ACC_MIN READ getMT_ACC_MIN CONSTANT) Fact* getMT_ACC_MIN(void) { return _mapParameterName2Fact["MT_ACC_MIN"]; }
+ Q_PROPERTY(Fact* MT_ACC_P READ getMT_ACC_P CONSTANT) Fact* getMT_ACC_P(void) { return _mapParameterName2Fact["MT_ACC_P"]; }
+ Q_PROPERTY(Fact* MT_AD_LP READ getMT_AD_LP CONSTANT) Fact* getMT_AD_LP(void) { return _mapParameterName2Fact["MT_AD_LP"]; }
+ Q_PROPERTY(Fact* MT_ALT_LP READ getMT_ALT_LP CONSTANT) Fact* getMT_ALT_LP(void) { return _mapParameterName2Fact["MT_ALT_LP"]; }
+ Q_PROPERTY(Fact* MT_A_LP READ getMT_A_LP CONSTANT) Fact* getMT_A_LP(void) { return _mapParameterName2Fact["MT_A_LP"]; }
+ Q_PROPERTY(Fact* MT_ENABLED READ getMT_ENABLED CONSTANT) Fact* getMT_ENABLED(void) { return _mapParameterName2Fact["MT_ENABLED"]; }
+ Q_PROPERTY(Fact* MT_FPA_D READ getMT_FPA_D CONSTANT) Fact* getMT_FPA_D(void) { return _mapParameterName2Fact["MT_FPA_D"]; }
+ Q_PROPERTY(Fact* MT_FPA_D_LP READ getMT_FPA_D_LP CONSTANT) Fact* getMT_FPA_D_LP(void) { return _mapParameterName2Fact["MT_FPA_D_LP"]; }
+ Q_PROPERTY(Fact* MT_FPA_LP READ getMT_FPA_LP CONSTANT) Fact* getMT_FPA_LP(void) { return _mapParameterName2Fact["MT_FPA_LP"]; }
+ Q_PROPERTY(Fact* MT_FPA_MAX READ getMT_FPA_MAX CONSTANT) Fact* getMT_FPA_MAX(void) { return _mapParameterName2Fact["MT_FPA_MAX"]; }
+ Q_PROPERTY(Fact* MT_FPA_MIN READ getMT_FPA_MIN CONSTANT) Fact* getMT_FPA_MIN(void) { return _mapParameterName2Fact["MT_FPA_MIN"]; }
+ Q_PROPERTY(Fact* MT_FPA_P READ getMT_FPA_P CONSTANT) Fact* getMT_FPA_P(void) { return _mapParameterName2Fact["MT_FPA_P"]; }
+ Q_PROPERTY(Fact* MT_LND_PIT_MAX READ getMT_LND_PIT_MAX CONSTANT) Fact* getMT_LND_PIT_MAX(void) { return _mapParameterName2Fact["MT_LND_PIT_MAX"]; }
+ Q_PROPERTY(Fact* MT_LND_PIT_MIN READ getMT_LND_PIT_MIN CONSTANT) Fact* getMT_LND_PIT_MIN(void) { return _mapParameterName2Fact["MT_LND_PIT_MIN"]; }
+ Q_PROPERTY(Fact* MT_LND_THR_MAX READ getMT_LND_THR_MAX CONSTANT) Fact* getMT_LND_THR_MAX(void) { return _mapParameterName2Fact["MT_LND_THR_MAX"]; }
+ Q_PROPERTY(Fact* MT_LND_THR_MIN READ getMT_LND_THR_MIN CONSTANT) Fact* getMT_LND_THR_MIN(void) { return _mapParameterName2Fact["MT_LND_THR_MIN"]; }
+ Q_PROPERTY(Fact* MT_PIT_FF READ getMT_PIT_FF CONSTANT) Fact* getMT_PIT_FF(void) { return _mapParameterName2Fact["MT_PIT_FF"]; }
+ Q_PROPERTY(Fact* MT_PIT_I READ getMT_PIT_I CONSTANT) Fact* getMT_PIT_I(void) { return _mapParameterName2Fact["MT_PIT_I"]; }
+ Q_PROPERTY(Fact* MT_PIT_I_MAX READ getMT_PIT_I_MAX CONSTANT) Fact* getMT_PIT_I_MAX(void) { return _mapParameterName2Fact["MT_PIT_I_MAX"]; }
+ Q_PROPERTY(Fact* MT_PIT_MAX READ getMT_PIT_MAX CONSTANT) Fact* getMT_PIT_MAX(void) { return _mapParameterName2Fact["MT_PIT_MAX"]; }
+ Q_PROPERTY(Fact* MT_PIT_MIN READ getMT_PIT_MIN CONSTANT) Fact* getMT_PIT_MIN(void) { return _mapParameterName2Fact["MT_PIT_MIN"]; }
+ Q_PROPERTY(Fact* MT_PIT_OFF READ getMT_PIT_OFF CONSTANT) Fact* getMT_PIT_OFF(void) { return _mapParameterName2Fact["MT_PIT_OFF"]; }
+ Q_PROPERTY(Fact* MT_PIT_P READ getMT_PIT_P CONSTANT) Fact* getMT_PIT_P(void) { return _mapParameterName2Fact["MT_PIT_P"]; }
+ Q_PROPERTY(Fact* MT_THR_FF READ getMT_THR_FF CONSTANT) Fact* getMT_THR_FF(void) { return _mapParameterName2Fact["MT_THR_FF"]; }
+ Q_PROPERTY(Fact* MT_THR_I READ getMT_THR_I CONSTANT) Fact* getMT_THR_I(void) { return _mapParameterName2Fact["MT_THR_I"]; }
+ Q_PROPERTY(Fact* MT_THR_I_MAX READ getMT_THR_I_MAX CONSTANT) Fact* getMT_THR_I_MAX(void) { return _mapParameterName2Fact["MT_THR_I_MAX"]; }
+ Q_PROPERTY(Fact* MT_THR_MAX READ getMT_THR_MAX CONSTANT) Fact* getMT_THR_MAX(void) { return _mapParameterName2Fact["MT_THR_MAX"]; }
+ Q_PROPERTY(Fact* MT_THR_MIN READ getMT_THR_MIN CONSTANT) Fact* getMT_THR_MIN(void) { return _mapParameterName2Fact["MT_THR_MIN"]; }
+ Q_PROPERTY(Fact* MT_THR_OFF READ getMT_THR_OFF CONSTANT) Fact* getMT_THR_OFF(void) { return _mapParameterName2Fact["MT_THR_OFF"]; }
+ Q_PROPERTY(Fact* MT_THR_P READ getMT_THR_P CONSTANT) Fact* getMT_THR_P(void) { return _mapParameterName2Fact["MT_THR_P"]; }
+ Q_PROPERTY(Fact* MT_TKF_PIT_MAX READ getMT_TKF_PIT_MAX CONSTANT) Fact* getMT_TKF_PIT_MAX(void) { return _mapParameterName2Fact["MT_TKF_PIT_MAX"]; }
+ Q_PROPERTY(Fact* MT_TKF_PIT_MIN READ getMT_TKF_PIT_MIN CONSTANT) Fact* getMT_TKF_PIT_MIN(void) { return _mapParameterName2Fact["MT_TKF_PIT_MIN"]; }
+ Q_PROPERTY(Fact* MT_TKF_THR_MAX READ getMT_TKF_THR_MAX CONSTANT) Fact* getMT_TKF_THR_MAX(void) { return _mapParameterName2Fact["MT_TKF_THR_MAX"]; }
+ Q_PROPERTY(Fact* MT_TKF_THR_MIN READ getMT_TKF_THR_MIN CONSTANT) Fact* getMT_TKF_THR_MIN(void) { return _mapParameterName2Fact["MT_TKF_THR_MIN"]; }
+ Q_PROPERTY(Fact* MT_USP_PIT_MAX READ getMT_USP_PIT_MAX CONSTANT) Fact* getMT_USP_PIT_MAX(void) { return _mapParameterName2Fact["MT_USP_PIT_MAX"]; }
+ Q_PROPERTY(Fact* MT_USP_PIT_MIN READ getMT_USP_PIT_MIN CONSTANT) Fact* getMT_USP_PIT_MIN(void) { return _mapParameterName2Fact["MT_USP_PIT_MIN"]; }
+ Q_PROPERTY(Fact* MT_USP_THR_MAX READ getMT_USP_THR_MAX CONSTANT) Fact* getMT_USP_THR_MAX(void) { return _mapParameterName2Fact["MT_USP_THR_MAX"]; }
+ Q_PROPERTY(Fact* MT_USP_THR_MIN READ getMT_USP_THR_MIN CONSTANT) Fact* getMT_USP_THR_MIN(void) { return _mapParameterName2Fact["MT_USP_THR_MIN"]; }
+ Q_PROPERTY(Fact* NAV_ACC_RAD READ getNAV_ACC_RAD CONSTANT) Fact* getNAV_ACC_RAD(void) { return _mapParameterName2Fact["NAV_ACC_RAD"]; }
+ Q_PROPERTY(Fact* NAV_AH_ALT READ getNAV_AH_ALT CONSTANT) Fact* getNAV_AH_ALT(void) { return _mapParameterName2Fact["NAV_AH_ALT"]; }
+ Q_PROPERTY(Fact* NAV_AH_LAT READ getNAV_AH_LAT CONSTANT) Fact* getNAV_AH_LAT(void) { return _mapParameterName2Fact["NAV_AH_LAT"]; }
+ Q_PROPERTY(Fact* NAV_AH_LON READ getNAV_AH_LON CONSTANT) Fact* getNAV_AH_LON(void) { return _mapParameterName2Fact["NAV_AH_LON"]; }
+ Q_PROPERTY(Fact* NAV_DLL_AH_T READ getNAV_DLL_AH_T CONSTANT) Fact* getNAV_DLL_AH_T(void) { return _mapParameterName2Fact["NAV_DLL_AH_T"]; }
+ Q_PROPERTY(Fact* NAV_DLL_CHSK READ getNAV_DLL_CHSK CONSTANT) Fact* getNAV_DLL_CHSK(void) { return _mapParameterName2Fact["NAV_DLL_CHSK"]; }
+ Q_PROPERTY(Fact* NAV_DLL_CH_ALT READ getNAV_DLL_CH_ALT CONSTANT) Fact* getNAV_DLL_CH_ALT(void) { return _mapParameterName2Fact["NAV_DLL_CH_ALT"]; }
+ Q_PROPERTY(Fact* NAV_DLL_CH_LAT READ getNAV_DLL_CH_LAT CONSTANT) Fact* getNAV_DLL_CH_LAT(void) { return _mapParameterName2Fact["NAV_DLL_CH_LAT"]; }
+ Q_PROPERTY(Fact* NAV_DLL_CH_LON READ getNAV_DLL_CH_LON CONSTANT) Fact* getNAV_DLL_CH_LON(void) { return _mapParameterName2Fact["NAV_DLL_CH_LON"]; }
+ Q_PROPERTY(Fact* NAV_DLL_CH_T READ getNAV_DLL_CH_T CONSTANT) Fact* getNAV_DLL_CH_T(void) { return _mapParameterName2Fact["NAV_DLL_CH_T"]; }
+ Q_PROPERTY(Fact* NAV_DLL_N READ getNAV_DLL_N CONSTANT) Fact* getNAV_DLL_N(void) { return _mapParameterName2Fact["NAV_DLL_N"]; }
+ Q_PROPERTY(Fact* NAV_DLL_OBC READ getNAV_DLL_OBC CONSTANT) Fact* getNAV_DLL_OBC(void) { return _mapParameterName2Fact["NAV_DLL_OBC"]; }
+ Q_PROPERTY(Fact* NAV_GPSF_LT READ getNAV_GPSF_LT CONSTANT) Fact* getNAV_GPSF_LT(void) { return _mapParameterName2Fact["NAV_GPSF_LT"]; }
+ Q_PROPERTY(Fact* NAV_GPSF_P READ getNAV_GPSF_P CONSTANT) Fact* getNAV_GPSF_P(void) { return _mapParameterName2Fact["NAV_GPSF_P"]; }
+ Q_PROPERTY(Fact* NAV_GPSF_R READ getNAV_GPSF_R CONSTANT) Fact* getNAV_GPSF_R(void) { return _mapParameterName2Fact["NAV_GPSF_R"]; }
+ Q_PROPERTY(Fact* NAV_GPSF_TR READ getNAV_GPSF_TR CONSTANT) Fact* getNAV_GPSF_TR(void) { return _mapParameterName2Fact["NAV_GPSF_TR"]; }
+ Q_PROPERTY(Fact* NAV_LOITER_RAD READ getNAV_LOITER_RAD CONSTANT) Fact* getNAV_LOITER_RAD(void) { return _mapParameterName2Fact["NAV_LOITER_RAD"]; }
+ Q_PROPERTY(Fact* NAV_RCL_LT READ getNAV_RCL_LT CONSTANT) Fact* getNAV_RCL_LT(void) { return _mapParameterName2Fact["NAV_RCL_LT"]; }
+ Q_PROPERTY(Fact* NAV_RCL_OBC READ getNAV_RCL_OBC CONSTANT) Fact* getNAV_RCL_OBC(void) { return _mapParameterName2Fact["NAV_RCL_OBC"]; }
+ Q_PROPERTY(Fact* PE_ABIAS_PNOISE READ getPE_ABIAS_PNOISE CONSTANT) Fact* getPE_ABIAS_PNOISE(void) { return _mapParameterName2Fact["PE_ABIAS_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_ACC_PNOISE READ getPE_ACC_PNOISE CONSTANT) Fact* getPE_ACC_PNOISE(void) { return _mapParameterName2Fact["PE_ACC_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_EAS_NOISE READ getPE_EAS_NOISE CONSTANT) Fact* getPE_EAS_NOISE(void) { return _mapParameterName2Fact["PE_EAS_NOISE"]; }
+ Q_PROPERTY(Fact* PE_GBIAS_PNOISE READ getPE_GBIAS_PNOISE CONSTANT) Fact* getPE_GBIAS_PNOISE(void) { return _mapParameterName2Fact["PE_GBIAS_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_GPS_ALT_WGT READ getPE_GPS_ALT_WGT CONSTANT) Fact* getPE_GPS_ALT_WGT(void) { return _mapParameterName2Fact["PE_GPS_ALT_WGT"]; }
+ Q_PROPERTY(Fact* PE_GYRO_PNOISE READ getPE_GYRO_PNOISE CONSTANT) Fact* getPE_GYRO_PNOISE(void) { return _mapParameterName2Fact["PE_GYRO_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_HGT_DELAY_MS READ getPE_HGT_DELAY_MS CONSTANT) Fact* getPE_HGT_DELAY_MS(void) { return _mapParameterName2Fact["PE_HGT_DELAY_MS"]; }
+ Q_PROPERTY(Fact* PE_MAGB_PNOISE READ getPE_MAGB_PNOISE CONSTANT) Fact* getPE_MAGB_PNOISE(void) { return _mapParameterName2Fact["PE_MAGB_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_MAGE_PNOISE READ getPE_MAGE_PNOISE CONSTANT) Fact* getPE_MAGE_PNOISE(void) { return _mapParameterName2Fact["PE_MAGE_PNOISE"]; }
+ Q_PROPERTY(Fact* PE_MAG_DELAY_MS READ getPE_MAG_DELAY_MS CONSTANT) Fact* getPE_MAG_DELAY_MS(void) { return _mapParameterName2Fact["PE_MAG_DELAY_MS"]; }
+ Q_PROPERTY(Fact* PE_MAG_NOISE READ getPE_MAG_NOISE CONSTANT) Fact* getPE_MAG_NOISE(void) { return _mapParameterName2Fact["PE_MAG_NOISE"]; }
+ Q_PROPERTY(Fact* PE_POSDEV_INIT READ getPE_POSDEV_INIT CONSTANT) Fact* getPE_POSDEV_INIT(void) { return _mapParameterName2Fact["PE_POSDEV_INIT"]; }
+ Q_PROPERTY(Fact* PE_POSD_NOISE READ getPE_POSD_NOISE CONSTANT) Fact* getPE_POSD_NOISE(void) { return _mapParameterName2Fact["PE_POSD_NOISE"]; }
+ Q_PROPERTY(Fact* PE_POSNE_NOISE READ getPE_POSNE_NOISE CONSTANT) Fact* getPE_POSNE_NOISE(void) { return _mapParameterName2Fact["PE_POSNE_NOISE"]; }
+ Q_PROPERTY(Fact* PE_POS_DELAY_MS READ getPE_POS_DELAY_MS CONSTANT) Fact* getPE_POS_DELAY_MS(void) { return _mapParameterName2Fact["PE_POS_DELAY_MS"]; }
+ Q_PROPERTY(Fact* PE_TAS_DELAY_MS READ getPE_TAS_DELAY_MS CONSTANT) Fact* getPE_TAS_DELAY_MS(void) { return _mapParameterName2Fact["PE_TAS_DELAY_MS"]; }
+ Q_PROPERTY(Fact* PE_VELD_NOISE READ getPE_VELD_NOISE CONSTANT) Fact* getPE_VELD_NOISE(void) { return _mapParameterName2Fact["PE_VELD_NOISE"]; }
+ Q_PROPERTY(Fact* PE_VELNE_NOISE READ getPE_VELNE_NOISE CONSTANT) Fact* getPE_VELNE_NOISE(void) { return _mapParameterName2Fact["PE_VELNE_NOISE"]; }
+ Q_PROPERTY(Fact* PE_VEL_DELAY_MS READ getPE_VEL_DELAY_MS CONSTANT) Fact* getPE_VEL_DELAY_MS(void) { return _mapParameterName2Fact["PE_VEL_DELAY_MS"]; }
+ Q_PROPERTY(Fact* RC10_DZ READ getRC10_DZ CONSTANT) Fact* getRC10_DZ(void) { return _mapParameterName2Fact["RC10_DZ"]; }
+ Q_PROPERTY(Fact* RC10_MAX READ getRC10_MAX CONSTANT) Fact* getRC10_MAX(void) { return _mapParameterName2Fact["RC10_MAX"]; }
+ Q_PROPERTY(Fact* RC10_MIN READ getRC10_MIN CONSTANT) Fact* getRC10_MIN(void) { return _mapParameterName2Fact["RC10_MIN"]; }
+ Q_PROPERTY(Fact* RC10_REV READ getRC10_REV CONSTANT) Fact* getRC10_REV(void) { return _mapParameterName2Fact["RC10_REV"]; }
+ Q_PROPERTY(Fact* RC10_TRIM READ getRC10_TRIM CONSTANT) Fact* getRC10_TRIM(void) { return _mapParameterName2Fact["RC10_TRIM"]; }
+ Q_PROPERTY(Fact* RC11_DZ READ getRC11_DZ CONSTANT) Fact* getRC11_DZ(void) { return _mapParameterName2Fact["RC11_DZ"]; }
+ Q_PROPERTY(Fact* RC11_MAX READ getRC11_MAX CONSTANT) Fact* getRC11_MAX(void) { return _mapParameterName2Fact["RC11_MAX"]; }
+ Q_PROPERTY(Fact* RC11_MIN READ getRC11_MIN CONSTANT) Fact* getRC11_MIN(void) { return _mapParameterName2Fact["RC11_MIN"]; }
+ Q_PROPERTY(Fact* RC11_REV READ getRC11_REV CONSTANT) Fact* getRC11_REV(void) { return _mapParameterName2Fact["RC11_REV"]; }
+ Q_PROPERTY(Fact* RC11_TRIM READ getRC11_TRIM CONSTANT) Fact* getRC11_TRIM(void) { return _mapParameterName2Fact["RC11_TRIM"]; }
+ Q_PROPERTY(Fact* RC12_DZ READ getRC12_DZ CONSTANT) Fact* getRC12_DZ(void) { return _mapParameterName2Fact["RC12_DZ"]; }
+ Q_PROPERTY(Fact* RC12_MAX READ getRC12_MAX CONSTANT) Fact* getRC12_MAX(void) { return _mapParameterName2Fact["RC12_MAX"]; }
+ Q_PROPERTY(Fact* RC12_MIN READ getRC12_MIN CONSTANT) Fact* getRC12_MIN(void) { return _mapParameterName2Fact["RC12_MIN"]; }
+ Q_PROPERTY(Fact* RC12_REV READ getRC12_REV CONSTANT) Fact* getRC12_REV(void) { return _mapParameterName2Fact["RC12_REV"]; }
+ Q_PROPERTY(Fact* RC12_TRIM READ getRC12_TRIM CONSTANT) Fact* getRC12_TRIM(void) { return _mapParameterName2Fact["RC12_TRIM"]; }
+ Q_PROPERTY(Fact* RC13_DZ READ getRC13_DZ CONSTANT) Fact* getRC13_DZ(void) { return _mapParameterName2Fact["RC13_DZ"]; }
+ Q_PROPERTY(Fact* RC13_MAX READ getRC13_MAX CONSTANT) Fact* getRC13_MAX(void) { return _mapParameterName2Fact["RC13_MAX"]; }
+ Q_PROPERTY(Fact* RC13_MIN READ getRC13_MIN CONSTANT) Fact* getRC13_MIN(void) { return _mapParameterName2Fact["RC13_MIN"]; }
+ Q_PROPERTY(Fact* RC13_REV READ getRC13_REV CONSTANT) Fact* getRC13_REV(void) { return _mapParameterName2Fact["RC13_REV"]; }
+ Q_PROPERTY(Fact* RC13_TRIM READ getRC13_TRIM CONSTANT) Fact* getRC13_TRIM(void) { return _mapParameterName2Fact["RC13_TRIM"]; }
+ Q_PROPERTY(Fact* RC14_DZ READ getRC14_DZ CONSTANT) Fact* getRC14_DZ(void) { return _mapParameterName2Fact["RC14_DZ"]; }
+ Q_PROPERTY(Fact* RC14_MAX READ getRC14_MAX CONSTANT) Fact* getRC14_MAX(void) { return _mapParameterName2Fact["RC14_MAX"]; }
+ Q_PROPERTY(Fact* RC14_MIN READ getRC14_MIN CONSTANT) Fact* getRC14_MIN(void) { return _mapParameterName2Fact["RC14_MIN"]; }
+ Q_PROPERTY(Fact* RC14_REV READ getRC14_REV CONSTANT) Fact* getRC14_REV(void) { return _mapParameterName2Fact["RC14_REV"]; }
+ Q_PROPERTY(Fact* RC14_TRIM READ getRC14_TRIM CONSTANT) Fact* getRC14_TRIM(void) { return _mapParameterName2Fact["RC14_TRIM"]; }
+ Q_PROPERTY(Fact* RC15_DZ READ getRC15_DZ CONSTANT) Fact* getRC15_DZ(void) { return _mapParameterName2Fact["RC15_DZ"]; }
+ Q_PROPERTY(Fact* RC15_MAX READ getRC15_MAX CONSTANT) Fact* getRC15_MAX(void) { return _mapParameterName2Fact["RC15_MAX"]; }
+ Q_PROPERTY(Fact* RC15_MIN READ getRC15_MIN CONSTANT) Fact* getRC15_MIN(void) { return _mapParameterName2Fact["RC15_MIN"]; }
+ Q_PROPERTY(Fact* RC15_REV READ getRC15_REV CONSTANT) Fact* getRC15_REV(void) { return _mapParameterName2Fact["RC15_REV"]; }
+ Q_PROPERTY(Fact* RC15_TRIM READ getRC15_TRIM CONSTANT) Fact* getRC15_TRIM(void) { return _mapParameterName2Fact["RC15_TRIM"]; }
+ Q_PROPERTY(Fact* RC16_DZ READ getRC16_DZ CONSTANT) Fact* getRC16_DZ(void) { return _mapParameterName2Fact["RC16_DZ"]; }
+ Q_PROPERTY(Fact* RC16_MAX READ getRC16_MAX CONSTANT) Fact* getRC16_MAX(void) { return _mapParameterName2Fact["RC16_MAX"]; }
+ Q_PROPERTY(Fact* RC16_MIN READ getRC16_MIN CONSTANT) Fact* getRC16_MIN(void) { return _mapParameterName2Fact["RC16_MIN"]; }
+ Q_PROPERTY(Fact* RC16_REV READ getRC16_REV CONSTANT) Fact* getRC16_REV(void) { return _mapParameterName2Fact["RC16_REV"]; }
+ Q_PROPERTY(Fact* RC16_TRIM READ getRC16_TRIM CONSTANT) Fact* getRC16_TRIM(void) { return _mapParameterName2Fact["RC16_TRIM"]; }
+ Q_PROPERTY(Fact* RC17_DZ READ getRC17_DZ CONSTANT) Fact* getRC17_DZ(void) { return _mapParameterName2Fact["RC17_DZ"]; }
+ Q_PROPERTY(Fact* RC17_MAX READ getRC17_MAX CONSTANT) Fact* getRC17_MAX(void) { return _mapParameterName2Fact["RC17_MAX"]; }
+ Q_PROPERTY(Fact* RC17_MIN READ getRC17_MIN CONSTANT) Fact* getRC17_MIN(void) { return _mapParameterName2Fact["RC17_MIN"]; }
+ Q_PROPERTY(Fact* RC17_REV READ getRC17_REV CONSTANT) Fact* getRC17_REV(void) { return _mapParameterName2Fact["RC17_REV"]; }
+ Q_PROPERTY(Fact* RC17_TRIM READ getRC17_TRIM CONSTANT) Fact* getRC17_TRIM(void) { return _mapParameterName2Fact["RC17_TRIM"]; }
+ Q_PROPERTY(Fact* RC18_DZ READ getRC18_DZ CONSTANT) Fact* getRC18_DZ(void) { return _mapParameterName2Fact["RC18_DZ"]; }
+ Q_PROPERTY(Fact* RC18_MAX READ getRC18_MAX CONSTANT) Fact* getRC18_MAX(void) { return _mapParameterName2Fact["RC18_MAX"]; }
+ Q_PROPERTY(Fact* RC18_MIN READ getRC18_MIN CONSTANT) Fact* getRC18_MIN(void) { return _mapParameterName2Fact["RC18_MIN"]; }
+ Q_PROPERTY(Fact* RC18_REV READ getRC18_REV CONSTANT) Fact* getRC18_REV(void) { return _mapParameterName2Fact["RC18_REV"]; }
+ Q_PROPERTY(Fact* RC18_TRIM READ getRC18_TRIM CONSTANT) Fact* getRC18_TRIM(void) { return _mapParameterName2Fact["RC18_TRIM"]; }
+ Q_PROPERTY(Fact* RC1_DZ READ getRC1_DZ CONSTANT) Fact* getRC1_DZ(void) { return _mapParameterName2Fact["RC1_DZ"]; }
+ Q_PROPERTY(Fact* RC1_MAX READ getRC1_MAX CONSTANT) Fact* getRC1_MAX(void) { return _mapParameterName2Fact["RC1_MAX"]; }
+ Q_PROPERTY(Fact* RC1_MIN READ getRC1_MIN CONSTANT) Fact* getRC1_MIN(void) { return _mapParameterName2Fact["RC1_MIN"]; }
+ Q_PROPERTY(Fact* RC1_REV READ getRC1_REV CONSTANT) Fact* getRC1_REV(void) { return _mapParameterName2Fact["RC1_REV"]; }
+ Q_PROPERTY(Fact* RC1_TRIM READ getRC1_TRIM CONSTANT) Fact* getRC1_TRIM(void) { return _mapParameterName2Fact["RC1_TRIM"]; }
+ Q_PROPERTY(Fact* RC2_DZ READ getRC2_DZ CONSTANT) Fact* getRC2_DZ(void) { return _mapParameterName2Fact["RC2_DZ"]; }
+ Q_PROPERTY(Fact* RC2_MAX READ getRC2_MAX CONSTANT) Fact* getRC2_MAX(void) { return _mapParameterName2Fact["RC2_MAX"]; }
+ Q_PROPERTY(Fact* RC2_MIN READ getRC2_MIN CONSTANT) Fact* getRC2_MIN(void) { return _mapParameterName2Fact["RC2_MIN"]; }
+ Q_PROPERTY(Fact* RC2_REV READ getRC2_REV CONSTANT) Fact* getRC2_REV(void) { return _mapParameterName2Fact["RC2_REV"]; }
+ Q_PROPERTY(Fact* RC2_TRIM READ getRC2_TRIM CONSTANT) Fact* getRC2_TRIM(void) { return _mapParameterName2Fact["RC2_TRIM"]; }
+ Q_PROPERTY(Fact* RC3_DZ READ getRC3_DZ CONSTANT) Fact* getRC3_DZ(void) { return _mapParameterName2Fact["RC3_DZ"]; }
+ Q_PROPERTY(Fact* RC3_MAX READ getRC3_MAX CONSTANT) Fact* getRC3_MAX(void) { return _mapParameterName2Fact["RC3_MAX"]; }
+ Q_PROPERTY(Fact* RC3_MIN READ getRC3_MIN CONSTANT) Fact* getRC3_MIN(void) { return _mapParameterName2Fact["RC3_MIN"]; }
+ Q_PROPERTY(Fact* RC3_REV READ getRC3_REV CONSTANT) Fact* getRC3_REV(void) { return _mapParameterName2Fact["RC3_REV"]; }
+ Q_PROPERTY(Fact* RC3_TRIM READ getRC3_TRIM CONSTANT) Fact* getRC3_TRIM(void) { return _mapParameterName2Fact["RC3_TRIM"]; }
+ Q_PROPERTY(Fact* RC4_DZ READ getRC4_DZ CONSTANT) Fact* getRC4_DZ(void) { return _mapParameterName2Fact["RC4_DZ"]; }
+ Q_PROPERTY(Fact* RC4_MAX READ getRC4_MAX CONSTANT) Fact* getRC4_MAX(void) { return _mapParameterName2Fact["RC4_MAX"]; }
+ Q_PROPERTY(Fact* RC4_MIN READ getRC4_MIN CONSTANT) Fact* getRC4_MIN(void) { return _mapParameterName2Fact["RC4_MIN"]; }
+ Q_PROPERTY(Fact* RC4_REV READ getRC4_REV CONSTANT) Fact* getRC4_REV(void) { return _mapParameterName2Fact["RC4_REV"]; }
+ Q_PROPERTY(Fact* RC4_TRIM READ getRC4_TRIM CONSTANT) Fact* getRC4_TRIM(void) { return _mapParameterName2Fact["RC4_TRIM"]; }
+ Q_PROPERTY(Fact* RC5_DZ READ getRC5_DZ CONSTANT) Fact* getRC5_DZ(void) { return _mapParameterName2Fact["RC5_DZ"]; }
+ Q_PROPERTY(Fact* RC5_MAX READ getRC5_MAX CONSTANT) Fact* getRC5_MAX(void) { return _mapParameterName2Fact["RC5_MAX"]; }
+ Q_PROPERTY(Fact* RC5_MIN READ getRC5_MIN CONSTANT) Fact* getRC5_MIN(void) { return _mapParameterName2Fact["RC5_MIN"]; }
+ Q_PROPERTY(Fact* RC5_REV READ getRC5_REV CONSTANT) Fact* getRC5_REV(void) { return _mapParameterName2Fact["RC5_REV"]; }
+ Q_PROPERTY(Fact* RC5_TRIM READ getRC5_TRIM CONSTANT) Fact* getRC5_TRIM(void) { return _mapParameterName2Fact["RC5_TRIM"]; }
+ Q_PROPERTY(Fact* RC6_DZ READ getRC6_DZ CONSTANT) Fact* getRC6_DZ(void) { return _mapParameterName2Fact["RC6_DZ"]; }
+ Q_PROPERTY(Fact* RC6_MAX READ getRC6_MAX CONSTANT) Fact* getRC6_MAX(void) { return _mapParameterName2Fact["RC6_MAX"]; }
+ Q_PROPERTY(Fact* RC6_MIN READ getRC6_MIN CONSTANT) Fact* getRC6_MIN(void) { return _mapParameterName2Fact["RC6_MIN"]; }
+ Q_PROPERTY(Fact* RC6_REV READ getRC6_REV CONSTANT) Fact* getRC6_REV(void) { return _mapParameterName2Fact["RC6_REV"]; }
+ Q_PROPERTY(Fact* RC6_TRIM READ getRC6_TRIM CONSTANT) Fact* getRC6_TRIM(void) { return _mapParameterName2Fact["RC6_TRIM"]; }
+ Q_PROPERTY(Fact* RC7_DZ READ getRC7_DZ CONSTANT) Fact* getRC7_DZ(void) { return _mapParameterName2Fact["RC7_DZ"]; }
+ Q_PROPERTY(Fact* RC7_MAX READ getRC7_MAX CONSTANT) Fact* getRC7_MAX(void) { return _mapParameterName2Fact["RC7_MAX"]; }
+ Q_PROPERTY(Fact* RC7_MIN READ getRC7_MIN CONSTANT) Fact* getRC7_MIN(void) { return _mapParameterName2Fact["RC7_MIN"]; }
+ Q_PROPERTY(Fact* RC7_REV READ getRC7_REV CONSTANT) Fact* getRC7_REV(void) { return _mapParameterName2Fact["RC7_REV"]; }
+ Q_PROPERTY(Fact* RC7_TRIM READ getRC7_TRIM CONSTANT) Fact* getRC7_TRIM(void) { return _mapParameterName2Fact["RC7_TRIM"]; }
+ Q_PROPERTY(Fact* RC8_DZ READ getRC8_DZ CONSTANT) Fact* getRC8_DZ(void) { return _mapParameterName2Fact["RC8_DZ"]; }
+ Q_PROPERTY(Fact* RC8_MAX READ getRC8_MAX CONSTANT) Fact* getRC8_MAX(void) { return _mapParameterName2Fact["RC8_MAX"]; }
+ Q_PROPERTY(Fact* RC8_MIN READ getRC8_MIN CONSTANT) Fact* getRC8_MIN(void) { return _mapParameterName2Fact["RC8_MIN"]; }
+ Q_PROPERTY(Fact* RC8_REV READ getRC8_REV CONSTANT) Fact* getRC8_REV(void) { return _mapParameterName2Fact["RC8_REV"]; }
+ Q_PROPERTY(Fact* RC8_TRIM READ getRC8_TRIM CONSTANT) Fact* getRC8_TRIM(void) { return _mapParameterName2Fact["RC8_TRIM"]; }
+ Q_PROPERTY(Fact* RC9_DZ READ getRC9_DZ CONSTANT) Fact* getRC9_DZ(void) { return _mapParameterName2Fact["RC9_DZ"]; }
+ Q_PROPERTY(Fact* RC9_MAX READ getRC9_MAX CONSTANT) Fact* getRC9_MAX(void) { return _mapParameterName2Fact["RC9_MAX"]; }
+ Q_PROPERTY(Fact* RC9_MIN READ getRC9_MIN CONSTANT) Fact* getRC9_MIN(void) { return _mapParameterName2Fact["RC9_MIN"]; }
+ Q_PROPERTY(Fact* RC9_REV READ getRC9_REV CONSTANT) Fact* getRC9_REV(void) { return _mapParameterName2Fact["RC9_REV"]; }
+ Q_PROPERTY(Fact* RC9_TRIM READ getRC9_TRIM CONSTANT) Fact* getRC9_TRIM(void) { return _mapParameterName2Fact["RC9_TRIM"]; }
+ Q_PROPERTY(Fact* RC_ACRO_TH READ getRC_ACRO_TH CONSTANT) Fact* getRC_ACRO_TH(void) { return _mapParameterName2Fact["RC_ACRO_TH"]; }
+ Q_PROPERTY(Fact* RC_ASSIST_TH READ getRC_ASSIST_TH CONSTANT) Fact* getRC_ASSIST_TH(void) { return _mapParameterName2Fact["RC_ASSIST_TH"]; }
+ Q_PROPERTY(Fact* RC_AUTO_TH READ getRC_AUTO_TH CONSTANT) Fact* getRC_AUTO_TH(void) { return _mapParameterName2Fact["RC_AUTO_TH"]; }
+ Q_PROPERTY(Fact* RC_DSM_BIND READ getRC_DSM_BIND CONSTANT) Fact* getRC_DSM_BIND(void) { return _mapParameterName2Fact["RC_DSM_BIND"]; }
+ Q_PROPERTY(Fact* RC_FAILS_THR READ getRC_FAILS_THR CONSTANT) Fact* getRC_FAILS_THR(void) { return _mapParameterName2Fact["RC_FAILS_THR"]; }
+ Q_PROPERTY(Fact* RC_LOITER_TH READ getRC_LOITER_TH CONSTANT) Fact* getRC_LOITER_TH(void) { return _mapParameterName2Fact["RC_LOITER_TH"]; }
+ Q_PROPERTY(Fact* RC_MAP_ACRO_SW READ getRC_MAP_ACRO_SW CONSTANT) Fact* getRC_MAP_ACRO_SW(void) { return _mapParameterName2Fact["RC_MAP_ACRO_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_AUX1 READ getRC_MAP_AUX1 CONSTANT) Fact* getRC_MAP_AUX1(void) { return _mapParameterName2Fact["RC_MAP_AUX1"]; }
+ Q_PROPERTY(Fact* RC_MAP_AUX2 READ getRC_MAP_AUX2 CONSTANT) Fact* getRC_MAP_AUX2(void) { return _mapParameterName2Fact["RC_MAP_AUX2"]; }
+ Q_PROPERTY(Fact* RC_MAP_AUX3 READ getRC_MAP_AUX3 CONSTANT) Fact* getRC_MAP_AUX3(void) { return _mapParameterName2Fact["RC_MAP_AUX3"]; }
+ Q_PROPERTY(Fact* RC_MAP_FAILSAFE READ getRC_MAP_FAILSAFE CONSTANT) Fact* getRC_MAP_FAILSAFE(void) { return _mapParameterName2Fact["RC_MAP_FAILSAFE"]; }
+ Q_PROPERTY(Fact* RC_MAP_FLAPS READ getRC_MAP_FLAPS CONSTANT) Fact* getRC_MAP_FLAPS(void) { return _mapParameterName2Fact["RC_MAP_FLAPS"]; }
+ Q_PROPERTY(Fact* RC_MAP_LOITER_SW READ getRC_MAP_LOITER_SW CONSTANT) Fact* getRC_MAP_LOITER_SW(void) { return _mapParameterName2Fact["RC_MAP_LOITER_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_MODE_SW READ getRC_MAP_MODE_SW CONSTANT) Fact* getRC_MAP_MODE_SW(void) { return _mapParameterName2Fact["RC_MAP_MODE_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_OFFB_SW READ getRC_MAP_OFFB_SW CONSTANT) Fact* getRC_MAP_OFFB_SW(void) { return _mapParameterName2Fact["RC_MAP_OFFB_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_PITCH READ getRC_MAP_PITCH CONSTANT) Fact* getRC_MAP_PITCH(void) { return _mapParameterName2Fact["RC_MAP_PITCH"]; }
+ Q_PROPERTY(Fact* RC_MAP_POSCTL_SW READ getRC_MAP_POSCTL_SW CONSTANT) Fact* getRC_MAP_POSCTL_SW(void) { return _mapParameterName2Fact["RC_MAP_POSCTL_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_RETURN_SW READ getRC_MAP_RETURN_SW CONSTANT) Fact* getRC_MAP_RETURN_SW(void) { return _mapParameterName2Fact["RC_MAP_RETURN_SW"]; }
+ Q_PROPERTY(Fact* RC_MAP_ROLL READ getRC_MAP_ROLL CONSTANT) Fact* getRC_MAP_ROLL(void) { return _mapParameterName2Fact["RC_MAP_ROLL"]; }
+ Q_PROPERTY(Fact* RC_MAP_THROTTLE READ getRC_MAP_THROTTLE CONSTANT) Fact* getRC_MAP_THROTTLE(void) { return _mapParameterName2Fact["RC_MAP_THROTTLE"]; }
+ Q_PROPERTY(Fact* RC_MAP_YAW READ getRC_MAP_YAW CONSTANT) Fact* getRC_MAP_YAW(void) { return _mapParameterName2Fact["RC_MAP_YAW"]; }
+ Q_PROPERTY(Fact* RC_OFFB_TH READ getRC_OFFB_TH CONSTANT) Fact* getRC_OFFB_TH(void) { return _mapParameterName2Fact["RC_OFFB_TH"]; }
+ Q_PROPERTY(Fact* RC_POSCTL_TH READ getRC_POSCTL_TH CONSTANT) Fact* getRC_POSCTL_TH(void) { return _mapParameterName2Fact["RC_POSCTL_TH"]; }
+ Q_PROPERTY(Fact* RC_RETURN_TH READ getRC_RETURN_TH CONSTANT) Fact* getRC_RETURN_TH(void) { return _mapParameterName2Fact["RC_RETURN_TH"]; }
+ Q_PROPERTY(Fact* RTL_DESCEND_ALT READ getRTL_DESCEND_ALT CONSTANT) Fact* getRTL_DESCEND_ALT(void) { return _mapParameterName2Fact["RTL_DESCEND_ALT"]; }
+ Q_PROPERTY(Fact* RTL_LAND_DELAY READ getRTL_LAND_DELAY CONSTANT) Fact* getRTL_LAND_DELAY(void) { return _mapParameterName2Fact["RTL_LAND_DELAY"]; }
+ Q_PROPERTY(Fact* RTL_LOITER_RAD READ getRTL_LOITER_RAD CONSTANT) Fact* getRTL_LOITER_RAD(void) { return _mapParameterName2Fact["RTL_LOITER_RAD"]; }
+ Q_PROPERTY(Fact* RTL_RETURN_ALT READ getRTL_RETURN_ALT CONSTANT) Fact* getRTL_RETURN_ALT(void) { return _mapParameterName2Fact["RTL_RETURN_ALT"]; }
+ Q_PROPERTY(Fact* SDLOG_EXT READ getSDLOG_EXT CONSTANT) Fact* getSDLOG_EXT(void) { return _mapParameterName2Fact["SDLOG_EXT"]; }
+ Q_PROPERTY(Fact* SDLOG_RATE READ getSDLOG_RATE CONSTANT) Fact* getSDLOG_RATE(void) { return _mapParameterName2Fact["SDLOG_RATE"]; }
+ Q_PROPERTY(Fact* SENS_ACC_XOFF READ getSENS_ACC_XOFF CONSTANT) Fact* getSENS_ACC_XOFF(void) { return _mapParameterName2Fact["SENS_ACC_XOFF"]; }
+ Q_PROPERTY(Fact* SENS_ACC_XSCALE READ getSENS_ACC_XSCALE CONSTANT) Fact* getSENS_ACC_XSCALE(void) { return _mapParameterName2Fact["SENS_ACC_XSCALE"]; }
+ Q_PROPERTY(Fact* SENS_ACC_YOFF READ getSENS_ACC_YOFF CONSTANT) Fact* getSENS_ACC_YOFF(void) { return _mapParameterName2Fact["SENS_ACC_YOFF"]; }
+ Q_PROPERTY(Fact* SENS_ACC_YSCALE READ getSENS_ACC_YSCALE CONSTANT) Fact* getSENS_ACC_YSCALE(void) { return _mapParameterName2Fact["SENS_ACC_YSCALE"]; }
+ Q_PROPERTY(Fact* SENS_ACC_ZOFF READ getSENS_ACC_ZOFF CONSTANT) Fact* getSENS_ACC_ZOFF(void) { return _mapParameterName2Fact["SENS_ACC_ZOFF"]; }
+ Q_PROPERTY(Fact* SENS_ACC_ZSCALE READ getSENS_ACC_ZSCALE CONSTANT) Fact* getSENS_ACC_ZSCALE(void) { return _mapParameterName2Fact["SENS_ACC_ZSCALE"]; }
+ Q_PROPERTY(Fact* SENS_BARO_QNH READ getSENS_BARO_QNH CONSTANT) Fact* getSENS_BARO_QNH(void) { return _mapParameterName2Fact["SENS_BARO_QNH"]; }
+ Q_PROPERTY(Fact* SENS_BOARD_ROT READ getSENS_BOARD_ROT CONSTANT) Fact* getSENS_BOARD_ROT(void) { return _mapParameterName2Fact["SENS_BOARD_ROT"]; }
+ Q_PROPERTY(Fact* SENS_BOARD_X_OFF READ getSENS_BOARD_X_OFF CONSTANT) Fact* getSENS_BOARD_X_OFF(void) { return _mapParameterName2Fact["SENS_BOARD_X_OFF"]; }
+ Q_PROPERTY(Fact* SENS_BOARD_Y_OFF READ getSENS_BOARD_Y_OFF CONSTANT) Fact* getSENS_BOARD_Y_OFF(void) { return _mapParameterName2Fact["SENS_BOARD_Y_OFF"]; }
+ Q_PROPERTY(Fact* SENS_BOARD_Z_OFF READ getSENS_BOARD_Z_OFF CONSTANT) Fact* getSENS_BOARD_Z_OFF(void) { return _mapParameterName2Fact["SENS_BOARD_Z_OFF"]; }
+ Q_PROPERTY(Fact* SENS_DPRES_ANSC READ getSENS_DPRES_ANSC CONSTANT) Fact* getSENS_DPRES_ANSC(void) { return _mapParameterName2Fact["SENS_DPRES_ANSC"]; }
+ Q_PROPERTY(Fact* SENS_DPRES_OFF READ getSENS_DPRES_OFF CONSTANT) Fact* getSENS_DPRES_OFF(void) { return _mapParameterName2Fact["SENS_DPRES_OFF"]; }
+ Q_PROPERTY(Fact* SENS_EXT_MAG READ getSENS_EXT_MAG CONSTANT) Fact* getSENS_EXT_MAG(void) { return _mapParameterName2Fact["SENS_EXT_MAG"]; }
+ Q_PROPERTY(Fact* SENS_EXT_MAG_ROT READ getSENS_EXT_MAG_ROT CONSTANT) Fact* getSENS_EXT_MAG_ROT(void) { return _mapParameterName2Fact["SENS_EXT_MAG_ROT"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_XOFF READ getSENS_GYRO_XOFF CONSTANT) Fact* getSENS_GYRO_XOFF(void) { return _mapParameterName2Fact["SENS_GYRO_XOFF"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_XSCALE READ getSENS_GYRO_XSCALE CONSTANT) Fact* getSENS_GYRO_XSCALE(void) { return _mapParameterName2Fact["SENS_GYRO_XSCALE"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_YOFF READ getSENS_GYRO_YOFF CONSTANT) Fact* getSENS_GYRO_YOFF(void) { return _mapParameterName2Fact["SENS_GYRO_YOFF"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_YSCALE READ getSENS_GYRO_YSCALE CONSTANT) Fact* getSENS_GYRO_YSCALE(void) { return _mapParameterName2Fact["SENS_GYRO_YSCALE"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_ZOFF READ getSENS_GYRO_ZOFF CONSTANT) Fact* getSENS_GYRO_ZOFF(void) { return _mapParameterName2Fact["SENS_GYRO_ZOFF"]; }
+ Q_PROPERTY(Fact* SENS_GYRO_ZSCALE READ getSENS_GYRO_ZSCALE CONSTANT) Fact* getSENS_GYRO_ZSCALE(void) { return _mapParameterName2Fact["SENS_GYRO_ZSCALE"]; }
+ Q_PROPERTY(Fact* SENS_MAG_XOFF READ getSENS_MAG_XOFF CONSTANT) Fact* getSENS_MAG_XOFF(void) { return _mapParameterName2Fact["SENS_MAG_XOFF"]; }
+ Q_PROPERTY(Fact* SENS_MAG_XSCALE READ getSENS_MAG_XSCALE CONSTANT) Fact* getSENS_MAG_XSCALE(void) { return _mapParameterName2Fact["SENS_MAG_XSCALE"]; }
+ Q_PROPERTY(Fact* SENS_MAG_YOFF READ getSENS_MAG_YOFF CONSTANT) Fact* getSENS_MAG_YOFF(void) { return _mapParameterName2Fact["SENS_MAG_YOFF"]; }
+ Q_PROPERTY(Fact* SENS_MAG_YSCALE READ getSENS_MAG_YSCALE CONSTANT) Fact* getSENS_MAG_YSCALE(void) { return _mapParameterName2Fact["SENS_MAG_YSCALE"]; }
+ Q_PROPERTY(Fact* SENS_MAG_ZOFF READ getSENS_MAG_ZOFF CONSTANT) Fact* getSENS_MAG_ZOFF(void) { return _mapParameterName2Fact["SENS_MAG_ZOFF"]; }
+ Q_PROPERTY(Fact* SENS_MAG_ZSCALE READ getSENS_MAG_ZSCALE CONSTANT) Fact* getSENS_MAG_ZSCALE(void) { return _mapParameterName2Fact["SENS_MAG_ZSCALE"]; }
+ Q_PROPERTY(Fact* SO3_COMP_KI READ getSO3_COMP_KI CONSTANT) Fact* getSO3_COMP_KI(void) { return _mapParameterName2Fact["SO3_COMP_KI"]; }
+ Q_PROPERTY(Fact* SO3_COMP_KP READ getSO3_COMP_KP CONSTANT) Fact* getSO3_COMP_KP(void) { return _mapParameterName2Fact["SO3_COMP_KP"]; }
+ Q_PROPERTY(Fact* SO3_PITCH_OFFS READ getSO3_PITCH_OFFS CONSTANT) Fact* getSO3_PITCH_OFFS(void) { return _mapParameterName2Fact["SO3_PITCH_OFFS"]; }
+ Q_PROPERTY(Fact* SO3_ROLL_OFFS READ getSO3_ROLL_OFFS CONSTANT) Fact* getSO3_ROLL_OFFS(void) { return _mapParameterName2Fact["SO3_ROLL_OFFS"]; }
+ Q_PROPERTY(Fact* SO3_YAW_OFFS READ getSO3_YAW_OFFS CONSTANT) Fact* getSO3_YAW_OFFS(void) { return _mapParameterName2Fact["SO3_YAW_OFFS"]; }
+ Q_PROPERTY(Fact* SYS_AUTOCONFIG READ getSYS_AUTOCONFIG CONSTANT) Fact* getSYS_AUTOCONFIG(void) { return _mapParameterName2Fact["SYS_AUTOCONFIG"]; }
+ Q_PROPERTY(Fact* SYS_AUTOSTART READ getSYS_AUTOSTART CONSTANT) Fact* getSYS_AUTOSTART(void) { return _mapParameterName2Fact["SYS_AUTOSTART"]; }
+ Q_PROPERTY(Fact* SYS_RESTART_TYPE READ getSYS_RESTART_TYPE CONSTANT) Fact* getSYS_RESTART_TYPE(void) { return _mapParameterName2Fact["SYS_RESTART_TYPE"]; }
+ Q_PROPERTY(Fact* SYS_USE_IO READ getSYS_USE_IO CONSTANT) Fact* getSYS_USE_IO(void) { return _mapParameterName2Fact["SYS_USE_IO"]; }
+ Q_PROPERTY(Fact* TEST_D READ getTEST_D CONSTANT) Fact* getTEST_D(void) { return _mapParameterName2Fact["TEST_D"]; }
+ Q_PROPERTY(Fact* TEST_DEV READ getTEST_DEV CONSTANT) Fact* getTEST_DEV(void) { return _mapParameterName2Fact["TEST_DEV"]; }
+ Q_PROPERTY(Fact* TEST_D_LP READ getTEST_D_LP CONSTANT) Fact* getTEST_D_LP(void) { return _mapParameterName2Fact["TEST_D_LP"]; }
+ Q_PROPERTY(Fact* TEST_HP READ getTEST_HP CONSTANT) Fact* getTEST_HP(void) { return _mapParameterName2Fact["TEST_HP"]; }
+ Q_PROPERTY(Fact* TEST_I READ getTEST_I CONSTANT) Fact* getTEST_I(void) { return _mapParameterName2Fact["TEST_I"]; }
+ Q_PROPERTY(Fact* TEST_I_MAX READ getTEST_I_MAX CONSTANT) Fact* getTEST_I_MAX(void) { return _mapParameterName2Fact["TEST_I_MAX"]; }
+ Q_PROPERTY(Fact* TEST_LP READ getTEST_LP CONSTANT) Fact* getTEST_LP(void) { return _mapParameterName2Fact["TEST_LP"]; }
+ Q_PROPERTY(Fact* TEST_MAX READ getTEST_MAX CONSTANT) Fact* getTEST_MAX(void) { return _mapParameterName2Fact["TEST_MAX"]; }
+ Q_PROPERTY(Fact* TEST_MEAN READ getTEST_MEAN CONSTANT) Fact* getTEST_MEAN(void) { return _mapParameterName2Fact["TEST_MEAN"]; }
+ Q_PROPERTY(Fact* TEST_MIN READ getTEST_MIN CONSTANT) Fact* getTEST_MIN(void) { return _mapParameterName2Fact["TEST_MIN"]; }
+ Q_PROPERTY(Fact* TEST_P READ getTEST_P CONSTANT) Fact* getTEST_P(void) { return _mapParameterName2Fact["TEST_P"]; }
+ Q_PROPERTY(Fact* TEST_TRIM READ getTEST_TRIM CONSTANT) Fact* getTEST_TRIM(void) { return _mapParameterName2Fact["TEST_TRIM"]; }
+ Q_PROPERTY(Fact* TRIM_PITCH READ getTRIM_PITCH CONSTANT) Fact* getTRIM_PITCH(void) { return _mapParameterName2Fact["TRIM_PITCH"]; }
+ Q_PROPERTY(Fact* TRIM_ROLL READ getTRIM_ROLL CONSTANT) Fact* getTRIM_ROLL(void) { return _mapParameterName2Fact["TRIM_ROLL"]; }
+ Q_PROPERTY(Fact* TRIM_YAW READ getTRIM_YAW CONSTANT) Fact* getTRIM_YAW(void) { return _mapParameterName2Fact["TRIM_YAW"]; }
+ Q_PROPERTY(Fact* UAVCAN_BITRATE READ getUAVCAN_BITRATE CONSTANT) Fact* getUAVCAN_BITRATE(void) { return _mapParameterName2Fact["UAVCAN_BITRATE"]; }
+ Q_PROPERTY(Fact* UAVCAN_ENABLE READ getUAVCAN_ENABLE CONSTANT) Fact* getUAVCAN_ENABLE(void) { return _mapParameterName2Fact["UAVCAN_ENABLE"]; }
+ Q_PROPERTY(Fact* UAVCAN_NODE_ID READ getUAVCAN_NODE_ID CONSTANT) Fact* getUAVCAN_NODE_ID(void) { return _mapParameterName2Fact["UAVCAN_NODE_ID"]; }
+
+public:
+ /// @param uas Uas which this set of facts is associated with
+ PX4ParameterFacts(UASInterface* uas, QObject* parent = NULL);
+
+ ~PX4ParameterFacts();
+
+ static void loadParameterFactMetaData(void);
+ static void deleteParameterFactMetaData(void);
+
+private slots:
+ /// Connected to UASInterface::parameterChanged
+ void _parameterChanged(int uas, int component, QString parameterName, QVariant value);
+
+ /// Signalled from Fact to indicate value was changed through the property write accessor
+ void _valueUpdated(QVariant& value);
+
+private:
+ static FactMetaData* _parseParameter(QXmlStreamReader& xml, const QString& group);
+ static void _initMetaData(FactMetaData* metaData);
+ static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false);
+
+ QMap _mapParameterName2Fact; ///< Maps from a parameter name to a Fact
+ QMap _mapFact2ParameterName; ///< Maps from a Fact to a parameter name
+
+ static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData
+
+ int _uasId; ///< Id for uas which this set of Facts are associated with
+ int _lastSeenComponent;
+
+ QGCUASParamManagerInterface* _paramMgr;
+};
+
+#endif
\ No newline at end of file
diff --git a/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
new file mode 100644
index 0000000..9e7b01f
--- /dev/null
+++ b/src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml
@@ -0,0 +1,3037 @@
+
+
+
+
+ Empty cell voltage
+ Defines the voltage where a single cell of the battery is considered empty.
+ 3.4
+
+
+ Full cell voltage
+ Defines the voltage where a single cell of the battery is considered full.
+ 4.2
+
+
+ Voltage drop per cell on 100% load
+ This implicitely defines the internal resistance
+ to maximum current ratio and assumes linearity.
+ 0.07
+
+
+ Number of cells
+ Defines the number of cells the attached battery consists of.
+ 3
+
+
+ Battery capacity
+ Defines the capacity of the attached battery.
+ -1.0
+
+
+ Scaling factor for battery voltage sensor on PX4IO
+ 10000
+
+
+ Scaling factor for battery voltage sensor on FMU v2
+ 0.0082
+
+
+ Scaling factor for battery voltage sensor on AeroCore
+ For R70 = 133K, R71 = 10K --> scale = 1.8 * 143 / (4096*10) = 0.0063
+ 0.0063
+
+
+ Scaling factor for battery voltage sensor on FMU v1
+ FMUv1 standalone: 1/(10 / (47+10)) * (3.3 / 4095) = 0.00459340659
+ FMUv1 with PX4IO: 0.00459340659
+ FMUv1 with PX4IOAR: (3.3f * 52.0f / 5.0f / 4095.0f) = 0.00838095238
+ 0.00459340659
+
+
+ Scaling factor for battery current sensor
+ 0.0124
+
+
+
+
+ Circuit breaker for power supply check
+ Setting this parameter to 894281 will disable the power valid
+ checks in the commander.
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 0
+ 0
+ 894281
+
+
+ Circuit breaker for rate controller output
+ Setting this parameter to 140253 will disable the rate
+ controller uORB publication.
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 0
+ 0
+ 140253
+
+
+ Circuit breaker for IO safety
+ Setting this parameter to 894281 will disable IO safety.
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 0
+ 0
+ 22027
+
+
+ Circuit breaker for airspeed sensor
+ Setting this parameter to 162128 will disable the check for an airspeed sensor.
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 0
+ 0
+ 162128
+
+
+ Circuit breaker for flight termination
+ Setting this parameter to 121212 will disable the flight termination action.
+ --> The IO driver will not do flight termination if requested by the FMU
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 121212
+ 0
+ 121212
+
+
+ Circuit breaker for engine failure detection
+ Setting this parameter to 284953 will disable the engine failure detection.
+ If the aircraft is in engine failure mode the enine failure flag will be
+ set to healthy
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 284953
+ 0
+ 284953
+
+
+ Circuit breaker for gps failure detection
+ Setting this parameter to 240024 will disable the gps failure detection.
+ If the aircraft is in gps failure mode the gps failure flag will be
+ set to healthy
+ WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK
+ 240024
+ 0
+ 240024
+
+
+
+
+ Comms hold wait time
+ The amount of time in seconds the system should wait at the comms hold waypoint
+ 120.0
+ 0.0
+ seconds
+
+
+ Comms hold Lat
+ Latitude of comms hold waypoint
+ -266072120
+ 0
+ degrees * 1e7
+
+
+ Comms hold Lon
+ Longitude of comms hold waypoint
+ 1518453890
+ 0
+ degrees * 1e7
+
+
+ Comms hold alt
+ Altitude of comms hold waypoint
+ 600.0
+ 0.0
+ m
+
+
+ Aifield hole wait time
+ The amount of time in seconds the system should wait at the airfield home waypoint
+ 120.0
+ 0.0
+ seconds
+
+
+ Number of allowed Datalink timeouts
+ After more than this number of data link timeouts the aircraft returns home directly
+ 2
+ 0
+ 1000
+
+
+ Skip comms hold wp
+ If set to 1 the system will skip the comms hold wp on data link loss and will directly fly to
+ airfield home
+ 0
+ 0
+ 1
+
+
+ Airfield home Lat
+ Latitude of airfield home waypoint
+ -265847810
+ 0
+ degrees * 1e7
+
+
+ Airfield home Lon
+ Longitude of airfield home waypoint
+ 1518423250
+ 0
+ degrees * 1e7
+
+
+ Airfield home alt
+ Altitude of airfield home waypoint
+ 600.0
+ 0.0
+ m
+
+
+
+
+ Attitude Time Constant
+ This defines the latency between a step input and the achieved setpoint
+ (inverse to a P gain). Half a second is a good start value and fits for
+ most average systems. Smaller systems may require smaller values, but as
+ this will wear out servos faster, the value should only be decreased as
+ needed.
+ 0.5
+ 0.4
+ 1.0
+ seconds
+
+
+ Pitch rate proportional gain
+ This defines how much the elevator input will be commanded depending on the
+ current body angular rate error.
+ 0.05
+
+
+ Pitch rate integrator gain
+ This gain defines how much control response will result out of a steady
+ state error. It trims any constant error.
+ 0.0
+ 0.0
+ 50.0
+
+
+ Maximum positive / up pitch rate
+ This limits the maximum pitch up angular rate the controller will output (in
+ degrees per second). Setting a value of zero disables the limit.
+ 0.0
+ 0.0
+ 90.0
+ deg/s
+
+
+ Maximum negative / down pitch rate
+ This limits the maximum pitch down up angular rate the controller will
+ output (in degrees per second). Setting a value of zero disables the limit.
+ 0.0
+ 0.0
+ 90.0
+ deg/s
+
+
+ Pitch rate integrator limit
+ The portion of the integrator part in the control surface deflection is
+ limited to this value
+ 0.2
+ 0.0
+ 1.0
+
+
+ Roll to Pitch feedforward gain
+ This compensates during turns and ensures the nose stays level.
+ 0.0
+ 0.0
+ 2.0
+
+
+ Roll rate proportional Gain
+ This defines how much the aileron input will be commanded depending on the
+ current body angular rate error.
+ 0.05
+
+
+ Roll rate integrator Gain
+ This gain defines how much control response will result out of a steady
+ state error. It trims any constant error.
+ 0.0
+ 0.0
+ 100.0
+
+
+ Roll Integrator Anti-Windup
+ The portion of the integrator part in the control surface deflection is limited to this value.
+ 0.2
+ 0.0
+ 1.0
+
+
+ Maximum Roll Rate
+ This limits the maximum roll rate the controller will output (in degrees per
+ second). Setting a value of zero disables the limit.
+ 0.0
+ 0.0
+ 90.0
+ deg/s
+
+
+ Yaw rate proportional gain
+ This defines how much the rudder input will be commanded depending on the
+ current body angular rate error.
+ 0.05
+
+
+ Yaw rate integrator gain
+ This gain defines how much control response will result out of a steady
+ state error. It trims any constant error.
+ 0.0
+ 0.0
+ 50.0
+
+
+ Yaw rate integrator limit
+ The portion of the integrator part in the control surface deflection is
+ limited to this value
+ 0.2
+ 0.0
+ 1.0
+
+
+ Maximum Yaw Rate
+ This limits the maximum yaw rate the controller will output (in degrees per
+ second). Setting a value of zero disables the limit.
+ 0.0
+ 0.0
+ 90.0
+ deg/s
+
+
+ Roll rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.3
+ 0.0
+ 10.0
+
+
+ Pitch rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.4
+ 0.0
+ 10.0
+
+
+ Yaw rate feed forward
+ Direct feed forward from rate setpoint to control surface output
+ 0.3
+ 0.0
+ 10.0
+
+
+ Minimal speed for yaw coordination
+ For airspeeds above this value, the yaw rate is calculated for a coordinated
+ turn. Set to a very high value to disable.
+ 1000.0
+ m/s
+
+
+ Minimum Airspeed
+ If the airspeed falls below this value, the TECS controller will try to
+ increase airspeed more aggressively.
+ 13.0
+ 0.0
+ 30.0
+ m/s
+
+
+ Trim Airspeed
+ The TECS controller tries to fly at this airspeed.
+ 20.0
+ 0.0
+ 30.0
+ m/s
+
+
+ Maximum Airspeed
+ If the airspeed is above this value, the TECS controller will try to decrease
+ airspeed more aggressively.
+ 50.0
+ 0.0
+ 30.0
+ m/s
+
+
+ Roll Setpoint Offset
+ An airframe specific offset of the roll setpoint in degrees, the value is
+ added to the roll setpoint and should correspond to the typical cruise speed
+ of the airframe.
+ 0.0
+ -90.0
+ 90.0
+ deg
+
+
+ Pitch Setpoint Offset
+ An airframe specific offset of the pitch setpoint in degrees, the value is
+ added to the pitch setpoint and should correspond to the typical cruise
+ speed of the airframe.
+ 0.0
+ -90.0
+ 90.0
+ deg
+
+
+ Max Manual Roll
+ Max roll for manual control in attitude stabilized mode
+ 45.0
+ 0.0
+ 90.0
+ deg
+
+
+ Max Manual Pitch
+ Max pitch for manual control in attitude stabilized mode
+ 45.0
+ 0.0
+ 90.0
+ deg
+
+
+
+
+ Minimum descent rate
+ This is the sink rate of the aircraft with the throttle
+ set to THR_MIN and flown at the same airspeed as used
+ to measure FW_T_CLMB_MAX.
+ 2.0
+
+
+ Maximum descent rate
+ This sets the maximum descent rate that the controller will use.
+ If this value is too large, the aircraft can over-speed on descent.
+ This should be set to a value that can be achieved without
+ exceeding the lower pitch angle limit and without over-speeding
+ the aircraft.
+ 5.0
+
+
+ TECS time constant
+ This is the time constant of the TECS control algorithm (in seconds).
+ Smaller values make it faster to respond, larger values make it slower
+ to respond.
+ 5.0
+
+
+ TECS Throttle time constant
+ This is the time constant of the TECS throttle control algorithm (in seconds).
+ Smaller values make it faster to respond, larger values make it slower
+ to respond.
+ 8.0
+
+
+ Throttle damping factor
+ This is the damping gain for the throttle demand loop.
+ Increase to add damping to correct for oscillations in speed and height.
+ 0.5
+
+
+ Integrator gain
+ This is the integrator gain on the control loop.
+ Increasing this gain increases the speed at which speed
+ and height offsets are trimmed out, but reduces damping and
+ increases overshoot.
+ 0.1
+
+
+ Maximum vertical acceleration
+ This is the maximum vertical acceleration (in metres/second square)
+ either up or down that the controller will use to correct speed
+ or height errors. The default value of 7 m/s/s (equivalent to +- 0.7 g)
+ allows for reasonably aggressive pitch changes if required to recover
+ from under-speed conditions.
+ 7.0
+
+
+ Complementary filter "omega" parameter for height
+ This is the cross-over frequency (in radians/second) of the complementary
+ filter used to fuse vertical acceleration and barometric height to obtain
+ an estimate of height rate and height. Increasing this frequency weights
+ the solution more towards use of the barometer, whilst reducing it weights
+ the solution more towards use of the accelerometer data.
+ 3.0
+
+
+ Complementary filter "omega" parameter for speed
+ This is the cross-over frequency (in radians/second) of the complementary
+ filter used to fuse longitudinal acceleration and airspeed to obtain an
+ improved airspeed estimate. Increasing this frequency weights the solution
+ more towards use of the arispeed sensor, whilst reducing it weights the
+ solution more towards use of the accelerometer data.
+ 2.0
+
+
+ Roll -> Throttle feedforward
+ Increasing this gain turn increases the amount of throttle that will
+ be used to compensate for the additional drag created by turning.
+ Ideally this should be set to approximately 10 x the extra sink rate
+ in m/s created by a 45 degree bank turn. Increase this gain if
+ the aircraft initially loses energy in turns and reduce if the
+ aircraft initially gains energy in turns. Efficient high aspect-ratio
+ aircraft (eg powered sailplanes) can use a lower value, whereas
+ inefficient low aspect-ratio models (eg delta wings) can use a higher value.
+ 10.0
+
+
+ Speed <--> Altitude priority
+ This parameter adjusts the amount of weighting that the pitch control
+ applies to speed vs height errors. Setting it to 0.0 will cause the
+ pitch control to control height and ignore speed errors. This will
+ normally improve height accuracy but give larger airspeed errors.
+ Setting it to 2.0 will cause the pitch control loop to control speed
+ and ignore height errors. This will normally reduce airspeed errors,
+ but give larger height errors. The default value of 1.0 allows the pitch
+ control to simultaneously control height and speed.
+ Note to Glider Pilots - set this parameter to 2.0 (The glider will
+ adjust its pitch angle to maintain airspeed, ignoring changes in height).
+ 1.0
+
+
+ Pitch damping factor
+ This is the damping gain for the pitch demand loop. Increase to add
+ damping to correct for oscillations in height. The default value of 0.0
+ will work well provided the pitch to servo controller has been tuned
+ properly.
+ 0.0
+
+
+ Height rate P factor
+ 0.05
+
+
+ Height rate FF factor
+ 0.0
+
+
+ Speed rate P factor
+ 0.05
+
+
+
+
+ Loiter time
+ The amount of time in seconds the system should do open loop loiter and wait for gps recovery
+ before it goes into flight termination.
+ 30.0
+ 0.0
+ seconds
+
+
+ Open loop loiter roll
+ Roll in degrees during the open loop loiter
+ 15.0
+ 0.0
+ 30.0
+ deg
+
+
+ Open loop loiter pitch
+ Pitch in degrees during the open loop loiter
+ 0.0
+ -30.0
+ 30.0
+ deg
+
+
+ Open loop loiter thrust
+ Thrust value which is set during the open loop loiter
+ 0.7
+ 0.0
+ 1.0
+
+
+
+
+ Enable geofence
+ Set to 1 to enable geofence.
+ Defaults to 1 because geofence is only enabled when the geofence.txt file is present.
+ 1
+ 0
+ 1
+
+
+ Geofence altitude mode
+ Select which altitude reference should be used
+ 0 = WGS84, 1 = AMSL
+ 0
+ 0
+ 1
+
+
+ Geofence source
+ Select which position source should be used. Selecting GPS instead of global position makes sure that there is
+ no dependence on the position estimator
+ 0 = global position, 1 = GPS
+ 0
+ 0
+ 1
+
+
+ Geofence counter limit
+ Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered
+ -1
+ -1
+ 10
+
+
+
+
+ L1 period
+ This is the L1 distance and defines the tracking
+ point ahead of the aircraft its following.
+ A value of 25 meters works for most aircraft. Shorten
+ slowly during tuning until response is sharp without oscillation.
+ 25.0
+ 1.0
+ 100.0
+
+
+ L1 damping
+ Damping factor for L1 control.
+ 0.75
+ 0.6
+ 0.9
+
+
+ Cruise throttle
+ This is the throttle setting required to achieve the desired cruise speed. Most airframes have a value of 0.5-0.7.
+ 0.7
+ 0.0
+ 1.0
+
+
+ Throttle max slew rate
+ Maximum slew rate for the commanded throttle
+ 0.0
+ 0.0
+ 1.0
+
+
+ Negative pitch limit
+ The minimum negative pitch the controller will output.
+ -45.0
+ -60.0
+ 0.0
+ degrees
+
+
+ Positive pitch limit
+ The maximum positive pitch the controller will output.
+ 45.0
+ 0.0
+ 60.0
+ degrees
+
+
+ Controller roll limit
+ The maximum roll the controller will output.
+ 45.0
+ 0.0
+ degrees
+
+
+ Throttle limit max
+ This is the maximum throttle % that can be used by the controller.
+ For overpowered aircraft, this should be reduced to a value that
+ provides sufficient thrust to climb at the maximum pitch angle PTCH_MAX.
+ 1.0
+
+
+ Throttle limit min
+ This is the minimum throttle % that can be used by the controller.
+ For electric aircraft this will normally be set to zero, but can be set
+ to a small non-zero value if a folding prop is fitted to prevent the
+ prop from folding and unfolding repeatedly in-flight or to provide
+ some aerodynamic drag from a turning prop to improve the descent rate.
+ For aircraft with internal combustion engine this parameter should be set
+ for desired idle rpm.
+ 0.0
+
+
+ Throttle limit value before flare
+ This throttle value will be set as throttle limit at FW_LND_TLALT,
+ before arcraft will flare.
+ 1.0
+
+
+ Climbout Altitude difference
+ If the altitude error exceeds this parameter, the system will climb out
+ with maximum throttle and minimum airspeed until it is closer than this
+ distance to the desired altitude. Mostly used for takeoff waypoints / modes.
+ Set to zero to disable climbout mode (not recommended).
+ 25.0
+
+
+ Maximum climb rate
+ This is the best climb rate that the aircraft can achieve with
+ the throttle set to THR_MAX and the airspeed set to the
+ default value. For electric aircraft make sure this number can be
+ achieved towards the end of flight when the battery voltage has reduced.
+ The setting of this parameter can be checked by commanding a positive
+ altitude change of 100m in loiter, RTL or guided mode. If the throttle
+ required to climb is close to THR_MAX and the aircraft is maintaining
+ airspeed, then this parameter is set correctly. If the airspeed starts
+ to reduce, then the parameter is set to high, and if the throttle
+ demand required to climb and maintain speed is noticeably less than
+ FW_THR_MAX, then either FW_T_CLMB_MAX should be increased or
+ FW_THR_MAX reduced.
+ 5.0
+
+
+ Landing slope angle
+ 5.0
+
+
+ FW_LND_HVIRT
+ 10.0
+
+
+ Landing flare altitude (relative to landing altitude)
+ 8.0
+ meter
+
+
+ Landing throttle limit altitude (relative landing altitude)
+ Default of -1.0f lets the system default to applying throttle
+ limiting at 2/3 of the flare altitude.
+ -1.0
+ meter
+
+
+ Landing heading hold horizontal distance
+ 15.0
+
+
+ Enable or disable usage of terrain estimate during landing
+ 0: disabled, 1: enabled
+ 0
+
+
+
+
+ Enable launch detection
+ 0
+ 0
+ 1
+
+
+ Catapult accelerometer theshold
+ LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
+ 30.0
+ 0
+
+
+ Catapult time theshold
+ LAUN_CAT_A * LAUN_CAT_T serves as threshold to trigger launch detection.
+ 0.05
+ 0
+
+
+ Motor delay
+ Delay between starting attitude control and powering up the throttle (giving throttle control to the controller)
+ Before this timespan is up the throttle will be set to LAUN_THR_PRE, set to 0 to deactivate
+ 0.0
+ 0
+ seconds
+
+
+ Maximum pitch before the throttle is powered up (during motor delay phase)
+ This is an extra limit for the maximum pitch which is imposed in the phase before the throttle turns on.
+ This allows to limit the maximum pitch angle during a bungee launch (make the launch less steep).
+ 30.0
+ 0
+ 45
+ deg
+
+
+ Throttle setting while detecting launch
+ The throttle is set to this value while the system is waiting for the take-off.
+ 0.0
+ 0
+ 1
+
+
+
+
+ MAVLink system ID
+ 1
+
+
+ MAVLink component ID
+ 50
+
+
+ MAVLink type
+ MAV_TYPE_FIXED_WING
+
+
+ Use/Accept HIL GPS message (even if not in HIL mode)
+ If set to 1 incomming HIL GPS messages are parsed
+ 0
+
+
+ Forward external setpoint messages
+ If set to 1 incomming external setpoint messages will be directly forwarded to the controllers if in offboard
+ control mode
+ 1
+
+
+
+
+ Take-off altitude
+ Even if first waypoint has altitude less then MIS_TAKEOFF_ALT above home position, system will climb to
+ MIS_TAKEOFF_ALT on takeoff, then go to waypoint.
+ 10.0
+ meters
+
+
+ Enable persistent onboard mission storage
+ When enabled, missions that have been uploaded by the GCS are stored
+ and reloaded after reboot persistently.
+ 1
+ 0
+ 1
+
+
+ Maximal horizontal distance from home to first waypoint
+ Failsafe check to prevent running mission stored from previous flight at a new takeoff location.
+ Set a value of zero or less to disable. The mission will not be started if the current
+ waypoint is more distant than MIS_DIS_1WP from the current position.
+ 500
+ 0
+ 1000
+
+
+ Altitude setpoint mode
+ 0: the system will follow a zero order hold altitude setpoint
+ 1: the system will follow a first order hold altitude setpoint
+ values follow the definition in enum mission_altitude_mode
+ 0
+ 0
+ 1
+
+
+ Loiter radius (FW only)
+ Default value of loiter radius for missions, loiter, RTL, etc. (fixedwing only).
+ 50.0
+ 0.0
+ meters
+
+
+ Acceptance Radius
+ Default acceptance radius, overridden by acceptance radius of waypoint if set.
+ 25.0
+ 1.0
+ meters
+
+
+ Set OBC mode for data link loss
+ If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
+ 0
+ 0
+
+
+ Set OBC mode for rc loss
+ If set to 1 the behaviour on data link loss is set to a mode according to the OBC rules
+ 0
+ 0
+
+
+
+
+ Roll P gain
+ Roll proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
+ 6.0
+ 0.0
+
+
+ Roll rate P gain
+ Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.1
+ 0.0
+
+
+ Roll rate I gain
+ Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
+ 0.0
+ 0.0
+
+
+ Roll rate D gain
+ Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.002
+ 0.0
+
+
+ Pitch P gain
+ Pitch proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
+ 6.0
+ 0.0
+ 1/s
+
+
+ Pitch rate P gain
+ Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.1
+ 0.0
+
+
+ Pitch rate I gain
+ Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
+ 0.0
+ 0.0
+
+
+ Pitch rate D gain
+ Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.002
+ 0.0
+
+
+ Yaw P gain
+ Yaw proportional gain, i.e. desired angular speed in rad/s for error 1 rad.
+ 2.0
+ 0.0
+ 1/s
+
+
+ Yaw rate P gain
+ Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.
+ 0.3
+ 0.0
+
+
+ Yaw rate I gain
+ Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.
+ 0.0
+ 0.0
+
+
+ Yaw rate D gain
+ Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.
+ 0.0
+ 0.0
+
+
+ Yaw feed forward
+ Feed forward weight for manual yaw control. 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ 0.5
+ 0.0
+ 1.0
+
+
+ Max yaw rate
+ Limit for yaw rate, has effect for large rotations in autonomous mode, to avoid large control output and mixer saturation.
+ 120.0
+ 0.0
+ 360.0
+ deg/s
+
+
+ Max manual roll
+ 35.0
+ 0.0
+ 90.0
+ deg
+
+
+ Max manual pitch
+ 35.0
+ 0.0
+ 90.0
+ deg
+
+
+ Max manual yaw rate
+ 120.0
+ 0.0
+ deg/s
+
+
+ Max acro roll rate
+ 90.0
+ 0.0
+ 360.0
+ deg/s
+
+
+ Max acro pitch rate
+ 90.0
+ 0.0
+ 360.0
+ deg/s
+
+
+ Max acro yaw rate
+ 120.0
+ 0.0
+ deg/s
+
+
+
+
+ Minimum thrust
+ Minimum vertical thrust. It's recommended to set it > 0 to avoid free fall with zero thrust.
+ 0.1
+ 0.0
+ 1.0
+
+
+ Maximum thrust
+ Limit max allowed thrust.
+ 1.0
+ 0.0
+ 1.0
+
+
+ Proportional gain for vertical position error
+ 1.0
+ 0.0
+
+
+ Proportional gain for vertical velocity error
+ 0.1
+ 0.0
+
+
+ Integral gain for vertical velocity error
+ Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.
+ 0.02
+ 0.0
+
+
+ Differential gain for vertical velocity error
+ 0.0
+ 0.0
+
+
+ Maximum vertical velocity
+ Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).
+ 5.0
+ 0.0
+ m/s
+
+
+ Vertical velocity feed forward
+ Feed forward weight for altitude control in stabilized modes (ALTCTRL, POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ 0.5
+ 0.0
+ 1.0
+
+
+ Proportional gain for horizontal position error
+ 1.0
+ 0.0
+
+
+ Proportional gain for horizontal velocity error
+ 0.1
+ 0.0
+
+
+ Integral gain for horizontal velocity error
+ Non-zero value allows to resist wind.
+ 0.02
+ 0.0
+
+
+ Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again
+ 0.01
+ 0.0
+
+
+ Maximum horizontal velocity
+ Maximum horizontal velocity in AUTO mode and endpoint for position stabilized mode (POSCTRL).
+ 5.0
+ 0.0
+ m/s
+
+
+ Horizontal velocity feed forward
+ Feed forward weight for position control in position control mode (POSCTRL). 0 will give slow responce and no overshot, 1 - fast responce and big overshot.
+ 0.5
+ 0.0
+ 1.0
+
+
+ Maximum tilt angle in air
+ Limits maximum tilt in AUTO and POSCTRL modes during flight.
+ 45.0
+ 0.0
+ 90.0
+ deg
+
+
+ Maximum tilt during landing
+ Limits maximum tilt angle on landing.
+ 15.0
+ 0.0
+ 90.0
+ deg
+
+
+ Landing descend rate
+ 1.0
+ 0.0
+ m/s
+
+
+
+
+ Ground drag property
+ This parameter encodes the ground drag coefficient and the corresponding
+ decrease in wind speed from the plane altitude to ground altitude.
+ 0.03
+ 0.001
+ 0.1
+ unknown
+
+
+ Plane turn radius
+ The planes known minimal turn radius - use a higher value
+ to make the plane maneuver more distant from the actual drop
+ position. This is to ensure the wings are level during the drop.
+ 120.0
+ 30.0
+ 500.0
+ meter
+
+
+ Drop precision
+ If the system is closer than this distance on passing over the
+ drop position, it will release the payload. This is a safeguard
+ to prevent a drop out of the required accuracy.
+ 30.0
+ 1.0
+ 80.0
+ meter
+
+
+ Payload drag coefficient of the dropped object
+ The drag coefficient (cd) is the typical drag
+ constant for air. It is in general object specific,
+ but the closest primitive shape to the actual object
+ should give good results:
+ http://en.wikipedia.org/wiki/Drag_coefficient
+ 0.1
+ 0.08
+ 1.5
+ meter
+
+
+ Payload mass
+ A typical small toy ball:
+ 0.025 kg
+ OBC water bottle:
+ 0.6 kg
+ 0.6
+ 0.001
+ 5.0
+ kilogram
+
+
+ Payload front surface area
+ A typical small toy ball:
+ (0.045 * 0.045) / 4.0 * pi = 0.001590 m^2
+ OBC water bottle:
+ (0.063 * 0.063) / 4.0 * pi = 0.003117 m^2
+ 0.00311724531
+ 0.001
+ 0.5
+ m^2
+
+
+
+
+ Velocity estimate delay
+ The delay in milliseconds of the velocity estimate from GPS.
+ 230
+ 0
+ 1000
+
+
+ Position estimate delay
+ The delay in milliseconds of the position estimate from GPS.
+ 210
+ 0
+ 1000
+
+
+ Height estimate delay
+ The delay in milliseconds of the height estimate from the barometer.
+ 350
+ 0
+ 1000
+
+
+ Mag estimate delay
+ The delay in milliseconds of the magnetic field estimate from
+ the magnetometer.
+ 30
+ 0
+ 1000
+
+
+ True airspeeed estimate delay
+ The delay in milliseconds of the airspeed estimate.
+ 210
+ 0
+ 1000
+
+
+ GPS vs. barometric altitude update weight
+ RE-CHECK this.
+ 0.9
+ 0.0
+ 1.0
+
+
+ Airspeed measurement noise
+ Increasing this value will make the filter trust this sensor
+ less and trust other sensors more.
+ 1.4
+ 0.5
+ 5.0
+
+
+ Velocity measurement noise in north-east (horizontal) direction
+ Generic default: 0.3, multicopters: 0.5, ground vehicles: 0.5
+ 0.3
+ 0.05
+ 5.0
+
+
+ Velocity noise in down (vertical) direction
+ Generic default: 0.5, multicopters: 0.7, ground vehicles: 0.7
+ 0.5
+ 0.05
+ 5.0
+
+
+ Position noise in north-east (horizontal) direction
+ Generic defaults: 0.5, multicopters: 0.5, ground vehicles: 0.5
+ 0.5
+ 0.1
+ 10.0
+
+
+ Position noise in down (vertical) direction
+ Generic defaults: 0.5, multicopters: 1.0, ground vehicles: 1.0
+ 0.5
+ 0.1
+ 10.0
+
+
+ Magnetometer measurement noise
+ Generic defaults: 0.05, multicopters: 0.05, ground vehicles: 0.05
+ 0.05
+ 0.1
+ 10.0
+
+
+ Gyro process noise
+ Generic defaults: 0.015, multicopters: 0.015, ground vehicles: 0.015.
+ This noise controls how much the filter trusts the gyro measurements.
+ Increasing it makes the filter trust the gyro less and other sensors more.
+ 0.015
+ 0.001
+ 0.05
+
+
+ Accelerometer process noise
+ Generic defaults: 0.25, multicopters: 0.25, ground vehicles: 0.25.
+ Increasing this value makes the filter trust the accelerometer less
+ and other sensors more.
+ 0.25
+ 0.05
+ 1.0
+
+
+ Gyro bias estimate process noise
+ Generic defaults: 1e-07f, multicopters: 1e-07f, ground vehicles: 1e-07f.
+ Increasing this value will make the gyro bias converge faster but noisier.
+ 1e-07
+ 0.0000001
+ 0.00001
+
+
+ Accelerometer bias estimate process noise
+ Generic defaults: 0.0001f, multicopters: 0.0001f, ground vehicles: 0.0001f.
+ Increasing this value makes the bias estimation faster and noisier.
+ 0.00005
+ 0.00001
+ 0.001
+
+
+ Magnetometer earth frame offsets process noise
+ Generic defaults: 0.0001, multicopters: 0.0001, ground vehicles: 0.0001.
+ Increasing this value makes the magnetometer earth bias estimate converge
+ faster but also noisier.
+ 0.0003
+ 0.0001
+ 0.01
+
+
+ Magnetometer body frame offsets process noise
+ Generic defaults: 0.0003, multicopters: 0.0003, ground vehicles: 0.0003.
+ Increasing this value makes the magnetometer body bias estimate converge faster
+ but also noisier.
+ 0.0003
+ 0.0001
+ 0.01
+
+
+ Threshold for filter initialization
+ If the standard deviation of the GPS position estimate is below this threshold
+ in meters, the filter will initialize.
+ 5.0
+ 0.3
+ 10.0
+
+
+
+
+ Z axis weight for barometer
+ Weight (cutoff frequency) for barometer altitude measurements.
+ 0.5
+ 0.0
+ 10.0
+
+
+ Z axis weight for GPS
+ Weight (cutoff frequency) for GPS altitude measurements. GPS altitude data is very noisy and should be used only as slow correction for baro offset.
+ 0.005
+ 0.0
+ 10.0
+
+
+ Z axis weight for vision
+ Weight (cutoff frequency) for vision altitude measurements. vision altitude data is very noisy and should be used only as slow correction for baro offset.
+ 0.5
+ 0.0
+ 10.0
+
+
+ Z axis weight for sonar
+ Weight (cutoff frequency) for sonar measurements.
+ 3.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for GPS position
+ Weight (cutoff frequency) for GPS position measurements.
+ 1.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for GPS velocity
+ Weight (cutoff frequency) for GPS velocity measurements.
+ 2.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for vision position
+ Weight (cutoff frequency) for vision position measurements.
+ 5.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for vision velocity
+ Weight (cutoff frequency) for vision velocity measurements.
+ 0.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for optical flow
+ Weight (cutoff frequency) for optical flow (velocity) measurements.
+ 5.0
+ 0.0
+ 10.0
+
+
+ XY axis weight for resetting velocity
+ When velocity sources lost slowly decrease estimated horizontal velocity with this weight.
+ 0.5
+ 0.0
+ 10.0
+
+
+ XY axis weight factor for GPS when optical flow available
+ When optical flow data available, multiply GPS weights (for position and velocity) by this factor.
+ 0.1
+ 0.0
+ 1.0
+
+
+ Accelerometer bias estimation weight
+ Weight (cutoff frequency) for accelerometer bias estimation. 0 to disable.
+ 0.05
+ 0.0
+ 0.1
+
+
+ Optical flow scale factor
+ Factor to convert raw optical flow (in pixels) to radians [rad/px].
+ 0.15
+ 0.0
+ 1.0
+ rad/px
+
+
+ Minimal acceptable optical flow quality
+ 0 - lowest quality, 1 - best quality.
+ 0.5
+ 0.0
+ 1.0
+
+
+ Weight for sonar filter
+ Sonar filter detects spikes on sonar measurements and used to detect new surface level.
+ 0.05
+ 0.0
+ 1.0
+
+
+ Sonar maximal error for new surface
+ If sonar measurement error is larger than this value it skiped (spike) or accepted as new surface level (if offset is stable).
+ 0.5
+ 0.0
+ 1.0
+ m
+
+
+ Land detector time
+ Vehicle assumed landed if no altitude changes happened during this time on low throttle.
+ 3.0
+ 0.0
+ 10.0
+ s
+
+
+ Land detector altitude dispersion threshold
+ Dispersion threshold for triggering land detector.
+ 0.7
+ 0.0
+ 10.0
+ m
+
+
+ Land detector throttle threshold
+ Value should be lower than minimal hovering thrust. Half of it is good choice.
+ 0.2
+ 0.0
+ 1.0
+
+
+ GPS delay
+ GPS delay compensation
+ 0.2
+ 0.0
+ 1.0
+ s
+
+
+ Disable vision input
+ Set to the appropriate key (328754) to disable vision input.
+ 0
+ 0
+ 1
+
+
+
+
+ Loiter Time
+ The amount of time in seconds the system should loiter at current position before termination
+ Set to -1 to make the system skip loitering
+ 120.0
+ -1.0
+ seconds
+
+
+
+
+ Loiter radius after RTL (FW only)
+ Default value of loiter radius after RTL (fixedwing only).
+ 50.0
+ 0.0
+ meters
+
+
+ RTL altitude
+ Altitude to fly back in RTL in meters
+ 100
+ 0
+ 1
+ meters
+
+
+ RTL loiter altitude
+ Stay at this altitude above home position after RTL descending.
+ Land (i.e. slowly descend) from this altitude if autolanding allowed.
+ 20
+ 0
+ 100
+ meters
+
+
+ RTL delay
+ Delay after descend before landing in RTL mode.
+ If set to -1 the system will not land but loiter at NAV_LAND_ALT.
+ -1.0
+ -1.0
+ seconds
+
+
+
+
+ RC Channel 1 Minimum
+ Minimum value for RC channel 1
+ 1000.0
+ 800.0
+ 1500.0
+
+
+ RC Channel 1 Trim
+ Mid point value (same as min for throttle)
+ 1500.0
+ 800.0
+ 2200.0
+
+
+ RC Channel 1 Maximum
+ Maximum value for RC channel 1
+ 2000.0
+ 1500.0
+ 2200.0
+
+
+ RC Channel 1 Reverse
+ Set to -1 to reverse channel.
+ 1.0
+ -1.0
+ 1.0
+
+
+ RC Channel 1 dead zone
+ The +- range of this value around the trim value will be considered as zero.
+ 10.0
+ 0.0
+ 100.0
+
+
+ RC Channel 2 Minimum
+ Minimum value for RC channel 2
+ 1000.0
+ 800.0
+ 1500.0
+
+
+ RC Channel 2 Trim
+ Mid point value (same as min for throttle)
+ 1500.0
+ 800.0
+ 2200.0
+
+
+ RC Channel 2 Maximum
+ Maximum value for RC channel 2
+ 2000.0
+ 1500.0
+ 2200.0
+
+
+ RC Channel 2 Reverse
+ Set to -1 to reverse channel.
+ 1.0
+ -1.0
+ 1.0
+
+
+ RC Channel 2 dead zone
+ The +- range of this value around the trim value will be considered as zero.
+ 10.0
+ 0.0
+ 100.0
+
+
+ DSM binding trigger
+ -1 = Idle, 0 = Start DSM2 bind, 1 = Start DSMX bind
+ -1
+
+
+ Roll control channel mapping
+ The channel index (starting from 1 for channel 1) indicates
+ which channel should be used for reading roll inputs from.
+ A value of zero indicates the switch is not assigned.
+ 1
+ 0
+ 18
+
+
+ Pitch control channel mapping
+ The channel index (starting from 1 for channel 1) indicates
+ which channel should be used for reading pitch inputs from.
+ A value of zero indicates the switch is not assigned.
+ 2
+ 0
+ 18
+
+
+ Throttle control channel mapping
+ The channel index (starting from 1 for channel 1) indicates
+ which channel should be used for reading throttle inputs from.
+ A value of zero indicates the switch is not assigned.
+ 3
+ 0
+ 18
+
+
+ Yaw control channel mapping
+ The channel index (starting from 1 for channel 1) indicates
+ which channel should be used for reading yaw inputs from.
+ A value of zero indicates the switch is not assigned.
+ 4
+ 0
+ 18
+
+
+ Mode switch channel mapping
+ This is the main flight mode selector.
+ The channel index (starting from 1 for channel 1) indicates
+ which channel should be used for deciding about the main mode.
+ A value of zero indicates the switch is not assigned.
+ 0
+ 0
+ 18
+
+
+ Return switch channel mapping
+ 0
+ 0
+ 18
+
+
+ Posctl switch channel mapping
+ 0
+ 0
+ 18
+
+
+ Loiter switch channel mapping
+ 0
+ 0
+ 18
+
+
+ Acro switch channel mapping
+ 0
+ 0
+ 18
+
+
+ Offboard switch channel mapping
+ 0
+ 0
+ 18
+
+
+ Flaps channel mapping
+ 0
+ 0
+ 18
+
+
+ Auxiliary switch 1 channel mapping
+ Default function: Camera pitch
+ 0
+ 0
+ 18
+
+
+ Auxiliary switch 2 channel mapping
+ Default function: Camera roll
+ 0
+ 0
+ 18
+
+
+ Auxiliary switch 3 channel mapping
+ Default function: Camera azimuth / yaw
+ 0
+ 0
+ 18
+
+
+ Failsafe channel PWM threshold
+ 0
+ 800
+ 2200
+
+
+
+
+ Logging rate
+ A value of -1 indicates the commandline argument
+ should be obeyed. A value of 0 sets the minimum rate,
+ any other value is interpreted as rate in Hertz. This
+ parameter is only read out before logging starts (which
+ commonly is before arming).
+ -1
+ -1
+ 1
+
+
+ Enable extended logging mode
+ A value of -1 indicates the commandline argument
+ should be obeyed. A value of 0 disables extended
+ logging mode, a value of 1 enables it. This
+ parameter is only read out before logging starts
+ (which commonly is before arming).
+ -1
+ -1
+ 1
+
+
+
+
+ Gyro X-axis offset
+ 0.0
+ -10.0
+ 10.0
+
+
+ Gyro Y-axis offset
+ 0.0
+ -10.0
+ 10.0
+
+
+ Gyro Z-axis offset
+ 0.0
+ -5.0
+ 5.0
+
+
+ Gyro X-axis scaling factor
+ 1.0
+ -1.5
+ 1.5
+
+
+ Gyro Y-axis scaling factor
+ 1.0
+ -1.5
+ 1.5
+
+
+ Gyro Z-axis scaling factor
+ 1.0
+ -1.5
+ 1.5
+
+
+ Magnetometer X-axis offset
+ 0.0
+ -500.0
+ 500.0
+
+
+ Magnetometer Y-axis offset
+ 0.0
+ -500.0
+ 500.0
+
+
+ Magnetometer Z-axis offset
+ 0.0
+ -500.0
+ 500.0
+
+
+ Magnetometer X-axis scaling factor
+ 1.0
+
+
+ Magnetometer Y-axis scaling factor
+ 1.0
+
+
+ Magnetometer Z-axis scaling factor
+ 1.0
+
+
+ Accelerometer X-axis offset
+ 0.0
+
+
+ Accelerometer Y-axis offset
+ 0.0
+
+
+ Accelerometer Z-axis offset
+ 0.0
+
+
+ Accelerometer X-axis scaling factor
+ 1.0
+
+
+ Accelerometer Y-axis scaling factor
+ 1.0
+
+
+ Accelerometer Z-axis scaling factor
+ 1.0
+
+
+ Differential pressure sensor offset
+ The offset (zero-reading) in Pascal
+ 0.0
+
+
+ Differential pressure sensor analog scaling
+ Pick the appropriate scaling from the datasheet.
+ this number defines the (linear) conversion from voltage
+ to Pascal (pa). For the MPXV7002DP this is 1000.
+ NOTE: If the sensor always registers zero, try switching
+ the static and dynamic tubes.
+ 0
+
+
+ QNH for barometer
+ 1013.25
+ 500
+ 1500
+ hPa
+
+
+ Board rotation
+ This parameter defines the rotation of the FMU board relative to the platform.
+ Possible values are:
+ 0 = No rotation
+ 1 = Yaw 45°
+ 2 = Yaw 90°
+ 3 = Yaw 135°
+ 4 = Yaw 180°
+ 5 = Yaw 225°
+ 6 = Yaw 270°
+ 7 = Yaw 315°
+ 8 = Roll 180°
+ 9 = Roll 180°, Yaw 45°
+ 10 = Roll 180°, Yaw 90°
+ 11 = Roll 180°, Yaw 135°
+ 12 = Pitch 180°
+ 13 = Roll 180°, Yaw 225°
+ 14 = Roll 180°, Yaw 270°
+ 15 = Roll 180°, Yaw 315°
+ 16 = Roll 90°
+ 17 = Roll 90°, Yaw 45°
+ 18 = Roll 90°, Yaw 90°
+ 19 = Roll 90°, Yaw 135°
+ 20 = Roll 270°
+ 21 = Roll 270°, Yaw 45°
+ 22 = Roll 270°, Yaw 90°
+ 23 = Roll 270°, Yaw 135°
+ 24 = Pitch 90°
+ 25 = Pitch 270°
+ 0
+
+
+ Board rotation Y (Pitch) offset
+ This parameter defines a rotational offset in degrees around the Y (Pitch) axis. It allows the user
+ to fine tune the board offset in the event of misalignment.
+ 0.0
+
+
+ Board rotation X (Roll) offset
+ This parameter defines a rotational offset in degrees around the X (Roll) axis It allows the user
+ to fine tune the board offset in the event of misalignment.
+ 0.0
+
+
+ Board rotation Z (YAW) offset
+ This parameter defines a rotational offset in degrees around the Z (Yaw) axis. It allows the user
+ to fine tune the board offset in the event of misalignment.
+ 0.0
+
+
+ External magnetometer rotation
+ This parameter defines the rotation of the external magnetometer relative
+ to the platform (not relative to the FMU).
+ See SENS_BOARD_ROT for possible values.
+ 0
+
+
+ Set usage of external magnetometer
+ * Set to 0 (default) to auto-detect (will try to get the external as primary)
+ * Set to 1 to force the external magnetometer as primary
+ * Set to 2 to force the internal magnetometer as primary
+ 0
+ 0
+ 2
+
+
+
+
+ Auto-start script index
+ Defines the auto-start script used to bootstrap the system.
+ 0
+
+
+ Automatically configure default values
+ Set to 1 to set platform-specific parameters to their default
+ values on next system startup.
+ 0
+ 0
+ 1
+
+
+ Set usage of IO board
+ Can be used to use a standard startup script but with a FMU only set-up. Set to 0 to force the FMU only set-up.
+ 1
+ 0
+ 1
+
+
+ Set restart type
+ Set by px4io to indicate type of restart
+ 2
+ 0
+ 2
+
+
+
+
+ Enable UAVCAN
+ Enables support for UAVCAN-interfaced actuators and sensors.
+ 0
+ 0
+ 1
+
+
+ UAVCAN Node ID
+ Read the specs at http://uavcan.org to learn more about Node ID.
+ 1
+ 1
+ 125
+
+
+ UAVCAN CAN bus bitrate
+ 1000000
+ 20000
+ 1000000
+
+
+
+
+ Body angular rate process noise
+ 1e-4
+
+
+ Body angular acceleration process noise
+ 0.08
+
+
+ Acceleration process noise
+ 0.009
+
+
+ Magnet field vector process noise
+ 0.005
+
+
+ Gyro measurement noise
+ 0.0008
+
+
+ Accel measurement noise
+ 10000.0
+
+
+ Mag measurement noise
+ 100.0
+
+
+ Moment of inertia matrix diagonal entry (1, 1)
+ 0.0018
+ kg*m^2
+
+
+ Moment of inertia matrix diagonal entry (2, 2)
+ 0.0018
+ kg*m^2
+
+
+ Moment of inertia matrix diagonal entry (3, 3)
+ 0.0037
+ kg*m^2
+
+
+ Moment of inertia enabled in estimator
+ If set to != 0 the moment of inertia will be used in the estimator
+ 0
+ 0
+ 1
+
+
+
+
+ Datalink loss mode enabled
+ Set to 1 to enable actions triggered when the datalink is lost.
+ 0
+ 0
+ 1
+
+
+ After this amount of seconds without datalink the data link lost mode triggers
+ 10
+ 0
+ 30
+ second
+
+
+ After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss'
+ flag is set back to false
+ 0
+ 0
+ 30
+ second
+
+
+ Engine failure triggers only above this throttle value
+ 0.5
+ 0.0
+ 1.0
+
+
+ Engine failure triggers only below this current/throttle value
+ 5.0
+ 0.0
+ 7.0
+
+
+ Engine failure triggers only if the throttle threshold and the
+ current to throttle threshold are violated for this time
+ 10.0
+ 0.0
+ 7.0
+ second
+
+
+ After this amount of seconds without RC connection the rc lost flag is set to true
+ 0.5
+ 0
+ 35
+ second
+
+
+
+
+ mTECS enabled
+ Set to 1 to enable mTECS
+ 0
+ 0
+ 1
+
+
+ Total Energy Rate Control Feedforward
+ Maps the total energy rate setpoint to the throttle setpoint
+ 0.7
+ 0.0
+ 10.0
+
+
+ Total Energy Rate Control P
+ Maps the total energy rate error to the throttle setpoint
+ 0.1
+ 0.0
+ 10.0
+
+
+ Total Energy Rate Control I
+ Maps the integrated total energy rate to the throttle setpoint
+ 0.25
+ 0.0
+ 10.0
+
+
+ Total Energy Rate Control Offset (Cruise throttle sp)
+ 0.7
+ 0.0
+ 10.0
+
+
+ Energy Distribution Rate Control Feedforward
+ Maps the energy distribution rate setpoint to the pitch setpoint
+ 0.4
+ 0.0
+ 10.0
+
+
+ Energy Distribution Rate Control P
+ Maps the energy distribution rate error to the pitch setpoint
+ 0.03
+ 0.0
+ 10.0
+
+
+ Energy Distribution Rate Control I
+ Maps the integrated energy distribution rate error to the pitch setpoint
+ 0.03
+ 0.0
+ 10.0
+
+
+ Total Energy Distribution Offset (Cruise pitch sp)
+ 0.0
+ 0.0
+ 10.0
+
+
+ Minimal Throttle Setpoint
+ 0.0
+ 0.0
+ 1.0
+
+
+ Maximal Throttle Setpoint
+ 1.0
+ 0.0
+ 1.0
+
+
+ Minimal Pitch Setpoint in Degrees
+ -45.0
+ -90.0
+ 90.0
+ deg
+
+
+ Maximal Pitch Setpoint in Degrees
+ 20.0
+ -90.0
+ 90.0
+ deg
+
+
+ Lowpass (cutoff freq.) for altitude
+ 1.0
+
+
+ Lowpass (cutoff freq.) for the flight path angle
+ 1.0
+
+
+ P gain for the altitude control
+ Maps the altitude error to the flight path angle setpoint
+ 0.3
+ 0.0
+ 10.0
+
+
+ D gain for the altitude control
+ Maps the change of altitude error to the flight path angle setpoint
+ 0.0
+ 0.0
+ 10.0
+
+
+ Lowpass for FPA error derivative calculation (see MT_FPA_D)
+ 1.0
+
+
+ Minimal flight path angle setpoint
+ -20.0
+ -90.0
+ 90.0
+ deg
+
+
+ Maximal flight path angle setpoint
+ 30.0
+ -90.0
+ 90.0
+ deg
+
+
+ Lowpass (cutoff freq.) for airspeed
+ 0.5
+
+
+ Airspeed derivative calculation lowpass
+ 0.5
+
+
+ P gain for the airspeed control
+ Maps the airspeed error to the acceleration setpoint
+ 0.3
+ 0.0
+ 10.0
+
+
+ D gain for the airspeed control
+ Maps the change of airspeed error to the acceleration setpoint
+ 0.0
+ 0.0
+ 10.0
+
+
+ Lowpass for ACC error derivative calculation (see MT_ACC_D)
+ 0.5
+
+
+ Minimal acceleration (air)
+ -40.0
+ m/s^2
+
+
+ Maximal acceleration (air)
+ 40.0
+ m/s^2
+
+
+ Minimal throttle during takeoff
+ 1.0
+ 0.0
+ 1.0
+
+
+ Maximal throttle during takeoff
+ 1.0
+ 0.0
+ 1.0
+
+
+ Minimal pitch during takeoff
+ 0.0
+ -90.0
+ 90.0
+ deg
+
+
+ Maximal pitch during takeoff
+ 45.0
+ -90.0
+ 90.0
+ deg
+
+
+ Minimal throttle in underspeed mode
+ 1.0
+ 0.0
+ 1.0
+
+
+ Maximal throttle in underspeed mode
+ 1.0
+ 0.0
+ 1.0
+
+
+ Minimal pitch in underspeed mode
+ -45.0
+ -90.0
+ 90.0
+ deg
+
+
+ Maximal pitch in underspeed mode
+ 0.0
+ -90.0
+ 90.0
+ deg
+
+
+ Minimal throttle in landing mode (only last phase of landing)
+ 0.0
+ 0.0
+ 1.0
+
+
+ Maximal throttle in landing mode (only last phase of landing)
+ 0.0
+ 0.0
+ 1.0
+
+
+ Minimal pitch in landing mode
+ -5.0
+ -90.0
+ 90.0
+ deg
+
+
+ Maximal pitch in landing mode
+ 15.0
+ -90.0
+ 90.0
+ deg
+
+
+ Integrator Limit for Total Energy Rate Control
+ 10.0
+ 0.0
+ 10.0
+
+
+ Integrator Limit for Energy Distribution Rate Control
+ 10.0
+ 0.0
+ 10.0
+
+
+
+
+ EXFW_HDNG_P
+ 0.1
+
+
+ EXFW_ROLL_P
+ 0.2
+
+
+ EXFW_PITCH_P
+ 0.2
+
+
+ FPE_LO_THRUST
+ 0.4
+
+
+ FPE_SONAR_LP_U
+ 0.5
+
+
+ FPE_SONAR_LP_L
+ 0.2
+
+
+ FPE_DEBUG
+ 0
+
+
+ FSC_S_P
+ 0.1
+
+
+ FSC_L_PITCH
+ 0.4
+
+
+ FSC_L_ROLL
+ 0.4
+
+
+ ATT_MAG_DECL
+ 0.0
+
+
+ ATT_ACC_COMP
+ 2
+
+
+ SO3_COMP_KP
+ 1.0
+
+
+ SO3_COMP_KI
+ 0.05
+
+
+ SO3_ROLL_OFFS
+ 0.0
+
+
+ SO3_PITCH_OFFS
+ 0.0
+
+
+ SO3_YAW_OFFS
+ 0.0
+
+
+ TRIM_ROLL
+ 0.0
+
+
+ TRIM_PITCH
+ 0.0
+
+
+ TRIM_YAW
+ 0.0
+
+
+ TEST_MIN
+ -1.0
+
+
+ TEST_MAX
+ 1.0
+
+
+ TEST_TRIM
+ 0.5
+
+
+ TEST_HP
+ 10.0
+
+
+ TEST_LP
+ 10.0
+
+
+ TEST_P
+ 0.2
+
+
+ TEST_I
+ 0.1
+
+
+ TEST_I_MAX
+ 1.0
+
+
+ TEST_D
+ 0.01
+
+
+ TEST_D_LP
+ 10.0
+
+
+ TEST_MEAN
+ 1.0
+
+
+ TEST_DEV
+ 2.0
+
+
+ FWB_P_LP
+ 300.0
+
+
+ FWB_Q_LP
+ 300.0
+
+
+ FWB_R_LP
+ 300.0
+
+
+ FWB_R_HP
+ 1.0
+
+
+ FWB_P2AIL
+ 0.3
+
+
+ FWB_Q2ELV
+ 0.1
+
+
+ FWB_R2RDR
+ 0.1
+
+
+ FWB_PSI2PHI
+ 0.5
+
+
+ FWB_PHI2P
+ 1.0
+
+
+ FWB_PHI_LIM_MAX
+ 0.3
+
+
+ FWB_V2THE_P
+ 1.0
+
+
+ FWB_V2THE_I
+ 0.0
+
+
+ FWB_V2THE_D
+ 0.0
+
+
+ FWB_V2THE_D_LP
+ 0.0
+
+
+ FWB_V2THE_I_MAX
+ 0.0
+
+
+ FWB_THE_MIN
+ -0.5
+
+
+ FWB_THE_MAX
+ 0.5
+
+
+ FWB_THE2Q_P
+ 1.0
+
+
+ FWB_THE2Q_I
+ 0.0
+
+
+ FWB_THE2Q_D
+ 0.0
+
+
+ FWB_THE2Q_D_LP
+ 0.0
+
+
+ FWB_THE2Q_I_MAX
+ 0.0
+
+
+ FWB_H2THR_P
+ 0.01
+
+
+ FWB_H2THR_I
+ 0.0
+
+
+ FWB_H2THR_D
+ 0.0
+
+
+ FWB_H2THR_D_LP
+ 0.0
+
+
+ FWB_H2THR_I_MAX
+ 0.0
+
+
+ FWB_XT2YAW_MAX
+ 1.57
+
+
+ FWB_XT2YAW
+ 0.005
+
+
+ FWB_V_MIN
+ 10.0
+
+
+ FWB_V_CMD
+ 12.0
+
+
+ FWB_V_MAX
+ 16.0
+
+
+ FWB_CR_MAX
+ 1.0
+
+
+ FWB_CR2THR_P
+ 0.01
+
+
+ FWB_CR2THR_I
+ 0.0
+
+
+ FWB_CR2THR_D
+ 0.0
+
+
+ FWB_CR2THR_D_LP
+ 0.0
+
+
+ FWB_CR2THR_I_MAX
+ 0.0
+
+
+ FWB_TRIM_THR
+ 0.8
+
+
+ FWB_TRIM_V
+ 12.0
+
+
+ Flare, minimum pitch
+ Minimum pitch during flare, a positive sign means nose up
+ Applied once FW_LND_TLALT is reached
+ 2.5
+
+
+ Flare, maximum pitch
+ Maximum pitch during flare, a positive sign means nose up
+ Applied once FW_LND_TLALT is reached
+ 15.0
+
+
+ SEG_TH2V_P
+ 10.0
+
+
+ SEG_TH2V_I
+ 0.0
+
+
+ SEG_TH2V_I_MAX
+ 0.0
+
+
+ SEG_Q2V
+ 1.0
+
+
+ RC3_MIN
+ 1000
+
+
+ RC3_TRIM
+ 1500
+
+
+ RC3_MAX
+ 2000
+
+
+ RC3_REV
+ 1.0
+
+
+ RC3_DZ
+ 10.0
+
+
+ RC4_MIN
+ 1000
+
+
+ RC4_TRIM
+ 1500
+
+
+ RC4_MAX
+ 2000
+
+
+ RC4_REV
+ 1.0
+
+
+ RC4_DZ
+ 10.0
+
+
+ RC5_MIN
+ 1000
+
+
+ RC5_TRIM
+ 1500
+
+
+ RC5_MAX
+ 2000
+
+
+ RC5_REV
+ 1.0
+
+
+ RC5_DZ
+ 10.0
+
+
+ RC6_MIN
+ 1000
+
+
+ RC6_TRIM
+ 1500
+
+
+ RC6_MAX
+ 2000
+
+
+ RC6_REV
+ 1.0
+
+
+ RC6_DZ
+ 10.0
+
+
+ RC7_MIN
+ 1000
+
+
+ RC7_TRIM
+ 1500
+
+
+ RC7_MAX
+ 2000
+
+
+ RC7_REV
+ 1.0
+
+
+ RC7_DZ
+ 10.0
+
+
+ RC8_MIN
+ 1000
+
+
+ RC8_TRIM
+ 1500
+
+
+ RC8_MAX
+ 2000
+
+
+ RC8_REV
+ 1.0
+
+
+ RC8_DZ
+ 10.0
+
+
+ RC9_MIN
+ 1000
+
+
+ RC9_TRIM
+ 1500
+
+
+ RC9_MAX
+ 2000
+
+
+ RC9_REV
+ 1.0
+
+
+ RC9_DZ
+ 0.0
+
+
+ RC10_MIN
+ 1000
+
+
+ RC10_TRIM
+ 1500
+
+
+ RC10_MAX
+ 2000
+
+
+ RC10_REV
+ 1.0
+
+
+ RC10_DZ
+ 0.0
+
+
+ RC11_MIN
+ 1000
+
+
+ RC11_TRIM
+ 1500
+
+
+ RC11_MAX
+ 2000
+
+
+ RC11_REV
+ 1.0
+
+
+ RC11_DZ
+ 0.0
+
+
+ RC12_MIN
+ 1000
+
+
+ RC12_TRIM
+ 1500
+
+
+ RC12_MAX
+ 2000
+
+
+ RC12_REV
+ 1.0
+
+
+ RC12_DZ
+ 0.0
+
+
+ RC13_MIN
+ 1000
+
+
+ RC13_TRIM
+ 1500
+
+
+ RC13_MAX
+ 2000
+
+
+ RC13_REV
+ 1.0
+
+
+ RC13_DZ
+ 0.0
+
+
+ RC14_MIN
+ 1000
+
+
+ RC14_TRIM
+ 1500
+
+
+ RC14_MAX
+ 2000
+
+
+ RC14_REV
+ 1.0
+
+
+ RC14_DZ
+ 0.0
+
+
+ RC15_MIN
+ 1000
+
+
+ RC15_TRIM
+ 1500
+
+
+ RC15_MAX
+ 2000
+
+
+ RC15_REV
+ 1.0
+
+
+ RC15_DZ
+ 0.0
+
+
+ RC16_MIN
+ 1000
+
+
+ RC16_TRIM
+ 1500
+
+
+ RC16_MAX
+ 2000
+
+
+ RC16_REV
+ 1.0
+
+
+ RC16_DZ
+ 0.0
+
+
+ RC17_MIN
+ 1000
+
+
+ RC17_TRIM
+ 1500
+
+
+ RC17_MAX
+ 2000
+
+
+ RC17_REV
+ 1.0
+
+
+ RC17_DZ
+ 0.0
+
+
+ RC18_MIN
+ 1000
+
+
+ RC18_TRIM
+ 1500
+
+
+ RC18_MAX
+ 2000
+
+
+ RC18_REV
+ 1.0
+
+
+ RC18_DZ
+ 0.0
+
+
+ RC_RL1_DSM_VCC
+ 0
+
+
+ Failsafe channel mapping
+ The RC mapping index indicates which channel is used for failsafe
+ If 0, whichever channel is mapped to throttle is used
+ otherwise the value indicates the specific rc channel to use
+ 0
+ 0
+ 18
+
+
+ Threshold for selecting assist mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.25
+
+
+ Threshold for selecting auto mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.75
+
+
+ Threshold for selecting posctl mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.5
+
+
+ Threshold for selecting return to launch mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.5
+
+
+ Threshold for selecting loiter mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.5
+
+
+ Threshold for selecting acro mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.5
+
+
+ Threshold for selecting offboard mode
+ min:-1
+ max:+1
+ 0-1 indicate where in the full channel range the threshold sits
+ 0 : min
+ 1 : max
+ sign indicates polarity of comparison
+ positive : true when channel>th
+ negative : true when channel<th
+ 0.5
+
+
+
diff --git a/src/FactSystem/Fact.cc b/src/FactSystem/Fact.cc
new file mode 100644
index 0000000..806b0e7
--- /dev/null
+++ b/src/FactSystem/Fact.cc
@@ -0,0 +1,47 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#include "Fact.h"
+
+#include
+
+Fact::Fact(QObject* parent) :
+ QObject(parent)
+{
+
+}
+
+void Fact::setValue(QVariant& value)
+{
+ _value = value;
+ emit valueUpdated(value);
+}
+
+void Fact::updateValue(QVariant& value)
+{
+ _value = value;
+ emit valueChanged(value);
+}
diff --git a/src/FactSystem/Fact.h b/src/FactSystem/Fact.h
new file mode 100644
index 0000000..1047162
--- /dev/null
+++ b/src/FactSystem/Fact.h
@@ -0,0 +1,112 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef Fact_H
+#define Fact_H
+
+#include "FactMetaData.h"
+
+#include
+#include
+#include
+
+/// @brief A Fact is used to hold a single value within the system.
+///
+/// Along with the value property is a set of meta data which further describes the Fact. This information is
+/// exposed through QObject Properties such that you can bind to it from QML as well as use it within C++ code.
+/// Since the meta data is common to all instances of the same Fact, it is acually stored once in a seperate object.
+class Fact : public QObject
+{
+ Q_OBJECT
+
+ Q_PROPERTY(QVariant value READ value WRITE setValue NOTIFY valueChanged USER true)
+ Q_PROPERTY(QVariant defaultValue READ defaultValue CONSTANT)
+ Q_PROPERTY(FactMetaData::ValueType_t type READ type CONSTANT)
+ Q_PROPERTY(QString shortDescription READ shortDescription CONSTANT)
+ Q_PROPERTY(QString longDescription READ longDescription CONSTANT)
+ Q_PROPERTY(QString units READ units CONSTANT)
+ Q_PROPERTY(QVariant min READ min CONSTANT)
+ Q_PROPERTY(QVariant max READ max CONSTANT)
+
+ Q_ENUMS(FactMetaData::ValueType_t)
+
+public:
+ Fact(QObject* parent = NULL);
+
+ // Property system methods
+
+ /// Read accessor for value property
+ QVariant value(void) const { return _value; }
+
+ /// Write accessor for value property
+ void setValue(QVariant& value);
+
+ /// Read accesor for defaultValue property
+ QVariant defaultValue(void) { return _metaData->defaultValue; }
+
+ /// Read accesor for type property
+ FactMetaData::ValueType_t type(void) { return _metaData->type; }
+
+ /// Read accesor for shortDescription property
+ QString shortDescription(void) { return _metaData->shortDescription; }
+
+ /// Read accesor for longDescription property
+ QString longDescription(void) { return _metaData->longDescription; }
+
+ /// Read accesor for units property
+ QString units(void) { return _metaData->units; }
+
+ /// Read accesor for min property
+ QVariant min(void) { return _metaData->min; }
+
+ /// Read accesor for max property
+ QVariant max(void) { return _metaData->max; }
+
+ /// Used to update the value property from C++ code.
+ ///
+ /// The setValue method is only for use by the QObject Property system. It should not be called directly by C++ app code.
+ void updateValue(QVariant& value);
+
+ /// Sets the meta data associated with the Fact.
+ void setMetaData(FactMetaData* metaData) { _metaData = metaData; }
+
+signals:
+ /// QObject Property System signal for value property changes
+ ///
+ /// This signal is only meant for use by the QT property system. It should not be connected to by client code.
+ void valueChanged(QVariant& value);
+
+ /// Signalled when property has been changed by a call to the property write accessor
+ ///
+ /// This signal is meant for use by client code.
+ void valueUpdated(QVariant& value);
+
+private:
+ QVariant _value; ///< Fact value
+ FactMetaData* _metaData; ///< FactMetaData object for Fact
+};
+
+#endif
\ No newline at end of file
diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc
new file mode 100644
index 0000000..769bb49
--- /dev/null
+++ b/src/FactSystem/FactMetaData.cc
@@ -0,0 +1,35 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @brief Object which exposes a FactMetaData
+///
+/// @author Don Gagne
+
+#include "FactMetaData.h"
+
+FactMetaData::FactMetaData(QObject* parent) :
+ QObject(parent)
+{
+
+}
diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h
new file mode 100644
index 0000000..9370b43
--- /dev/null
+++ b/src/FactSystem/FactMetaData.h
@@ -0,0 +1,66 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef FactMetaData_H
+#define FactMetaData_H
+
+#include
+#include
+#include
+
+/// Holds the meta data associated with a Fact.
+///
+/// Holds the meta data associated with a Fact. This is kept in a seperate object from the Fact itself
+/// since you may have multiple instances of the same Fact. But there is only ever one FactMetaData
+/// instance or each Fact.
+class FactMetaData : public QObject
+{
+ Q_OBJECT
+
+public:
+ FactMetaData(QObject* parent = NULL);
+
+ typedef enum {
+ valueTypeUint8,
+ valueTypeInt8,
+ valueTypeUint16,
+ valueTypeInt16,
+ valueTypeUint32,
+ valueTypeInt32,
+ valueTypeFloat,
+ valueTypeDouble
+ } ValueType_t;
+
+ QVariant defaultValue;
+ ValueType_t type;
+ QString shortDescription;
+ QString longDescription;
+ QString units;
+ QVariant min;
+ QVariant max;
+};
+
+#endif
\ No newline at end of file
diff --git a/src/FactSystem/FactSystem.cc b/src/FactSystem/FactSystem.cc
new file mode 100644
index 0000000..06a324f
--- /dev/null
+++ b/src/FactSystem/FactSystem.cc
@@ -0,0 +1,68 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#include "FactSystem.h"
+#include "UASManager.h"
+
+#include
+
+FactSystem* FactSystem::_instance = NULL;
+QMutex FactSystem::_singletonLock;
+const char* FactSystem::_factSystemQmlUri = "QGroundControl.FactSystem";
+
+FactSystem* FactSystem::instance(void)
+{
+ if(_instance == 0) {
+ _singletonLock.lock();
+ if (_instance == 0) {
+ _instance = new FactSystem(qgcApp());
+ Q_CHECK_PTR(_instance);
+ }
+ _singletonLock.unlock();
+ }
+
+ Q_ASSERT(_instance);
+
+ return _instance;
+}
+
+void FactSystem::deleteInstance(void)
+{
+ _instance = NULL;
+ delete this;
+}
+
+FactSystem::FactSystem(QObject* parent, bool registerSingleton) :
+ QGCSingleton(parent, registerSingleton)
+{
+ qmlRegisterType(_factSystemQmlUri, 1, 0, "Fact");
+ qmlRegisterType(_factSystemQmlUri, 1, 0, "FactValidator");
+}
+
+FactSystem::~FactSystem()
+{
+
+}
diff --git a/src/FactSystem/FactSystem.h b/src/FactSystem/FactSystem.h
new file mode 100644
index 0000000..9100188
--- /dev/null
+++ b/src/FactSystem/FactSystem.h
@@ -0,0 +1,69 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef FactSystem_h
+#define FactSystem_h
+
+#include "Fact.h"
+#include "FactMetaData.h"
+#include "UASInterface.h"
+#include "QGCSingleton.h"
+#include "FactValidator.h"
+
+#include
+
+/// FactSystem is a singleton which provides access to the Facts in the system
+///
+/// The components of the FactSystem are a Fact which holds an individual value. FactMetaData holds
+/// additional meta data associated with a Fact such as description, min/max ranges and so forth.
+/// The FactValidator object is a QML validator which validates input according to the FactMetaData
+/// settings. Client code can then use this system to expose sets of Facts to QML code. An example
+/// of this is the PX4ParameterFacts onbject which is part of the PX4 AutoPilot plugin. It exposes
+/// the firmware parameters to QML such that you can bind QML ui elements directly to parameters.
+class FactSystem : public QGCSingleton
+{
+ Q_OBJECT
+
+public:
+ /// Returns the FactSystem singleton
+ static FactSystem* instance(void);
+
+ /// Override from QGCSingleton
+ virtual void deleteInstance(void);
+
+ ~FactSystem();
+
+private:
+ /// All access to FactSystem is through FactSystem::instance, so constructor is private
+ FactSystem(QObject* parent = NULL, bool registerSingleton = true);
+
+ static QMutex _singletonLock; ///< Mutex to make calls to instance thread-safe
+
+ static FactSystem* _instance; ///< FactSystem singleton
+ static const char* _factSystemQmlUri; ///< URI for FactSystem QML imports
+};
+
+#endif
diff --git a/src/FactSystem/FactValidator.cc b/src/FactSystem/FactValidator.cc
new file mode 100644
index 0000000..a2a23c9
--- /dev/null
+++ b/src/FactSystem/FactValidator.cc
@@ -0,0 +1,46 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#include "FactValidator.h"
+
+FactValidator::FactValidator(QObject* parent) :
+ QValidator(parent)
+{
+
+}
+
+void FactValidator::fixup(QString& input) const
+{
+ Q_UNUSED(input);
+}
+
+FactValidator::State FactValidator::validate(QString& input, int& pos) const
+{
+ Q_UNUSED(input);
+ Q_UNUSED(pos);
+
+ return Acceptable;
+}
diff --git a/src/FactSystem/FactValidator.h b/src/FactSystem/FactValidator.h
new file mode 100644
index 0000000..2283f7a
--- /dev/null
+++ b/src/FactSystem/FactValidator.h
@@ -0,0 +1,69 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+/// @file
+/// @author Don Gagne
+
+#ifndef FactValidator_H
+#define FactValidator_H
+
+#include
+
+class Fact;
+
+/// QML Validator for Facts (Work In Progress)
+///
+/// The validator uses the FactMetaData to impose restrictions on the input. It is used as follows:
+/// @code{.unparsed}
+/// TextInput {
+/// validator: FactValidator { fact: parameterFacts.RC_MAP_THROTTLE; }
+/// }
+/// @endcode
+class FactValidator : public QValidator
+{
+ Q_OBJECT
+
+ Q_PROPERTY(Fact* fact READ fact WRITE setFact)
+
+public:
+ FactValidator(QObject* parent = NULL);
+
+ // Property system methods
+
+ /// Read accessor for fact property
+ Fact* fact(void) { return _fact; }
+
+ /// Write accessor for fact property
+ void setFact(Fact* fact) { _fact = fact; }
+
+ /// Override from QValidator
+ virtual void fixup(QString& input) const;
+
+ /// Override from QValidator
+ virtual State validate(QString& input, int& pos) const;
+
+private:
+ Fact* _fact; ///< Fact that the validator is working on
+};
+
+#endif
\ No newline at end of file
diff --git a/src/QGCApplication.cc b/src/QGCApplication.cc
index 57bb92b..f9bb471 100644
--- a/src/QGCApplication.cc
+++ b/src/QGCApplication.cc
@@ -433,6 +433,11 @@ void QGCApplication::_createSingletons(void)
AutoPilotPluginManager* pluginManager = AutoPilotPluginManager::instance();
Q_UNUSED(pluginManager);
Q_ASSERT(pluginManager);
+
+ // Must be after UASManager since FactSystem connects to UASManager
+ FactSystem* factSystem = FactSystem::instance();
+ Q_UNUSED(factSystem);
+ Q_ASSERT(factSystem);
}
void QGCApplication::destroySingletonsForUnitTest(void)
diff --git a/src/QGCQuickWidget.cc b/src/QGCQuickWidget.cc
new file mode 100644
index 0000000..7815b8e
--- /dev/null
+++ b/src/QGCQuickWidget.cc
@@ -0,0 +1,51 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+#include "QGCQuickWidget.h"
+#include "UASManager.h"
+#include "AutoPilotPluginManager.h"
+
+#include
+#include
+
+/// @file
+/// @brief Subclass of QQuickWidget which injects Facts and the Pallete object into
+/// the QML context.
+///
+/// @author Don Gagne
+
+QGCQuickWidget::QGCQuickWidget(QWidget* parent) :
+ QQuickWidget(parent)
+{
+ UASManagerInterface* uasMgr = UASManager::instance();
+ Q_ASSERT(uasMgr);
+
+ UASInterface* uas = uasMgr->getActiveUAS();
+ Q_ASSERT(uas);
+
+ AutoPilotPluginManager::instance()->getInstanceForAutoPilotPlugin(uas->getAutopilotType())->addFactsToQmlContext(rootContext(), uas);
+
+ rootContext()->engine()->addImportPath("qrc:/qml");
+
+ setSource(QUrl::fromLocalFile("/Users/Don/repos/qgroundcontrol/test.qml"));
+}
diff --git a/src/QGCQuickWidget.h b/src/QGCQuickWidget.h
new file mode 100644
index 0000000..a239cff
--- /dev/null
+++ b/src/QGCQuickWidget.h
@@ -0,0 +1,45 @@
+/*=====================================================================
+
+ QGroundControl Open Source Ground Control Station
+
+ (c) 2009 - 2014 QGROUNDCONTROL PROJECT
+
+ This file is part of the QGROUNDCONTROL project
+
+ QGROUNDCONTROL is free software: you can redistribute it and/or modify
+ it under the terms of the GNU General Public License as published by
+ the Free Software Foundation, either version 3 of the License, or
+ (at your option) any later version.
+
+ QGROUNDCONTROL is distributed in the hope that it will be useful,
+ but WITHOUT ANY WARRANTY; without even the implied warranty of
+ MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ GNU General Public License for more details.
+
+ You should have received a copy of the GNU General Public License
+ along with QGROUNDCONTROL. If not, see .
+
+ ======================================================================*/
+
+#ifndef QGCQuickWidget_H
+#define QGCQuickWidget_H
+
+#include
+
+#include "UASInterface.h"
+
+/// @file
+/// @brief Subclass of QQuickWidget which injects Facts and the Pallete object into
+/// the QML context.
+///
+/// @author Don Gagne
+
+class QGCQuickWidget : public QQuickWidget {
+ Q_OBJECT
+
+public:
+ QGCQuickWidget(QWidget* parent = NULL);
+};
+
+
+#endif
diff --git a/src/qgcunittest/MockUAS.h b/src/qgcunittest/MockUAS.h
index e9a48d9..993307c 100644
--- a/src/qgcunittest/MockUAS.h
+++ b/src/qgcunittest/MockUAS.h
@@ -103,7 +103,7 @@ public:
virtual QList* getLinks() { Q_ASSERT(false); return NULL; };
virtual bool systemCanReverse() const { Q_ASSERT(false); return false; };
virtual QString getSystemTypeName() { Q_ASSERT(false); return _bogusString; };
- virtual int getAutopilotType() { Q_ASSERT(false); return 0; };
+ virtual int getAutopilotType() { return MAV_AUTOPILOT_PX4; };
virtual QGCUASFileManager* getFileManager() {Q_ASSERT(false); return NULL; }
/** @brief Send a message over this link (to this or to all UAS on this link) */