diff --git a/qgroundcontrol.pro b/qgroundcontrol.pro index df4d81974e753106048eebeceb03ac13daffc2ce..c5e4e1064594e1a2558498d13d417d51068f4ee3 100644 --- a/qgroundcontrol.pro +++ b/qgroundcontrol.pro @@ -683,6 +683,9 @@ HEADERS += \ src/SHPFileHelper.h \ src/Terrain/TerrainQuery.h \ src/TerrainTile.h \ + src/Vehicle/CompInfo.h \ + src/Vehicle/CompInfoParam.h \ + src/Vehicle/CompInfoVersion.h \ src/Vehicle/ComponentInformationManager.h \ src/Vehicle/FTPManager.h \ src/Vehicle/GPSRTKFactGroup.h \ @@ -899,6 +902,9 @@ SOURCES += \ src/SHPFileHelper.cc \ src/Terrain/TerrainQuery.cc \ src/TerrainTile.cc\ + src/Vehicle/CompInfo.cc \ + src/Vehicle/CompInfoParam.cc \ + src/Vehicle/CompInfoVersion.cc \ src/Vehicle/ComponentInformationManager.cc \ src/Vehicle/FTPManager.cc \ src/Vehicle/GPSRTKFactGroup.cc \ diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 1a18a83bc231f3f44c3d89f04f710550f087c555..59399b7b8e0f5daca5a94b2ec8d27813598fe4c4 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -131,6 +131,9 @@ const char* FactMetaData::_maxJsonKey = "max"; const char* FactMetaData::_incrementJsonKey = "increment"; const char* FactMetaData::_hasControlJsonKey = "control"; const char* FactMetaData::_qgcRebootRequiredJsonKey = "qgcRebootRequired"; +const char* FactMetaData::_categoryJsonKey = "category"; +const char* FactMetaData::_groupJsonKey = "group"; +const char* FactMetaData::_volatileJsonKey = "volatile"; FactMetaData::FactMetaData(QObject* parent) : QObject (parent) @@ -1233,14 +1236,6 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QMap keyInfoList = { { _nameJsonKey, QJsonValue::String, true }, { _typeJsonKey, QJsonValue::String, true }, @@ -1252,6 +1247,9 @@ FactMetaData* FactMetaData::createFromJsonObject(const QJsonObject& json, QMapsetHasControl(json[_hasControlJsonKey].toBool()); - } else { - metaData->setHasControl(true); + hasControlJsonKey = json[_hasControlJsonKey].toBool(); } + metaData->setHasControl(hasControlJsonKey); + bool qgcRebootRequired = false; if (json.contains(_qgcRebootRequiredJsonKey)) { - metaData->setQGCRebootRequired(json[_qgcRebootRequiredJsonKey].toBool()); - } else { - metaData->setQGCRebootRequired(false); + qgcRebootRequired = json[_qgcRebootRequiredJsonKey].toBool(); + } + metaData->setQGCRebootRequired(qgcRebootRequired); + + bool volatileValue = false; + if (json.contains(_volatileJsonKey)) { + volatileValue = json[_volatileJsonKey].toBool(); + } + metaData->setVolatileValue(volatileValue); + + if (json.contains(_groupJsonKey)) { + metaData->setGroup(json[_groupJsonKey].toString()); + } + + if (json.contains(_categoryJsonKey)) { + metaData->setCategory(json[_categoryJsonKey].toString()); } return metaData; diff --git a/src/FactSystem/FactMetaData.h b/src/FactSystem/FactMetaData.h index 119b19c9f0946b148d970c956ce89ce098b2d745..8a5de25f3c4edba8caac925b9fa37709ecd55006 100644 --- a/src/FactSystem/FactMetaData.h +++ b/src/FactSystem/FactMetaData.h @@ -47,6 +47,8 @@ public: // @return Error string for failed validation explanation to user. Empty string indicates no error. typedef QString (*CustomCookedValidator)(const QVariant& cookedValue); + typedef QMap NameToMetaDataMap_t; + FactMetaData(QObject* parent = nullptr); FactMetaData(ValueType_t type, QObject* parent = nullptr); FactMetaData(ValueType_t type, const QString name, QObject* parent = nullptr); @@ -359,6 +361,9 @@ private: static const char* _incrementJsonKey; static const char* _hasControlJsonKey; static const char* _qgcRebootRequiredJsonKey; + static const char* _categoryJsonKey; + static const char* _groupJsonKey; + static const char* _volatileJsonKey; static const char* _jsonMetaDataDefinesName; static const char* _jsonMetaDataFactsName; diff --git a/src/FactSystem/ParameterManager.cc b/src/FactSystem/ParameterManager.cc index 4304d4ae802f42ca346bc45bfe1326e80518400f..0a7bda58baf3ba2235e79211a33f29dbbc5b619e 100644 --- a/src/FactSystem/ParameterManager.cc +++ b/src/FactSystem/ParameterManager.cc @@ -15,6 +15,8 @@ #include "FirmwarePlugin.h" #include "UAS.h" #include "JsonHelper.h" +#include "ComponentInformationManager.h" +#include "CompInfoParam.h" #include #include @@ -63,7 +65,6 @@ const QHash _mavlinkCompIdHash { { MAV_COMP_ID_GPS2, "GPS2" } }; -const char* ParameterManager::_cachedMetaDataFilePrefix = "ParameterFactMetaData"; const char* ParameterManager::_jsonParametersKey = "parameters"; const char* ParameterManager::_jsonCompIdKey = "compId"; const char* ParameterManager::_jsonParamNameKey = "name"; @@ -82,7 +83,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle) , _metaDataAddedToFacts (false) , _logReplay (vehicle->priorityLink() && vehicle->priorityLink()->isLogReplay()) , _parameterSetMajorVersion (-1) - , _parameterMetaData (nullptr) , _prevWaitingReadParamIndexCount (0) , _prevWaitingReadParamNameCount (0) , _prevWaitingWriteParamNameCount (0) @@ -114,11 +114,6 @@ ParameterManager::ParameterManager(Vehicle* vehicle) QFileInfo(QSettings().fileName()).dir().mkdir("ParamCache"); } -ParameterManager::~ParameterManager() -{ - delete _parameterMetaData; -} - void ParameterManager::_updateProgressBar(void) { int waitingReadParamIndexCount = 0; @@ -937,20 +932,12 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian if (cacheMap.contains(_versionParam)) { _parameterSetMajorVersion = cacheMap[_versionParam].second.toInt(); } - _loadMetaData(); + _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_parameterMajorVersionKnown(_parameterSetMajorVersion); /* compute the crc of the local cache to check against the remote */ - FirmwarePlugin* firmwarePlugin = _vehicle->firmwarePlugin(); for (const QString& name: cacheMap.keys()) { - bool volatileValue = false; - - FactMetaData* metaData = firmwarePlugin->getMetaDataForFact(_parameterMetaData, name, _vehicle->vehicleType()); - if (metaData) { - volatileValue = metaData->volatileValue(); - } - - if (volatileValue) { + if (_vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_isParameterVolatile(name)) { // Does not take part in CRC qCDebug(ParameterManagerLog) << "Volatile parameter" << name; } else { @@ -1015,7 +1002,6 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian } else { // Cache parameter version may differ from vehicle parameter version so we can't trust information loaded from cache parameter version number _parameterSetMajorVersion = -1; - _clearMetaData(); qCInfo(ParameterManagerLog) << "Parameters cache match failed" << qPrintable(QFileInfo(cacheFile).absoluteFilePath()); if (ParameterManagerDebugCacheFailureLog().isDebugEnabled()) { _debugCacheCRC[componentId] = true; @@ -1025,6 +1011,7 @@ void ParameterManager::_tryCacheHashLoad(int vehicleId, int componentId, QVarian } qgcApp()->showAppMessage(tr("Parameter cache CRC match failed")); } + _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_clearPX4ParameterMetaData(); } } @@ -1193,42 +1180,23 @@ FactMetaData::ValueType_t ParameterManager::_mavTypeToFactType(MAV_PARAM_TYPE ma } } -void ParameterManager::_clearMetaData(void) -{ - if (_parameterMetaData) { - _parameterMetaData->deleteLater(); - _parameterMetaData = nullptr; - } -} - -void ParameterManager::_loadMetaData(void) -{ - if (_parameterMetaData) { - return; - } - - QString metaDataFile; - int majorVersion, minorVersion; - - // Load best parameter meta data set - metaDataFile = parameterMetaDataFile(_vehicle, _vehicle->firmwareType(), _parameterSetMajorVersion, majorVersion, minorVersion); - qCDebug(ParameterManagerLog) << "Loading meta data file:major:minor" << metaDataFile << majorVersion << minorVersion; - _parameterMetaData = _vehicle->firmwarePlugin()->loadParameterMetaData(metaDataFile); -} - void ParameterManager::_addMetaDataToDefaultComponent(void) { - _loadMetaData(); - if (_metaDataAddedToFacts) { return; } _metaDataAddedToFacts = true; - // Loop over all parameters in default component adding meta data - QVariantMap& factMap = _mapParameterName2Variant[_vehicle->defaultComponentId()]; - for (const QString& key: factMap.keys()) { - _vehicle->firmwarePlugin()->addMetaDataToFact(_parameterMetaData, factMap[key].value(), _vehicle->vehicleType()); + _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->_parameterMajorVersionKnown(_parameterSetMajorVersion); + + if (_mapParameterName2Variant.contains(MAV_COMP_ID_AUTOPILOT1)) { + // Loop over all parameters in autopilot component adding meta data + QVariantMap& factMap = _mapParameterName2Variant[MAV_COMP_ID_AUTOPILOT1]; + for (const QString& key: factMap.keys()) { + Fact* fact = factMap[key].value(); + FactMetaData* factMetaData = _vehicle->compInfoManager()->compInfoParam(MAV_COMP_ID_AUTOPILOT1)->factMetaDataForName(key, fact->type()); + fact->setMetaData(factMetaData); + } } } @@ -1319,152 +1287,6 @@ void ParameterManager::_initialRequestTimeout(void) } } -QString ParameterManager::parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion) -{ - bool cacheHit = false; - FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(firmwareType); - - // Cached files are stored in settings location - QSettings settings; - QDir cacheDir = QFileInfo(settings.fileName()).dir(); - - // First look for a direct cache hit - int cacheMinorVersion, cacheMajorVersion; - QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion))); - if (cacheFile.exists()) { - plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion); - if (wantedMajorVersion != cacheMajorVersion) { - qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion; - } else { - qCDebug(ParameterManagerLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion; - cacheHit = true; - } - } - - if (!cacheHit) { - // No direct hit, look for lower param set version - QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType); - QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name); - - // Find the highest major version number which is below the vehicles major version number - int cacheHitIndex = -1; - cacheMajorVersion = -1; - QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType)); - for (int i=0; i< cacheHits.count(); i++) { - if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) { - int majorVersion = regExp.capturedTexts()[0].toInt(); - if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) { - cacheMajorVersion = majorVersion; - cacheHitIndex = i; - } - } - } - - if (cacheHitIndex != -1) { - // We have a cache hit on a lower major version, read minor version as well - int majorVersion; - cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex])); - plugin->getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion); - if (majorVersion != cacheMajorVersion) { - qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion; - cacheHit = false; - } else { - qCDebug(ParameterManagerLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion; - cacheHit = true; - } - } - } - - int internalMinorVersion, internalMajorVersion; - QString internalMetaDataFile = plugin->internalParameterMetaDataFile(vehicle); - plugin->getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion); - qCDebug(ParameterManagerLog) << "Internal meta data file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion; - if (cacheHit) { - // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version - if (internalMajorVersion == wantedMajorVersion) { - if (cacheMajorVersion == wantedMajorVersion) { - // Both internal and cache are direct hit on major version, Use higher minor version number - cacheHit = cacheMinorVersion > internalMinorVersion; - } else { - // Direct internal hit, but not direct hit in cache, use internal - cacheHit = false; - } - } else { - if (cacheMajorVersion == wantedMajorVersion) { - // Direct hit on cache, no direct hit on internal, use cache - cacheHit = true; - } else { - // No direct hit anywhere, use internal - cacheHit = false; - } - } - } - - QString metaDataFile; - if (cacheHit && !qgcApp()->runningUnitTests()) { - majorVersion = cacheMajorVersion; - minorVersion = cacheMinorVersion; - metaDataFile = cacheFile.fileName(); - } else { - majorVersion = internalMajorVersion; - minorVersion = internalMinorVersion; - metaDataFile = internalMetaDataFile; - } - qCDebug(ParameterManagerLog) << "ParameterManager::parameterMetaDataFile file:major:minor" << metaDataFile << majorVersion << minorVersion; - - return metaDataFile; -} - -FirmwarePlugin* ParameterManager::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType) -{ - // There are cases where we need a FirmwarePlugin but we don't have a vehicle. In those specified case the plugin for any of the supported vehicle types will do. - MAV_TYPE anySupportedVehicleType = qgcApp()->toolbox()->firmwarePluginManager()->supportedVehicleTypes(firmwareType)[0]; - - return qgcApp()->toolbox()->firmwarePluginManager()->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType); -} - -void ParameterManager::cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType) -{ - FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(firmwareType); - - int newMajorVersion, newMinorVersion; - plugin->getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion); - qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile file:firmware:major;minor" << metaDataFile << firmwareType << newMajorVersion << newMinorVersion; - - // Find the cache hit closest to this new file - int cacheMajorVersion, cacheMinorVersion; - QString cacheHit = ParameterManager::parameterMetaDataFile(nullptr, firmwareType, newMajorVersion, cacheMajorVersion, cacheMinorVersion); - qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion; - - bool cacheNewFile = false; - if (cacheHit.isEmpty()) { - // No cache hits, store the new file - cacheNewFile = true; - } else if (cacheMajorVersion == newMajorVersion) { - // Direct hit on major version in cache: - // Cache new file if newer/equal minor version. We cache if equal to allow flashing test builds with new parameter metadata. - // Also delete older cache file. - if (newMinorVersion >= cacheMinorVersion) { - cacheNewFile = true; - QFile::remove(cacheHit); - } - } else { - // Indirect hit in cache, store new file - cacheNewFile = true; - } - - if (cacheNewFile) { - // Cached files are stored in settings location. Copy from current file to cache naming. - - QSettings settings; - QDir cacheDir = QFileInfo(settings.fileName()).dir(); - QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(newMajorVersion))); - qCDebug(ParameterManagerLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName(); - QFile newFile(metaDataFile); - newFile.copy(cacheFile.fileName()); - } -} - /// Remap a parameter from one firmware version to another QString ParameterManager::_remapParamNameToVersion(const QString& paramName) { @@ -1583,118 +1405,12 @@ void ParameterManager::_loadOfflineEditingParams(void) _mapParameterName2Variant[defaultComponentId][paramName] = QVariant::fromValue(fact); } - _addMetaDataToDefaultComponent(); _setupDefaultComponentCategoryMap(); _parametersReady = true; _initialLoadComplete = true; _debugCacheCRC.clear(); } -void ParameterManager::saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject) -{ - QList rgCompIds; - QStringList rgParamNames; - - if (componentId == MAV_COMP_ID_ALL) { - rgCompIds = _mapParameterName2Variant.keys(); - } else { - rgCompIds.append(_actualComponentId(componentId)); - } - - QJsonArray rgParams; - - // Loop over all requested component ids - for (int i=0; iname())); - paramJson.insert(_jsonParamValueKey, QJsonValue(fact->rawValue().toDouble())); - - rgParams.append(QJsonValue(paramJson)); - } - } - - saveObject.insert(_jsonParametersKey, QJsonValue(rgParams)); -} - -bool ParameterManager::loadFromJson(const QJsonObject& json, bool required, QString& errorString) -{ - QList keyTypes; - - errorString.clear(); - - if (required) { - if (!JsonHelper::validateRequiredKeys(json, QStringList(_jsonParametersKey), errorString)) { - return false; - } - } else if (!json.contains(_jsonParametersKey)) { - return true; - } - - keyTypes = { QJsonValue::Array }; - if (!JsonHelper::validateKeyTypes(json, QStringList(_jsonParametersKey), keyTypes, errorString)) { - return false; - } - - QJsonArray rgParams = json[_jsonParametersKey].toArray(); - for (int i=0; isetRawValue(value); - } - - return true; -} - void ParameterManager::resetAllParametersToDefaults() { _vehicle->sendMavCommand(MAV_COMP_ID_ALL, diff --git a/src/FactSystem/ParameterManager.h b/src/FactSystem/ParameterManager.h index e1b061cb8942ee40756d501aae4bd1ac0c80e82d..334db9844418c7f04972e8997cd8b4253e5f9d8d 100644 --- a/src/FactSystem/ParameterManager.h +++ b/src/FactSystem/ParameterManager.h @@ -33,8 +33,7 @@ class ParameterManager : public QObject public: /// @param uas Uas which this set of facts is associated with - ParameterManager (Vehicle* vehicle); - ~ParameterManager (); + ParameterManager(Vehicle* vehicle); Q_PROPERTY(bool parametersReady READ parametersReady NOTIFY parametersReadyChanged) ///< true: Parameters are ready for use Q_PROPERTY(bool missingParameters READ missingParameters NOTIFY missingParametersChanged) ///< true: Parameters are missing from firmware response, false: all parameters received from firmware @@ -91,29 +90,6 @@ public: /// Returns the version number for the parameter set, -1 if not known int parameterSetVersion(void) { return _parameterSetMajorVersion; } - /// Returns the newest available parameter meta data file (from cache or internal) for the specified information. - /// @param wantedMajorVersion Major version you are looking for - /// @param[out] majorVersion Major version for found meta data - /// @param[out] minorVersion Minor version for found meta data - /// @return Meta data file name of best match, emptyString is none found - static QString parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion); - - /// If this file is newer than anything in the cache, cache it as the latest version - static void cacheMetaDataFile(const QString& metaDataFile, MAV_AUTOPILOT firmwareType); - - /// Saves the specified param set to the json object. - /// @param componentId Component id which contains params, MAV_COMP_ID_ALL to save all components - /// @param paramsToSave List of params names to save, empty to save all for component - /// @param saveObject Json object to save to - void saveToJson(int componentId, const QStringList& paramsToSave, QJsonObject& saveObject); - - /// Load a parameter set from json - /// @param json Json object to load from - /// @param required true: no parameters in object will generate error - /// @param errorString Error string if return is false - /// @return true: success, false: failure (errorString set) - bool loadFromJson(const QJsonObject& json, bool required, QString& errorString); - bool pendingWrites(void); Vehicle* vehicle(void) { return _vehicle; } @@ -128,32 +104,31 @@ protected: Vehicle* _vehicle; MAVLinkProtocol* _mavlink; - void _parameterUpdate(int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); - void _valueUpdated(const QVariant& value); - void _waitingParamTimeout(void); - void _tryCacheLookup(void); - void _initialRequestTimeout(void); + void _parameterUpdate (int vehicleId, int componentId, QString parameterName, int parameterCount, int parameterId, int mavType, QVariant value); + void _valueUpdated (const QVariant& value); + void _waitingParamTimeout (void); + void _tryCacheLookup (void); + void _initialRequestTimeout (void); private: static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool failOk = false); - static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType); - - int _actualComponentId(int componentId); - void _setupComponentCategoryMap(int componentId); - void _setupDefaultComponentCategoryMap(void); - void _readParameterRaw(int componentId, const QString& paramName, int paramIndex); - void _writeParameterRaw(int componentId, const QString& paramName, const QVariant& value); - void _writeLocalParamCache(int vehicleId, int componentId); - void _tryCacheHashLoad(int vehicleId, int componentId, QVariant hash_value); - void _loadMetaData(void); - void _clearMetaData(void); - void _addMetaDataToDefaultComponent(void); - QString _remapParamNameToVersion(const QString& paramName); - void _loadOfflineEditingParams(void); - QString _logVehiclePrefix(int componentId); - void _setLoadProgress(double loadProgress); - bool _fillIndexBatchQueue(bool waitingParamTimeout); - void _updateProgressBar(void); + + int _actualComponentId (int componentId); + void _setupComponentCategoryMap (int componentId); + void _setupDefaultComponentCategoryMap (void); + void _readParameterRaw (int componentId, const QString& paramName, int paramIndex); + void _writeParameterRaw (int componentId, const QString& paramName, const QVariant& value); + void _writeLocalParamCache (int vehicleId, int componentId); + void _tryCacheHashLoad (int vehicleId, int componentId, QVariant hash_value); + void _loadMetaData (void); + void _clearMetaData (void); + void _addMetaDataToDefaultComponent (void); + QString _remapParamNameToVersion (const QString& paramName); + void _loadOfflineEditingParams (void); + QString _logVehiclePrefix (int componentId); + void _setLoadProgress (double loadProgress); + bool _fillIndexBatchQueue (bool waitingParamTimeout); + void _updateProgressBar (void); MAV_PARAM_TYPE _factTypeToMavType(FactMetaData::ValueType_t factType); FactMetaData::ValueType_t _mavTypeToFactType(MAV_PARAM_TYPE mavType); @@ -178,7 +153,6 @@ private: bool _logReplay; ///< true: running with log replay link QString _versionParam; ///< Parameter which contains parameter set version int _parameterSetMajorVersion; ///< Version for parameter set, -1 if not known - QObject* _parameterMetaData; ///< Opaque data from FirmwarePlugin::loadParameterMetaDataCall typedef QPair ParamTypeVal; typedef QMap CacheMapName2ParamTypeVal; @@ -222,7 +196,6 @@ private: Fact _defaultFact; ///< Used to return default fact, when parameter not found - static const char* _cachedMetaDataFilePrefix; static const char* _jsonParametersKey; static const char* _jsonCompIdKey; static const char* _jsonParamNameKey; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 4e66b44185e5cc2e31f067478b5634c009c030d1..4fefe198b81b892b13c6a0b762c44b8a78b3985f 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -702,15 +702,17 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) return true; } -void APMFirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) +FactMetaData* APMFirmwarePlugin::_getMetaDataForFact(QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) { APMParameterMetaData* apmMetaData = qobject_cast(parameterMetaData); if (apmMetaData) { - apmMetaData->addMetaDataToFact(fact, vehicleType); + return apmMetaData->getMetaDataForFact(name, vehicleType, type); } else { qWarning() << "Internal error: pointer passed to APMFirmwarePlugin::addMetaDataToFact not APMParameterMetaData"; } + + return nullptr; } QList APMFirmwarePlugin::supportedMissionCommands(void) @@ -771,7 +773,7 @@ QString APMFirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const } } -QObject* APMFirmwarePlugin::loadParameterMetaData(const QString& metaDataFile) +QObject* APMFirmwarePlugin::_loadParameterMetaData(const QString& metaDataFile) { Q_UNUSED(metaDataFile); @@ -806,7 +808,7 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr qgcApp()->showAppMessage(tr("Error during Solo video link setup: %1").arg(socketError)); } -QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) +QString APMFirmwarePlugin::_internalParameterMetaDataFile(Vehicle* vehicle) { switch (vehicle->vehicleType()) { case MAV_TYPE_QUADROTOR: diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index 802a1b28f6c60d46073b7a2aec2e1912821ec450..02b02ea4be30adaf81cf292697d2b076d4823ebe 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -97,12 +97,12 @@ public: virtual void initializeStreamRates (Vehicle* vehicle); void initializeVehicle (Vehicle* vehicle) override; bool sendHomePositionToVehicle (void) override; - void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override; QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString getVersionParam (void) override { return QStringLiteral("SYSID_SW_MREV"); } - QString internalParameterMetaDataFile (Vehicle* vehicle) override; - void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } - QObject* loadParameterMetaData (const QString& metaDataFile) override; + QString _internalParameterMetaDataFile (Vehicle* vehicle) override; + FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override; + void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override { APMParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } + QObject* _loadParameterMetaData (const QString& metaDataFile) override; QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/APM/BrandImage"); } diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 7859fea5b764cdbf4f282ccca8bf51e0d91990a1..b64785c60df8eba6da0b284e278ae6831c5e179b 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -425,27 +425,26 @@ bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFa return true; } -void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) +FactMetaData* APMParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type) { const QString mavTypeString = mavTypeToString(vehicleType); APMFactMetaDataRaw* rawMetaData = nullptr; // check if we have metadata for fact, use generic otherwise - if (_vehicleTypeToParametersMap[mavTypeString].contains(fact->name())) { - rawMetaData = _vehicleTypeToParametersMap[mavTypeString][fact->name()]; - } else if (_vehicleTypeToParametersMap["libraries"].contains(fact->name())) { - rawMetaData = _vehicleTypeToParametersMap["libraries"][fact->name()]; + if (_vehicleTypeToParametersMap[mavTypeString].contains(name)) { + rawMetaData = _vehicleTypeToParametersMap[mavTypeString][name]; + } else if (_vehicleTypeToParametersMap["libraries"].contains(name)) { + rawMetaData = _vehicleTypeToParametersMap["libraries"][name]; } - FactMetaData *metaData = new FactMetaData(fact->type(), fact); + FactMetaData *metaData = new FactMetaData(type, this); // we don't have data for this fact if (!rawMetaData) { metaData->setCategory(QStringLiteral("Advanced")); - metaData->setGroup(_groupFromParameterName(fact->name())); - fact->setMetaData(metaData); - qCDebug(APMParameterMetaDataLog) << "No metaData for " << fact->name() << "using generic metadata"; - return; + metaData->setGroup(_groupFromParameterName(name)); + qCDebug(APMParameterMetaDataLog) << "No metaData for " << name << "using generic metadata"; + return metaData; } metaData->setName(rawMetaData->name); @@ -531,7 +530,7 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) QVariant typedBitSet; - switch (fact->type()) { + switch (type) { case FactMetaData::valueTypeInt8: typedBitSet = QVariant((signed char)bitSet); break; @@ -599,15 +598,15 @@ void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) } // ArduPilot does not yet support decimal places meta data. So for P/I/D parameters we force to 6 places - if ((fact->name().endsWith(QStringLiteral("_P")) || - fact->name().endsWith(QStringLiteral("_I")) || - fact->name().endsWith(QStringLiteral("_D"))) && - (fact->type() == FactMetaData::valueTypeFloat || - fact->type() == FactMetaData::valueTypeDouble)) { + if ((name.endsWith(QStringLiteral("_P")) || + name.endsWith(QStringLiteral("_I")) || + name.endsWith(QStringLiteral("_D"))) && + (type == FactMetaData::valueTypeFloat || + type == FactMetaData::valueTypeDouble)) { metaData->setDecimalPlaces(6); } - fact->setMetaData(metaData); + return metaData; } void APMParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.h b/src/FirmwarePlugin/APM/APMParameterMetaData.h index 51ca87b4569621c28a61ccb936df5a80922092eb..b86ad5442d6e863f4aee74cec57e49c73e6f5307 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.h +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.h @@ -58,7 +58,7 @@ class APMParameterMetaData : public QObject public: APMParameterMetaData(void); - void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); + FactMetaData* getMetaDataForFact(const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type); void loadParameterFactMetaDataFile(const QString& metaDataFile); static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); @@ -83,8 +83,9 @@ private: QString mavTypeToString(MAV_TYPE vehicleTypeEnum); QString _groupFromParameterName(const QString& name); - bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded - QMap _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map> + bool _parameterMetaDataLoaded = false; ///< true: parameter meta data already loaded + // FIXME: metadata is vehicle type specific now + QMap _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map> }; #endif diff --git a/src/FirmwarePlugin/FirmwarePlugin.cc b/src/FirmwarePlugin/FirmwarePlugin.cc index 531fd1abe6b92b47c006610632ec8c3352bb8922..0a1096fa2c510ed8d62e32ee76ea2e5f517d714c 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.cc +++ b/src/FirmwarePlugin/FirmwarePlugin.cc @@ -203,7 +203,7 @@ QString FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const } } -void FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) +void FirmwarePlugin::_getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) { Q_UNUSED(metaDataFile); majorVersion = -1; diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index aa6cade478884e1cc154c51aef29af55180dab5b..b80f12db72311229a4b6d522040e0a797e3d3b4f 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -214,24 +214,28 @@ public: /// Returns the parameter set version info pulled from inside the meta data file. -1 if not found. /// Note: The implementation for this must not vary by vehicle type. - virtual void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); + /// Important: Only CompInfoParam code should use this method + virtual void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); /// Returns the internal resource parameter meta date file. - virtual QString internalParameterMetaDataFile(Vehicle* /*vehicle*/) { return QString(); } + /// Important: Only CompInfoParam code should use this method + virtual QString _internalParameterMetaDataFile(Vehicle* /*vehicle*/) { return QString(); } /// Loads the specified parameter meta data file. /// @return Opaque parameter meta data information which must be stored with Vehicle. Vehicle is responsible to /// call deleteParameterMetaData when no longer needed. - virtual QObject* loadParameterMetaData(const QString& /*metaDataFile*/) { return nullptr; } + /// Important: Only CompInfoParam code should use this method + virtual QObject* _loadParameterMetaData(const QString& /*metaDataFile*/) { return nullptr; } /// Returns the FactMetaData associated with the parameter name /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData - /// @param name Parameter name - virtual FactMetaData* getMetaDataForFact(QObject* /*parameterMetaData*/, const QString& /*name*/, MAV_TYPE /*vehicleType*/) { return nullptr; } + /// Important: Only CompInfoParam code should use this method + virtual FactMetaData* _getMetaDataForFact(QObject* /*parameterMetaData*/, const QString& /*name*/, FactMetaData::ValueType_t /* type */, MAV_TYPE /*vehicleType*/) { return nullptr; } - /// Adds the parameter meta data to the Fact + /// Returns the FactMetaData associated with the parameter name /// @param opaqueParameterMetaData Opaque pointer returned from loadParameterMetaData - virtual void addMetaDataToFact(QObject* /*parameterMetaData*/, Fact* /*fact*/, MAV_TYPE /*vehicleType*/) { return; } + /// Important: Only CompInfoParam code should use this method + virtual bool _isParameterVolatile(QObject* /*parameterMetaData*/, const QString& /*name*/, MAV_TYPE /*vehicleType*/) { return false; } /// List of supported mission commands. Empty list for all commands supported. virtual QList supportedMissionCommands(void); diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 9e70bffece639fc6469e1269ae11ce75a0ab0b61..9fd02fa5a38601f120914da87a98b73fc29e030c 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -250,12 +250,12 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) return false; } -FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) +FactMetaData* PX4FirmwarePlugin::_getMetaDataForFact(QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) { PX4ParameterMetaData* px4MetaData = qobject_cast(parameterMetaData); if (px4MetaData) { - return px4MetaData->getMetaDataForFact(name, vehicleType); + return px4MetaData->getMetaDataForFact(name, vehicleType, type); } else { qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::getMetaDataForFact not PX4ParameterMetaData"; } @@ -263,18 +263,7 @@ FactMetaData* PX4FirmwarePlugin::getMetaDataForFact(QObject* parameterMetaData, return nullptr; } -void PX4FirmwarePlugin::addMetaDataToFact(QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) -{ - PX4ParameterMetaData* px4MetaData = qobject_cast(parameterMetaData); - - if (px4MetaData) { - px4MetaData->addMetaDataToFact(fact, vehicleType); - } else { - qWarning() << "Internal error: pointer passed to PX4FirmwarePlugin::addMetaDataToFact not PX4ParameterMetaData"; - } -} - -void PX4FirmwarePlugin::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) +void PX4FirmwarePlugin::_getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) { return PX4ParameterMetaData::getParameterMetaDataVersionInfo(metaDataFile, majorVersion, minorVersion); } @@ -329,7 +318,7 @@ QString PX4FirmwarePlugin::missionCommandOverrides(MAV_TYPE vehicleType) const } } -QObject* PX4FirmwarePlugin::loadParameterMetaData(const QString& metaDataFile) +QObject* PX4FirmwarePlugin::_loadParameterMetaData(const QString& metaDataFile) { PX4ParameterMetaData* metaData = new PX4ParameterMetaData; if (!metaDataFile.isEmpty()) { diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index cf522c4f465cd975915c101d4f9f6df7100d9f52..554c8caff431ea0e8bbc033f070ef4607f85ebac 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -55,15 +55,14 @@ public: bool isGuidedMode (const Vehicle* vehicle) const override; void initializeVehicle (Vehicle* vehicle) override; bool sendHomePositionToVehicle (void) override; - void addMetaDataToFact (QObject* parameterMetaData, Fact* fact, MAV_TYPE vehicleType) override; - FactMetaData* getMetaDataForFact (QObject* parameterMetaData, const QString& name, MAV_TYPE vehicleType) override; QString missionCommandOverrides (MAV_TYPE vehicleType) const override; QString getVersionParam (void) override { return QString("SYS_PARAM_VER"); } - QString internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } - void getParameterMetaDataVersionInfo (const QString& metaDataFile, int& majorVersion, int& minorVersion) override; - QObject* loadParameterMetaData (const QString& metaDataFile) final; + FactMetaData* _getMetaDataForFact (QObject* parameterMetaData, const QString& name, FactMetaData::ValueType_t type, MAV_TYPE vehicleType) override; + QString _internalParameterMetaDataFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QString(":/FirmwarePlugin/PX4/PX4ParameterFactMetaData.xml"); } + void _getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) override; + QObject* _loadParameterMetaData (const QString& metaDataFile) final; bool adjustIncomingMavlinkMessage (Vehicle* vehicle, mavlink_message_t* message) override; - QString offlineEditingParamFile(Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); } + QString offlineEditingParamFile (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/PX4/PX4.OfflineEditing.params"); } QString brandImageIndoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } QString brandImageOutdoor (const Vehicle* vehicle) const override { Q_UNUSED(vehicle); return QStringLiteral("/qmlimages/PX4/BrandImage"); } QString autoDisarmParameter (Vehicle* vehicle) override { Q_UNUSED(vehicle); return QStringLiteral("COM_DISARM_LAND"); } diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index 161a5a4798cb16b59c4c2a98e69e91ad60e39336..0ce2badab487cfc0a15d848692e2a58816255a9a 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -25,7 +25,6 @@ static const char* kInvalidConverstion = "Internal Error: No support for string QGC_LOGGING_CATEGORY(PX4ParameterMetaDataLog, "PX4ParameterMetaDataLog") PX4ParameterMetaData::PX4ParameterMetaData(void) - : _parameterMetaDataLoaded(false) { } @@ -480,7 +479,7 @@ void PX4ParameterMetaData::_generateParameterJson() if (metaData->volatileValue()) { _jsonWriteLine(jsonFile, indentLevel, "\"volatile\": true,"); } - _jsonWriteLine(jsonFile, indentLevel, QStringLiteral("\"decimalPlaces\": \"%1\",").arg(metaData->decimalPlaces())); + _jsonWriteLine(jsonFile, indentLevel, QStringLiteral("\"decimalPlaces\": %1,").arg(metaData->decimalPlaces())); _jsonWriteLine(jsonFile, indentLevel, QStringLiteral("\"minValue\": %1,").arg(metaData->rawMin().toDouble())); _jsonWriteLine(jsonFile, indentLevel, QStringLiteral("\"maxValue\": %1").arg(metaData->rawMax().toDouble())); _jsonWriteLine(jsonFile, --indentLevel, QStringLiteral("}%1").arg(++keyIndex == _mapParameterName2FactMetaData.keys().count() ? "" : ",")); @@ -491,24 +490,17 @@ void PX4ParameterMetaData::_generateParameterJson() } #endif -FactMetaData* PX4ParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType) +FactMetaData* PX4ParameterMetaData::getMetaDataForFact(const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type) { Q_UNUSED(vehicleType) - if (_mapParameterName2FactMetaData.contains(name)) { - return _mapParameterName2FactMetaData[name]; - } else { - return nullptr; + if (!_mapParameterName2FactMetaData.contains(name)) { + qCDebug(PX4ParameterMetaDataLog) << "No metaData for " << name << "using generic metadata"; + FactMetaData* metaData = new FactMetaData(type, this); + _mapParameterName2FactMetaData[name] = metaData; } -} -void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) -{ - Q_UNUSED(vehicleType) - - if (_mapParameterName2FactMetaData.contains(fact->name())) { - fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); - } + return _mapParameterName2FactMetaData[name]; } void PX4ParameterMetaData::getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion) diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h index 24cfe48d3b6b84cab94e9cd1350e8f5932a37075..30bccc3cda20ac6405690bb0e3485feaa2056143 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h @@ -36,8 +36,7 @@ public: PX4ParameterMetaData(void); void loadParameterFactMetaDataFile (const QString& metaDataFile); - FactMetaData* getMetaDataForFact (const QString& name, MAV_TYPE vehicleType); - void addMetaDataToFact (Fact* fact, MAV_TYPE vehicleType); + FactMetaData* getMetaDataForFact (const QString& name, MAV_TYPE vehicleType, FactMetaData::ValueType_t type); static void getParameterMetaDataVersionInfo(const QString& metaDataFile, int& majorVersion, int& minorVersion); @@ -58,8 +57,8 @@ private: void _generateParameterJson(); #endif - bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded - QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData + bool _parameterMetaDataLoaded = false; ///< true: parameter meta data already loaded + FactMetaData::NameToMetaDataMap_t _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData }; #endif diff --git a/src/Vehicle/CompInfo.cc b/src/Vehicle/CompInfo.cc new file mode 100644 index 0000000000000000000000000000000000000000..510fef9bb5b51eebbb994f9b46dbc7613a48ae46 --- /dev/null +++ b/src/Vehicle/CompInfo.cc @@ -0,0 +1,32 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "CompInfo.h" + +CompInfo::CompInfo(COMP_METADATA_TYPE type, uint8_t compId, Vehicle* vehicle, QObject* parent) + : QObject (parent) + , type (type) + , vehicle (vehicle) + , compId (compId) +{ + +} + +void CompInfo::setMessage(const mavlink_message_t& message) +{ + mavlink_component_information_t componentInformation; + + mavlink_msg_component_information_decode(&message, &componentInformation); + + available = true; + uidMetaData = componentInformation.metadata_uid; + uidTranslation = componentInformation.translation_uid; + uriMetaData = componentInformation.metadata_uri; + uriTranslation = componentInformation.translation_uri; +} diff --git a/src/Vehicle/CompInfo.h b/src/Vehicle/CompInfo.h new file mode 100644 index 0000000000000000000000000000000000000000..cc15e5bfdc9943af005fdeb085c6a6cb42e73733 --- /dev/null +++ b/src/Vehicle/CompInfo.h @@ -0,0 +1,43 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "QGCMAVLink.h" +#include "QGCLoggingCategory.h" +#include "FactMetaData.h" + +#include + +class FactMetaData; +class Vehicle; +class FirmwarePlugin; + +/// Base class for all CompInfo types +class CompInfo : public QObject +{ + Q_OBJECT + +public: + CompInfo(COMP_METADATA_TYPE type, uint8_t compId, Vehicle* vehicle, QObject* parent = nullptr); + + /// Called to pass the COMPONENT_INFORMATION message in + void setMessage(const mavlink_message_t& message); + + virtual void setJson(const QString& metaDataJsonFileName, const QString& translationJsonFileName) = 0; + + COMP_METADATA_TYPE type; + Vehicle* vehicle = nullptr; + uint8_t compId = MAV_COMP_ID_ALL; + bool available = false; + uint32_t uidMetaData = 0; + uint32_t uidTranslation = 0; + QString uriMetaData; + QString uriTranslation; +}; diff --git a/src/Vehicle/CompInfoParam.cc b/src/Vehicle/CompInfoParam.cc new file mode 100644 index 0000000000000000000000000000000000000000..5e1471d3434dc68cb725bb681f6c0f9652cdd1da --- /dev/null +++ b/src/Vehicle/CompInfoParam.cc @@ -0,0 +1,277 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "CompInfoParam.h" +#include "JsonHelper.h" +#include "FactMetaData.h" +#include "FirmwarePlugin.h" +#include "FirmwarePluginManager.h" +#include "QGCApplication.h" + +#include +#include +#include + +QGC_LOGGING_CATEGORY(CompInfoParamLog, "CompInfoParamLog") + +const char* CompInfoParam::_jsonScopeKey = "scope"; +const char* CompInfoParam::_jsonParametersKey = "parameters"; +const char* CompInfoParam::_cachedMetaDataFilePrefix = "ParameterFactMetaData"; + +CompInfoParam::CompInfoParam(uint8_t compId, Vehicle* vehicle, QObject* parent) + : CompInfo(COMP_METADATA_TYPE_PARAMETER, compId, vehicle, parent) +{ + +} + +void CompInfoParam::setJson(const QString& metadataJsonFileName, const QString& /*translationJsonFileName*/) +{ + if (metadataJsonFileName.isEmpty()) { + // This will fall back to using the old FirmwarePlugin mechanism for parameter meta data. + // In this case paramter metadata is loaded through the _parameterMajorVersionKnown call which happens after parameter are downloaded + return; + } + + QString errorString; + QJsonDocument jsonDoc; + + _noJsonMetadata = false; + + if (!JsonHelper::isJsonFile(metadataJsonFileName, jsonDoc, errorString)) { + qCWarning(CompInfoParamLog) << "Metadata json file open failed: compid:" << compId << errorString; + return; + } + QJsonObject jsonObj = jsonDoc.object(); + + QList keyInfoList = { + { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, + { _jsonScopeKey, QJsonValue::String, true }, + { _jsonParametersKey, QJsonValue::Array, true }, + }; + if (!JsonHelper::validateKeys(jsonObj, keyInfoList, errorString)) { + qCWarning(CompInfoParamLog) << "Metadata json validation failed: compid:" << compId << errorString; + return; + } + + int version = jsonObj[JsonHelper::jsonVersionKey].toInt(); + if (version != 1) { + qCWarning(CompInfoParamLog) << "Metadata json unsupported version" << version; + return; + } + + QJsonArray rgParameters = jsonObj[_jsonParametersKey].toArray(); + for (const QJsonValue& parameterValue: rgParameters) { + QMap emptyDefineMap; + + if (!parameterValue.isObject()) { + qCWarning(CompInfoParamLog) << "Metadata json read failed: compid:" << compId << "parameters array contains non-object"; + return; + } + + FactMetaData* newMetaData = FactMetaData::createFromJsonObject(parameterValue.toObject(), emptyDefineMap, this); + _nameToMetaDataMap[newMetaData->name()] = newMetaData; + } +} + +FactMetaData* CompInfoParam::factMetaDataForName(const QString& name, FactMetaData::ValueType_t type) +{ + if (_opaqueParameterMetaData) { + return vehicle->firmwarePlugin()->_getMetaDataForFact(_opaqueParameterMetaData, name, type, vehicle->vehicleType()); + } else { + if (!_nameToMetaDataMap.contains(name)) { + _nameToMetaDataMap[name] = new FactMetaData(type, this); + } + return _nameToMetaDataMap[name]; + } +} + +bool CompInfoParam::_isParameterVolatile(const QString& name) +{ + if (_opaqueParameterMetaData) { + return vehicle->firmwarePlugin()->_isParameterVolatile(_opaqueParameterMetaData, name, vehicle->vehicleType()); + } else { + return _nameToMetaDataMap.contains(name) ? _nameToMetaDataMap[name]->volatileValue() : false; + } +} + +FirmwarePlugin* CompInfoParam::_anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT firmwareType) +{ + FirmwarePluginManager* pluginMgr = qgcApp()->toolbox()->firmwarePluginManager(); + MAV_TYPE anySupportedVehicleType = pluginMgr->supportedVehicleTypes(firmwareType)[0]; + + return pluginMgr->firmwarePluginForAutopilot(firmwareType, anySupportedVehicleType); +} + +QString CompInfoParam::_parameterMetaDataFile(Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion) +{ + bool cacheHit = false; + FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(firmwareType); + + if (firmwareType != MAV_AUTOPILOT_PX4) { + return plugin->_internalParameterMetaDataFile(vehicle); + } else { + // Only PX4 support the old style cached metadata + QSettings settings; + QDir cacheDir = QFileInfo(settings.fileName()).dir(); + + // First look for a direct cache hit + int cacheMinorVersion, cacheMajorVersion; + QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType).arg(wantedMajorVersion))); + if (cacheFile.exists()) { + plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), cacheMajorVersion, cacheMinorVersion); + if (wantedMajorVersion != cacheMajorVersion) { + qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << cacheMajorVersion << wantedMajorVersion; + } else { + qCDebug(CompInfoParamLog) << "Direct cache hit on file:major:minor" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion; + cacheHit = true; + } + } + + if (!cacheHit) { + // No direct hit, look for lower param set version + QString wildcard = QString("%1.%2.*.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType); + QStringList cacheHits = cacheDir.entryList(QStringList(wildcard), QDir::Files, QDir::Name); + + // Find the highest major version number which is below the vehicles major version number + int cacheHitIndex = -1; + cacheMajorVersion = -1; + QRegExp regExp(QString("%1\\.%2\\.(\\d*)\\.xml").arg(_cachedMetaDataFilePrefix).arg(firmwareType)); + for (int i=0; i< cacheHits.count(); i++) { + if (regExp.exactMatch(cacheHits[i]) && regExp.captureCount() == 1) { + int majorVersion = regExp.capturedTexts()[0].toInt(); + if (majorVersion > cacheMajorVersion && majorVersion < wantedMajorVersion) { + cacheMajorVersion = majorVersion; + cacheHitIndex = i; + } + } + } + + if (cacheHitIndex != -1) { + // We have a cache hit on a lower major version, read minor version as well + int majorVersion; + cacheFile.setFileName(cacheDir.filePath(cacheHits[cacheHitIndex])); + plugin->_getParameterMetaDataVersionInfo(cacheFile.fileName(), majorVersion, cacheMinorVersion); + if (majorVersion != cacheMajorVersion) { + qWarning() << "Parameter meta data cache corruption:" << cacheFile.fileName() << "major version does not match file name" << "actual:excepted" << majorVersion << cacheMajorVersion; + cacheHit = false; + } else { + qCDebug(CompInfoParamLog) << "Indirect cache hit on file:major:minor:want" << cacheFile.fileName() << cacheMajorVersion << cacheMinorVersion << wantedMajorVersion; + cacheHit = true; + } + } + } + + int internalMinorVersion, internalMajorVersion; + QString internalMetaDataFile = plugin->_internalParameterMetaDataFile(vehicle); + plugin->_getParameterMetaDataVersionInfo(internalMetaDataFile, internalMajorVersion, internalMinorVersion); + qCDebug(CompInfoParamLog) << "Internal metadata file:major:minor" << internalMetaDataFile << internalMajorVersion << internalMinorVersion; + if (cacheHit) { + // Cache hit is available, we need to check if internal meta data is a better match, if so use internal version + if (internalMajorVersion == wantedMajorVersion) { + if (cacheMajorVersion == wantedMajorVersion) { + // Both internal and cache are direct hit on major version, Use higher minor version number + cacheHit = cacheMinorVersion > internalMinorVersion; + } else { + // Direct internal hit, but not direct hit in cache, use internal + cacheHit = false; + } + } else { + if (cacheMajorVersion == wantedMajorVersion) { + // Direct hit on cache, no direct hit on internal, use cache + cacheHit = true; + } else { + // No direct hit anywhere, use internal + cacheHit = false; + } + } + } + + QString metaDataFile; + if (cacheHit && !qgcApp()->runningUnitTests()) { + majorVersion = cacheMajorVersion; + minorVersion = cacheMinorVersion; + metaDataFile = cacheFile.fileName(); + } else { + majorVersion = internalMajorVersion; + minorVersion = internalMinorVersion; + metaDataFile = internalMetaDataFile; + } + qCDebug(CompInfoParamLog) << "_parameterMetaDataFile returning file:major:minor" << metaDataFile << majorVersion << minorVersion; + + return metaDataFile; + } +} + +void CompInfoParam::_cachePX4MetaDataFile(const QString& metaDataFile) +{ + FirmwarePlugin* plugin = _anyVehicleTypeFirmwarePlugin(MAV_AUTOPILOT_PX4); + + int newMajorVersion, newMinorVersion; + plugin->_getParameterMetaDataVersionInfo(metaDataFile, newMajorVersion, newMinorVersion); + qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile file:major;minor" << metaDataFile << newMajorVersion << newMinorVersion; + + // Find the cache hit closest to this new file + int cacheMajorVersion, cacheMinorVersion; + QString cacheHit = _parameterMetaDataFile(nullptr, MAV_AUTOPILOT_PX4, newMajorVersion, cacheMajorVersion, cacheMinorVersion); + qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile cacheHit file:firmware:major;minor" << cacheHit << cacheMajorVersion << cacheMinorVersion; + + bool cacheNewFile = false; + if (cacheHit.isEmpty()) { + // No cache hits, store the new file + cacheNewFile = true; + } else if (cacheMajorVersion == newMajorVersion) { + // Direct hit on major version in cache: + // Cache new file if newer/equal minor version. We cache if equal to allow flashing test builds with new parameter metadata. + // Also delete older cache file. + if (newMinorVersion >= cacheMinorVersion) { + cacheNewFile = true; + QFile::remove(cacheHit); + } + } else { + // Indirect hit in cache, store new file + cacheNewFile = true; + } + + if (cacheNewFile) { + // Cached files are stored in settings location. Copy from current file to cache naming. + + QSettings settings; + QDir cacheDir = QFileInfo(settings.fileName()).dir(); + QFile cacheFile(cacheDir.filePath(QString("%1.%2.%3.xml").arg(_cachedMetaDataFilePrefix).arg(MAV_AUTOPILOT_PX4).arg(newMajorVersion))); + qCDebug(CompInfoParamLog) << "ParameterManager::cacheMetaDataFile caching file:" << cacheFile.fileName(); + QFile newFile(metaDataFile); + newFile.copy(cacheFile.fileName()); + } +} + +void CompInfoParam::_parameterMajorVersionKnown(int wantedMajorVersion) +{ + if (_noJsonMetadata) { + if (_opaqueParameterMetaData) { + return; + } + + QString metaDataFile; + int majorVersion, minorVersion; + + // Load best parameter meta data set + metaDataFile = _parameterMetaDataFile(vehicle, vehicle->firmwareType(), wantedMajorVersion, majorVersion, minorVersion); + qCDebug(CompInfoParamLog) << "Loading meta data the old way file:major:minor" << metaDataFile << majorVersion << minorVersion; + _opaqueParameterMetaData = vehicle->firmwarePlugin()->_loadParameterMetaData(metaDataFile); + } +} + +void CompInfoParam::_clearPX4ParameterMetaData (void) +{ + if (_opaqueParameterMetaData) { + qCDebug(CompInfoParamLog) << "_clearPX4ParameterMetaData"; + _opaqueParameterMetaData->deleteLater(); + _opaqueParameterMetaData = nullptr; + } +} diff --git a/src/Vehicle/CompInfoParam.h b/src/Vehicle/CompInfoParam.h new file mode 100644 index 0000000000000000000000000000000000000000..c25eecab0b1f78cd6744246a16c6e49f02fe616c --- /dev/null +++ b/src/Vehicle/CompInfoParam.h @@ -0,0 +1,55 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "CompInfo.h" +#include "QGCMAVLink.h" +#include "QGCLoggingCategory.h" +#include "FactMetaData.h" + +#include + +class FactMetaData; +class Vehicle; +class FirmwarePlugin; + +Q_DECLARE_LOGGING_CATEGORY(CompInfoParamLog) + +class CompInfoParam : public CompInfo +{ + Q_OBJECT + +public: + CompInfoParam(uint8_t compId, Vehicle* vehicle, QObject* parent = nullptr); + + FactMetaData* factMetaDataForName(const QString& name, FactMetaData::ValueType_t type); + + // Overrides from CompInfo + void setJson(const QString& metadataJsonFileName, const QString& translationJsonFileName) override; + + // The following methods are used to support the old non-COMPONENT_INFORMATION based mechanism to get parameter meta data + bool _isParameterVolatile (const QString& name); + void _parameterMajorVersionKnown(int wantedMajorVersion); + void _clearPX4ParameterMetaData (void); + static void _cachePX4MetaDataFile(const QString& metaDataFile); + +private: + static FirmwarePlugin* _anyVehicleTypeFirmwarePlugin (MAV_AUTOPILOT firmwareType); + static QString _parameterMetaDataFile (Vehicle* vehicle, MAV_AUTOPILOT firmwareType, int wantedMajorVersion, int& majorVersion, int& minorVersion); + + bool _noJsonMetadata = true; + FactMetaData::NameToMetaDataMap_t _nameToMetaDataMap; + QObject* _opaqueParameterMetaData = nullptr; + + static const char* _cachedMetaDataFilePrefix; + + static const char* _jsonScopeKey; + static const char* _jsonParametersKey; +}; diff --git a/src/Vehicle/CompInfoVersion.cc b/src/Vehicle/CompInfoVersion.cc new file mode 100644 index 0000000000000000000000000000000000000000..d728fd9977c6383184ced2b7f1bf47a1d2808839 --- /dev/null +++ b/src/Vehicle/CompInfoVersion.cc @@ -0,0 +1,65 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#include "CompInfoVersion.h" +#include "JsonHelper.h" +#include "FactMetaData.h" +#include "FirmwarePlugin.h" +#include "FirmwarePluginManager.h" +#include "QGCApplication.h" + +#include +#include +#include + +QGC_LOGGING_CATEGORY(CompInfoVersionLog, "CompInfoVersionLog") + +const char* CompInfoVersion::_jsonSupportedCompMetadataTypesKey = "supportedCompMetadataTypes"; + +CompInfoVersion::CompInfoVersion(uint8_t compId, Vehicle* vehicle, QObject* parent) + : CompInfo (COMP_METADATA_TYPE_VERSION, compId, vehicle, parent) +{ + +} + +void CompInfoVersion::setJson(const QString& metadataJsonFileName, const QString& /*translationJsonFileName*/) +{ + if (metadataJsonFileName.isEmpty()) { + return; + } + + QString errorString; + QJsonDocument jsonDoc; + + if (!JsonHelper::isJsonFile(metadataJsonFileName, jsonDoc, errorString)) { + qCWarning(CompInfoVersionLog) << "Metadata json file open failed: compid:" << compId << errorString; + return; + } + QJsonObject jsonObj = jsonDoc.object(); + + QList keyInfoList = { + { JsonHelper::jsonVersionKey, QJsonValue::Double, true }, + { _jsonSupportedCompMetadataTypesKey, QJsonValue::Array, true }, + }; + if (!JsonHelper::validateKeys(jsonObj, keyInfoList, errorString)) { + qCWarning(CompInfoVersionLog) << "Metadata json validation failed: compid:" << compId << errorString; + return; + } + + int version = jsonObj[JsonHelper::jsonVersionKey].toInt(); + if (version != 1) { + qCWarning(CompInfoVersionLog) << "Metadata json unsupported version" << version; + return; + } + + QJsonArray rgSupportedTypes = jsonObj[_jsonSupportedCompMetadataTypesKey].toArray(); + for (const QJsonValue& typeValue: rgSupportedTypes) { + _supportedTypes.append(static_cast(typeValue.toInt())); + } +} diff --git a/src/Vehicle/CompInfoVersion.h b/src/Vehicle/CompInfoVersion.h new file mode 100644 index 0000000000000000000000000000000000000000..4408f2124d6fc0f49879ffcccce4a7fa791eceed --- /dev/null +++ b/src/Vehicle/CompInfoVersion.h @@ -0,0 +1,41 @@ +/**************************************************************************** + * + * (c) 2009-2020 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +#pragma once + +#include "CompInfo.h" +#include "QGCMAVLink.h" +#include "QGCLoggingCategory.h" +#include "FactMetaData.h" + +#include + +class FactMetaData; +class Vehicle; +class FirmwarePlugin; + +Q_DECLARE_LOGGING_CATEGORY(CompInfoVersionLog) + +class CompInfoVersion : public CompInfo +{ + Q_OBJECT + +public: + CompInfoVersion(uint8_t compId, Vehicle* vehicle, QObject* parent = nullptr); + + bool isMetaDataTypeSupported(COMP_METADATA_TYPE type) { return _supportedTypes.contains(type); } + + // Overrides from CompInfo + void setJson(const QString& metadataJsonFileName, const QString& translationJsonFileName) override; + +private: + QList _supportedTypes; + + static const char* _jsonSupportedCompMetadataTypesKey; +}; diff --git a/src/Vehicle/ComponentInformationManager.cc b/src/Vehicle/ComponentInformationManager.cc index f811313c3a86f50121f876fb9a6bbfaab6c8c62a..1e6634139e2e22565343d2acbb6032c6b9f09ed0 100644 --- a/src/Vehicle/ComponentInformationManager.cc +++ b/src/Vehicle/ComponentInformationManager.cc @@ -12,6 +12,8 @@ #include "FTPManager.h" #include "QGCZlib.h" #include "JsonHelper.h" +#include "CompInfoVersion.h" +#include "CompInfoParam.h" #include #include @@ -19,9 +21,6 @@ QGC_LOGGING_CATEGORY(ComponentInformationManagerLog, "ComponentInformationManagerLog") -const char* ComponentInformationManager::_jsonVersionKey = "version"; -const char* ComponentInformationManager::_jsonSupportedCompMetadataTypesKey = "supportedCompMetadataTypes"; - ComponentInformationManager::StateFn ComponentInformationManager::_rgStates[]= { ComponentInformationManager::_stateRequestCompInfoVersion, ComponentInformationManager::_stateRequestCompInfoParam, @@ -43,7 +42,8 @@ ComponentInformationManager::ComponentInformationManager(Vehicle* vehicle) : _vehicle (vehicle) , _requestTypeStateMachine (this) { - + _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_VERSION] = new CompInfoVersion (MAV_COMP_ID_AUTOPILOT1, vehicle, this); + _compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_PARAMETER] = new CompInfoParam (MAV_COMP_ID_AUTOPILOT1, vehicle, this); } int ComponentInformationManager::stateCount(void) const @@ -66,7 +66,7 @@ void ComponentInformationManager::requestAllComponentInformation(RequestAllCompl void ComponentInformationManager::_stateRequestCompInfoVersion(StateMachine* stateMachine) { ComponentInformationManager* compMgr = static_cast(stateMachine); - compMgr->_requestTypeStateMachine.request(COMP_METADATA_TYPE_VERSION); + compMgr->_requestTypeStateMachine.request(compMgr->_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_VERSION]); } void ComponentInformationManager::_stateRequestCompInfoComplete(void) @@ -79,9 +79,10 @@ void ComponentInformationManager::_stateRequestCompInfoParam(StateMachine* state ComponentInformationManager* compMgr = static_cast(stateMachine); if (compMgr->_isCompTypeSupported(COMP_METADATA_TYPE_PARAMETER)) { - compMgr->_requestTypeStateMachine.request(COMP_METADATA_TYPE_PARAMETER); + compMgr->_requestTypeStateMachine.request(compMgr->_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_PARAMETER]); } else { - + qCDebug(ComponentInformationManagerLog) << "_stateRequestCompInfoParam skipping, not supported"; + compMgr->advance(); } } @@ -93,39 +94,19 @@ void ComponentInformationManager::_stateRequestAllCompInfoComplete(StateMachine* compMgr->_requestAllCompleteFnData = nullptr; } -void ComponentInformationManager::_compInfoJsonAvailable(const QString& metadataJsonFileName, const QString& translationsJsonFileName) +bool ComponentInformationManager::_isCompTypeSupported(COMP_METADATA_TYPE type) { - qCDebug(ComponentInformationManagerLog) << "_compInfoJsonAvailable metadata:translation" << metadataJsonFileName << translationsJsonFileName; - - if (!metadataJsonFileName.isEmpty()) { - QString errorString; - QJsonDocument jsonDoc; - if (!JsonHelper::isJsonFile(metadataJsonFileName, jsonDoc, errorString)) { - qCWarning(ComponentInformationManagerLog) << "Version json file read failed" << errorString; - return; - } - QJsonObject jsonObj = jsonDoc.object(); - - if (currentState() == _stateRequestCompInfoVersion) { - QList keyInfoList = { - { _jsonVersionKey, QJsonValue::Double, true }, - { _jsonSupportedCompMetadataTypesKey, QJsonValue::Array, true }, - }; - if (!JsonHelper::validateKeys(jsonObj, keyInfoList, errorString)) { - qCWarning(ComponentInformationManagerLog) << "Version json validation failed:" << errorString; - return; - } + return qobject_cast(_compInfoMap[MAV_COMP_ID_AUTOPILOT1][COMP_METADATA_TYPE_VERSION])->isMetaDataTypeSupported(type); +} - for (const QJsonValue& idValue: jsonObj[_jsonSupportedCompMetadataTypesKey].toArray()) { - _supportedMetaDataTypes.append(static_cast(idValue.toInt())); - } - } - } +CompInfoParam* ComponentInformationManager::compInfoParam(uint8_t compId) +{ + return _compInfoMap.contains(compId) && _compInfoMap[compId].contains(COMP_METADATA_TYPE_PARAMETER) ? qobject_cast(_compInfoMap[compId][COMP_METADATA_TYPE_PARAMETER]) : nullptr; } -bool ComponentInformationManager::_isCompTypeSupported(COMP_METADATA_TYPE type) +CompInfoVersion* ComponentInformationManager::compInfoVersion(uint8_t compId) { - return _supportedMetaDataTypes.contains(type); + return _compInfoMap.contains(compId) && _compInfoMap[compId].contains(COMP_METADATA_TYPE_VERSION) ? qobject_cast(_compInfoMap[compId][COMP_METADATA_TYPE_VERSION]) : nullptr; } RequestMetaDataTypeStateMachine::RequestMetaDataTypeStateMachine(ComponentInformationManager* compMgr) @@ -134,11 +115,10 @@ RequestMetaDataTypeStateMachine::RequestMetaDataTypeStateMachine(ComponentInform } -void RequestMetaDataTypeStateMachine::request(COMP_METADATA_TYPE type) +void RequestMetaDataTypeStateMachine::request(CompInfo* compInfo) { - _compInfoAvailable = false; - _type = type; - _stateIndex = -1; + _compInfo = compInfo; + _stateIndex = -1; _jsonMetadataFileName.clear(); _jsonTranslationFileName.clear(); @@ -162,19 +142,7 @@ void RequestMetaDataTypeStateMachine::statesCompleted(void) const QString RequestMetaDataTypeStateMachine::typeToString(void) { - return _type == COMP_METADATA_TYPE_VERSION ? "COMP_METADATA_TYPE_VERSION" : "COMP_METADATA_TYPE_PARAM"; -} - -void RequestMetaDataTypeStateMachine::handleComponentInformation(const mavlink_message_t& message) -{ - mavlink_component_information_t componentInformation; - mavlink_msg_component_information_decode(&message, &componentInformation); - - _compInfo.metadataUID = componentInformation.metadata_uid; - _compInfo.metadataURI = componentInformation.metadata_uri; - _compInfo.translationUID = componentInformation.translation_uid; - _compInfo.translationURI = componentInformation.translation_uri; - _compInfoAvailable = true; + return _compInfo->type == COMP_METADATA_TYPE_VERSION ? "COMP_METADATA_TYPE_VERSION" : "COMP_METADATA_TYPE_PARAM"; } static void _requestMessageResultHandler(void* resultHandlerData, MAV_RESULT result, Vehicle::RequestMessageResultHandlerFailureCode_t failureCode, const mavlink_message_t &message) @@ -182,7 +150,7 @@ static void _requestMessageResultHandler(void* resultHandlerData, MAV_RESULT res RequestMetaDataTypeStateMachine* requestMachine = static_cast(resultHandlerData); if (result == MAV_RESULT_ACCEPTED) { - requestMachine->handleComponentInformation(message); + requestMachine->compInfo()->setMessage(message); } else { switch (failureCode) { case Vehicle::RequestMessageFailureCommandError: @@ -217,7 +185,7 @@ void RequestMetaDataTypeStateMachine::_stateRequestCompInfo(StateMachine* stateM stateMachine, MAV_COMP_ID_AUTOPILOT1, MAVLINK_MSG_ID_COMPONENT_INFORMATION, - requestMachine->_type); + requestMachine->_compInfo->type); } } @@ -260,7 +228,7 @@ void RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson(const QSt jsonTranslationFileName = _downloadCompleteJsonWorker(fileName, "translation.json"); } - _compMgr->_compInfoJsonAvailable(_jsonMetadataFileName, jsonTranslationFileName); + _compInfo->setJson(_jsonMetadataFileName, jsonTranslationFileName); advance(); } @@ -268,22 +236,20 @@ void RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson(const QSt void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* stateMachine) { RequestMetaDataTypeStateMachine* requestMachine = static_cast(stateMachine); - Vehicle* vehicle = requestMachine->_compMgr->vehicle(); - FTPManager* ftpManager = vehicle->ftpManager(); + CompInfo* compInfo = requestMachine->compInfo(); + FTPManager* ftpManager = compInfo->vehicle->ftpManager(); - if (requestMachine->_compInfoAvailable) { - ComponentInformation_t& compInfo = requestMachine->_compInfo; - - qCDebug(ComponentInformationManagerLog) << "Downloading metadata json" << compInfo.metadataURI; - if (_uriIsFTP(compInfo.metadataURI)) { + if (compInfo->available) { + qCDebug(ComponentInformationManagerLog) << "Downloading metadata json" << compInfo->uriMetaData; + if (_uriIsFTP(compInfo->uriMetaData)) { connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_downloadCompleteMetaDataJson); - ftpManager->download(compInfo.metadataURI, QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + ftpManager->download(compInfo->uriMetaData, QStandardPaths::writableLocation(QStandardPaths::TempLocation)); } else { // FIXME: NYI qCDebug(ComponentInformationManagerLog) << "Skipping metadata json download. http download NYI"; } } else { - qCDebug(ComponentInformationManagerLog) << "Skipping metadata json download. Component informatiom not available"; + qCDebug(ComponentInformationManagerLog) << "Skipping metadata json download. Component information not available"; requestMachine->advance(); } } @@ -291,26 +257,25 @@ void RequestMetaDataTypeStateMachine::_stateRequestMetaDataJson(StateMachine* st void RequestMetaDataTypeStateMachine::_stateRequestTranslationJson(StateMachine* stateMachine) { RequestMetaDataTypeStateMachine* requestMachine = static_cast(stateMachine); - Vehicle* vehicle = requestMachine->_compMgr->vehicle(); - FTPManager* ftpManager = vehicle->ftpManager(); + CompInfo* compInfo = requestMachine->compInfo(); + FTPManager* ftpManager = compInfo->vehicle->ftpManager(); - if (requestMachine->_compInfoAvailable) { - ComponentInformation_t& compInfo = requestMachine->_compInfo; - if (compInfo.translationURI.isEmpty()) { + if (compInfo->available) { + if (compInfo->uriTranslation.isEmpty()) { qCDebug(ComponentInformationManagerLog) << "Skipping translation json download. No translation json specified"; requestMachine->advance(); } else { - qCDebug(ComponentInformationManagerLog) << "Downloading translation json" << compInfo.translationURI; - if (_uriIsFTP(compInfo.translationURI)) { + qCDebug(ComponentInformationManagerLog) << "Downloading translation json" << compInfo->uriTranslation; + if (_uriIsFTP(compInfo->uriTranslation)) { connect(ftpManager, &FTPManager::downloadComplete, requestMachine, &RequestMetaDataTypeStateMachine::_downloadCompleteTranslationJson); - ftpManager->download(compInfo.metadataURI, QStandardPaths::writableLocation(QStandardPaths::TempLocation)); + ftpManager->download(compInfo->uriTranslation, QStandardPaths::writableLocation(QStandardPaths::TempLocation)); } else { // FIXME: NYI qCDebug(ComponentInformationManagerLog) << "Skipping translation json download. http download NYI"; } } } else { - qCDebug(ComponentInformationManagerLog) << "Skipping translation json download. Component informatiom not available"; + qCDebug(ComponentInformationManagerLog) << "Skipping translation json download. Component information not available"; requestMachine->advance(); } } @@ -318,8 +283,9 @@ void RequestMetaDataTypeStateMachine::_stateRequestTranslationJson(StateMachine* void RequestMetaDataTypeStateMachine::_stateRequestComplete(StateMachine* stateMachine) { RequestMetaDataTypeStateMachine* requestMachine = static_cast(stateMachine); + CompInfo* compInfo = requestMachine->compInfo(); - requestMachine->compMgr()->_compInfoJsonAvailable(requestMachine->_jsonMetadataFileName, requestMachine->_jsonTranslationFileName); + compInfo->setJson(requestMachine->_jsonMetadataFileName, requestMachine->_jsonTranslationFileName); requestMachine->advance(); } diff --git a/src/Vehicle/ComponentInformationManager.h b/src/Vehicle/ComponentInformationManager.h index 5112ddbf67deeae55a0d99546b33683af21be5aa..2220450ff38183f5ae69fe825a97a1a0c6d28354 100644 --- a/src/Vehicle/ComponentInformationManager.h +++ b/src/Vehicle/ComponentInformationManager.h @@ -17,13 +17,9 @@ Q_DECLARE_LOGGING_CATEGORY(ComponentInformationManagerLog) class Vehicle; class ComponentInformationManager; - -typedef struct { - uint32_t metadataUID; - QString metadataURI; - uint32_t translationUID; - QString translationURI; -} ComponentInformation_t; +class CompInfo; +class CompInfoParam; +class CompInfoVersion; class RequestMetaDataTypeStateMachine : public StateMachine { @@ -32,10 +28,9 @@ class RequestMetaDataTypeStateMachine : public StateMachine public: RequestMetaDataTypeStateMachine(ComponentInformationManager* compMgr); - void request (COMP_METADATA_TYPE type); - QString typeToString (void); - ComponentInformationManager* compMgr (void) { return _compMgr; } - void handleComponentInformation (const mavlink_message_t& message); + void request (CompInfo* compInfo); + QString typeToString(void); + CompInfo* compInfo (void) { return _compInfo; } // Overrides from StateMachine int stateCount (void) const final; @@ -55,15 +50,13 @@ private: static bool _uriIsFTP (const QString& uri); - ComponentInformationManager* _compMgr; - COMP_METADATA_TYPE _type = COMP_METADATA_TYPE_VERSION; - bool _compInfoAvailable = false; - ComponentInformation_t _compInfo; + ComponentInformationManager* _compMgr = nullptr; + CompInfo* _compInfo = nullptr; QString _jsonMetadataFileName; QString _jsonTranslationFileName; - static StateFn _rgStates[]; - static int _cStates; + static StateFn _rgStates[]; + static int _cStates; }; class ComponentInformationManager : public StateMachine @@ -75,8 +68,10 @@ public: typedef void (*RequestAllCompleteFn)(void* requestAllCompleteFnData); - void requestAllComponentInformation (RequestAllCompleteFn requestAllCompletFn, void * requestAllCompleteFnData); - Vehicle* vehicle (void) { return _vehicle; } + void requestAllComponentInformation (RequestAllCompleteFn requestAllCompletFn, void * requestAllCompleteFnData); + Vehicle* vehicle (void) { return _vehicle; } + CompInfoParam* compInfoParam (uint8_t compId); + CompInfoVersion* compInfoVersion (uint8_t compId); // Overrides from StateMachine int stateCount (void) const final; @@ -84,7 +79,6 @@ public: private: void _stateRequestCompInfoComplete (void); - void _compInfoJsonAvailable (const QString& metadataJsonFileName, const QString& translationsJsonFileName); bool _isCompTypeSupported (COMP_METADATA_TYPE type); static void _stateRequestCompInfoVersion (StateMachine* stateMachine); @@ -93,19 +87,13 @@ private: Vehicle* _vehicle = nullptr; RequestMetaDataTypeStateMachine _requestTypeStateMachine; - bool _versionCompInfoAvailable = false; - ComponentInformation_t _versionCompInfo; - bool _paramCompInfoAvailable = false; - ComponentInformation_t _parameterCompInfo; - QList _supportedMetaDataTypes; RequestAllCompleteFn _requestAllCompleteFn = nullptr; void* _requestAllCompleteFnData = nullptr; + QMap> _compInfoMap; + static StateFn _rgStates[]; static int _cStates; - static const char* _jsonVersionKey; - static const char* _jsonSupportedCompMetadataTypesKey; - friend class RequestMetaDataTypeStateMachine; }; diff --git a/src/Vehicle/Vehicle.cc b/src/Vehicle/Vehicle.cc index 2a7d1b493fbdd53b16463c6b2d54f507dd17acf6..31a06f31411b9262f60777869bbeb909ec6f5fa1 100644 --- a/src/Vehicle/Vehicle.cc +++ b/src/Vehicle/Vehicle.cc @@ -462,13 +462,13 @@ void Vehicle::_commonInit() connect(_missionManager, &MissionManager::sendComplete, _trajectoryPoints, &TrajectoryPoints::clear); connect(_missionManager, &MissionManager::newMissionItemsAvailable, _trajectoryPoints, &TrajectoryPoints::clear); - _parameterManager = new ParameterManager(this); - connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); - _componentInformationManager = new ComponentInformationManager (this); _initialConnectStateMachine = new InitialConnectStateMachine (this); _ftpManager = new FTPManager (this); + _parameterManager = new ParameterManager(this); + connect(_parameterManager, &ParameterManager::parametersReadyChanged, this, &Vehicle::_parametersReady); + _objectAvoidance = new VehicleObjectAvoidance(this, this); // GeoFenceManager needs to access ParameterManager so make sure to create after diff --git a/src/Vehicle/Vehicle.h b/src/Vehicle/Vehicle.h index 1229c67daacf0d276b2a18e5e600e1775e67ca5d..94fea7d8eee09e8c614571c5e0eded37c7cb8218 100644 --- a/src/Vehicle/Vehicle.h +++ b/src/Vehicle/Vehicle.h @@ -1007,9 +1007,10 @@ public: void setConnectionLostEnabled(bool connectionLostEnabled); - ParameterManager* parameterManager () { return _parameterManager; } - ParameterManager* parameterManager () const { return _parameterManager; } - FTPManager* ftpManager () { return _ftpManager; } + ParameterManager* parameterManager () { return _parameterManager; } + ParameterManager* parameterManager () const { return _parameterManager; } + FTPManager* ftpManager () { return _ftpManager; } + ComponentInformationManager* compInfoManager () { return _componentInformationManager; } VehicleObjectAvoidance* objectAvoidance () { return _objectAvoidance; } static const int cMaxRcChannels = 18; diff --git a/src/VehicleSetup/FirmwareImage.cc b/src/VehicleSetup/FirmwareImage.cc index e6bd109bbb3afeace0c1134e69b5923a1f64cb75..33c00a4a370be3fa327d0280680cd2bda8e2118d 100644 --- a/src/VehicleSetup/FirmwareImage.cc +++ b/src/VehicleSetup/FirmwareImage.cc @@ -7,18 +7,13 @@ * ****************************************************************************/ - -/// @file -/// @brief Support for Intel Hex firmware file -/// @author Don Gagne - #include "FirmwareImage.h" #include "QGCLoggingCategory.h" #include "JsonHelper.h" #include "QGCMAVLink.h" #include "QGCApplication.h" #include "FirmwarePlugin.h" -#include "ParameterManager.h" +#include "CompInfoParam.h" #include "Bootloader.h" #include @@ -292,7 +287,7 @@ bool FirmwareImage::_px4Load(const QString& imageFilename) } // Cache this file with the system - ParameterManager::cacheMetaDataFile(parameterFilename, firmwareType); + CompInfoParam::_cachePX4MetaDataFile(parameterFilename); } // Decompress the airframe xml and save to file diff --git a/src/comm/MockLink.Parameter.MetaData.json b/src/comm/MockLink.Parameter.MetaData.json index 6ee37e644a9d983aa93add735bc5efc857f957c1..ea73339c174df6d8af709beff7bb9996ce31ce99 100644 --- a/src/comm/MockLink.Parameter.MetaData.json +++ b/src/comm/MockLink.Parameter.MetaData.json @@ -12,7 +12,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 5 }, @@ -25,7 +25,7 @@ "longDescription": "Sideslip measurement noise of the internal wind estimator(s) of the airspeed selector.", "units": "rad", "defaultValue": 0.3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -38,7 +38,7 @@ "longDescription": "If set to true then the data comming from the airspeed sensors is checked for validity. Only applied if ASPD_PRIMARY > 0.", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -61,7 +61,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -73,7 +73,7 @@ "shortDescription": "Airspeed failsafe consistency threshold (Experimental)", "longDescription": "This specifies the minimum airspeed test ratio required to trigger a failsafe. Larger values make the check less sensitive, smaller values make it more sensitive. Start with a value of 1.0 when tuning. When tas_test_ratio is > 1.0 it indicates the inconsistency between predicted and measured airspeed is large enough to cause the navigation EKF to reject airspeed measurements. The time required to detect a fault when the threshold is exceeded depends on the size of the exceedance and is controlled by the ASPD_FS_INTEG parameter.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.5, "maxValue": 3 }, @@ -86,7 +86,7 @@ "longDescription": "This sets the time integral of airspeed test ratio exceedance above ASPD_FS_INNOV required to trigger a failsafe. For example if ASPD_FS_INNOV is 1 and estimator_status.tas_test_ratio is 2.0, then the exceedance is 1.0 and the integral will rise at a rate of 1.0/second. A negative value disables the check. Larger positive values make the check less sensitive, smaller positive values make it more sensitive.", "units": "s", "defaultValue": -1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 30 }, @@ -99,7 +99,7 @@ "longDescription": "Delay before stopping use of airspeed sensor if checks indicate sensor is bad.", "units": "s", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 10 }, @@ -112,7 +112,7 @@ "longDescription": "Delay before switching back to using airspeed sensor if checks indicate sensor is good.", "units": "s", "defaultValue": 100, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 10, "maxValue": 1000 }, @@ -146,7 +146,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -158,7 +158,7 @@ "shortDescription": "Airspeed scale (scale from IAS to CAS/EAS)", "longDescription": "Scale can either be entered manually, or estimated in-flight by setting ASPD_SCALE_EST to 1.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.5, "maxValue": 1.5 }, @@ -170,7 +170,7 @@ "shortDescription": "Automatic airspeed scale estimation on", "longDescription": "Turns the automatic airspeed scale (scale from IAS to CAS/EAS) on or off. It is recommended to fly level altitude while performing the estimation. Set to 1 to start estimation (best when already flying). Set to 0 to end scale estimation. The estimated scale is then saved using the ASPD_SCALE parameter.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -183,7 +183,7 @@ "longDescription": "Airspeed scale process noise of the internal wind estimator(s) of the airspeed selector.", "units": "1/s", "defaultValue": 0.0001, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 0.1 }, @@ -196,7 +196,7 @@ "longDescription": "This is the minimum indicated airspeed at which the wing can produce 1g of lift. It is used by the airspeed sensor fault detection and failsafe calculation to detect a significant airspeed low measurement error condition and should be set based on flight test for reliable operation.", "units": "m/s", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -209,7 +209,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 5 }, @@ -222,7 +222,7 @@ "longDescription": "True airspeed measurement noise of the internal wind estimator(s) of the airspeed selector.", "units": "m/s", "defaultValue": 1.4, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 4 }, @@ -235,7 +235,7 @@ "longDescription": "Wind process noise of the internal wind estimator(s) of the airspeed selector.", "units": "m/s/s", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -246,7 +246,7 @@ "category": "Standard", "shortDescription": "Acceleration compensation based on GPS velocity", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -258,7 +258,7 @@ "shortDescription": "Gyro bias limit", "units": "rad/s", "defaultValue": 0.05, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -283,7 +283,7 @@ "description": "Motion Capture" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -296,7 +296,7 @@ "longDescription": "This parameter is not used in normal operation, as the declination is looked up based on the GPS coordinates of the vehicle.", "units": "deg", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -307,7 +307,7 @@ "category": "Standard", "shortDescription": "Automatic GPS based declination compensation", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -318,7 +318,7 @@ "category": "Standard", "shortDescription": "Complimentary filter accelerometer weight", "defaultValue": 0.2, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -329,7 +329,7 @@ "category": "Standard", "shortDescription": "Complimentary filter external heading weight", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -340,7 +340,7 @@ "category": "Standard", "shortDescription": "Complimentary filter gyroscope bias weight", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -352,7 +352,7 @@ "shortDescription": "Complimentary filter magnetometer weight", "longDescription": "Set to 0 to avoid using the magnetometer.", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -365,7 +365,7 @@ "longDescription": "The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -380,7 +380,7 @@ "defaultValue": -1, "increment": 50, "rebootRequired": true, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -1, "maxValue": 100000 }, @@ -393,7 +393,7 @@ "longDescription": "This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -468,7 +468,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -483,7 +483,7 @@ "defaultValue": -1, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -1, "maxValue": 0.2 }, @@ -510,7 +510,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -523,7 +523,7 @@ "longDescription": "This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -538,7 +538,7 @@ "defaultValue": 4.05, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -551,7 +551,7 @@ "longDescription": "This is the divider from battery 1 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -566,7 +566,7 @@ "defaultValue": 3.5, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -581,7 +581,7 @@ "defaultValue": 0.3, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.07, "maxValue": 0.5 }, @@ -594,7 +594,7 @@ "longDescription": "The voltage seen by the ADC multiplied by this factor will determine the battery current. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -609,7 +609,7 @@ "defaultValue": -1, "increment": 50, "rebootRequired": true, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -1, "maxValue": 100000 }, @@ -622,7 +622,7 @@ "longDescription": "This parameter specifies the ADC channel used to monitor current of main power battery. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -697,7 +697,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -712,7 +712,7 @@ "defaultValue": -1, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -1, "maxValue": 0.2 }, @@ -739,7 +739,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -752,7 +752,7 @@ "longDescription": "This parameter specifies the ADC channel used to monitor voltage of main power battery. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -767,7 +767,7 @@ "defaultValue": 4.05, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -780,7 +780,7 @@ "longDescription": "This is the divider from battery 2 voltage to ADC voltage. If using e.g. Mauch power modules the value from the datasheet can be applied straight here. A value of -1 means to use the board default.", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -795,7 +795,7 @@ "defaultValue": 3.5, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -810,7 +810,7 @@ "defaultValue": 0.3, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.07, "maxValue": 0.5 }, @@ -821,7 +821,7 @@ "category": "Standard", "shortDescription": "This parameter is deprecated. Please use BAT1_ADC_CHANNEL", "defaultValue": -1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -832,7 +832,7 @@ "category": "Standard", "shortDescription": "This parameter is deprecated. Please use BAT1_A_PER_V", "defaultValue": -1, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -847,7 +847,7 @@ "defaultValue": -1, "increment": 50, "rebootRequired": true, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -1, "maxValue": 100000 }, @@ -862,7 +862,7 @@ "defaultValue": 0.07, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.05, "maxValue": 0.25 }, @@ -874,7 +874,7 @@ "shortDescription": "Capacity/current multiplier for high-current capable SMBUS battery", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -889,7 +889,7 @@ "defaultValue": 0.05, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.03, "maxValue": 0.1 }, @@ -904,7 +904,7 @@ "defaultValue": 0.15, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.12, "maxValue": 0.5 }, @@ -984,7 +984,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -998,7 +998,7 @@ "units": "Ohms", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 0.2 }, @@ -1020,7 +1020,7 @@ "description": "External" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -1035,7 +1035,7 @@ "defaultValue": 4.05, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1046,7 +1046,7 @@ "category": "Standard", "shortDescription": "This parameter is deprecated. Please use BAT1_V_DIV", "defaultValue": -1, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1061,7 +1061,7 @@ "defaultValue": 3.5, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1076,7 +1076,7 @@ "defaultValue": 0.3, "increment": 0.01, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.07, "maxValue": 0.5 }, @@ -1088,7 +1088,7 @@ "shortDescription": "Offset in volt as seen by the ADC input of the current sensor", "longDescription": "This offset will be subtracted before calculating the battery current based on the voltage.", "defaultValue": 0, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1099,7 +1099,7 @@ "category": "System", "shortDescription": "Accelerometer 0 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1110,7 +1110,7 @@ "category": "System", "shortDescription": "ID of the Accelerometer that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1121,7 +1121,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1132,7 +1132,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1143,7 +1143,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1154,7 +1154,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1165,7 +1165,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1176,7 +1176,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1187,7 +1187,7 @@ "category": "System", "shortDescription": "Accelerometer 1 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1198,7 +1198,7 @@ "category": "System", "shortDescription": "ID of the Accelerometer that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1209,7 +1209,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1220,7 +1220,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1231,7 +1231,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1242,7 +1242,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1253,7 +1253,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1264,7 +1264,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1275,7 +1275,7 @@ "category": "System", "shortDescription": "Accelerometer 2 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1286,7 +1286,7 @@ "category": "System", "shortDescription": "ID of the Accelerometer that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1297,7 +1297,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1308,7 +1308,7 @@ "category": "System", "shortDescription": "Accelerometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1319,7 +1319,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1330,7 +1330,7 @@ "category": "System", "shortDescription": "Accelerometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1341,7 +1341,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1352,7 +1352,7 @@ "category": "System", "shortDescription": "Accelerometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1363,7 +1363,7 @@ "category": "System", "shortDescription": "Primary accel ID", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1389,7 +1389,7 @@ "description": "Tube Pressure Drop" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1401,7 +1401,7 @@ "shortDescription": "Airspeed sensor tube diameter. Only used for the Tube Pressure Drop Compensation", "units": "millimeter", "defaultValue": 1.5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 100 }, @@ -1414,7 +1414,7 @@ "longDescription": "See the CAL_AIR_CMODEL explanation on how this parameter should be set.", "units": "meter", "defaultValue": 0.2, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 2 }, @@ -1425,7 +1425,7 @@ "category": "System", "shortDescription": "Gyro 0 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1436,7 +1436,7 @@ "category": "System", "shortDescription": "ID of the Gyro that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1447,7 +1447,7 @@ "category": "System", "shortDescription": "Gyro X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1458,7 +1458,7 @@ "category": "System", "shortDescription": "Gyro Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1469,7 +1469,7 @@ "category": "System", "shortDescription": "Gyro Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1480,7 +1480,7 @@ "category": "System", "shortDescription": "Gyro 1 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1491,7 +1491,7 @@ "category": "System", "shortDescription": "ID of the Gyro that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1502,7 +1502,7 @@ "category": "System", "shortDescription": "Gyro X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1513,7 +1513,7 @@ "category": "System", "shortDescription": "Gyro Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1524,7 +1524,7 @@ "category": "System", "shortDescription": "Gyro Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1535,7 +1535,7 @@ "category": "System", "shortDescription": "Gyro 2 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1546,7 +1546,7 @@ "category": "System", "shortDescription": "ID of the Gyro that the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1557,7 +1557,7 @@ "category": "System", "shortDescription": "Gyro X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1568,7 +1568,7 @@ "category": "System", "shortDescription": "Gyro Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1579,7 +1579,7 @@ "category": "System", "shortDescription": "Gyro Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1590,7 +1590,7 @@ "category": "System", "shortDescription": "Primary gyro ID", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1601,7 +1601,7 @@ "category": "System", "shortDescription": "Mag 0 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1612,7 +1612,7 @@ "category": "System", "shortDescription": "ID of Magnetometer the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1735,7 +1735,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 30 }, @@ -1746,7 +1746,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1757,7 +1757,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1768,7 +1768,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1779,7 +1779,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1790,7 +1790,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1801,7 +1801,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1812,7 +1812,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1823,7 +1823,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1834,7 +1834,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -1845,7 +1845,7 @@ "category": "System", "shortDescription": "Mag 1 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1856,7 +1856,7 @@ "category": "System", "shortDescription": "ID of Magnetometer the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -1979,7 +1979,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 30 }, @@ -1990,7 +1990,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2001,7 +2001,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2012,7 +2012,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2023,7 +2023,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2034,7 +2034,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2045,7 +2045,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2056,7 +2056,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2067,7 +2067,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2078,7 +2078,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2089,7 +2089,7 @@ "category": "System", "shortDescription": "Mag 2 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2100,7 +2100,7 @@ "category": "System", "shortDescription": "ID of Magnetometer the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2223,7 +2223,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 30 }, @@ -2234,7 +2234,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2245,7 +2245,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2256,7 +2256,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2267,7 +2267,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2278,7 +2278,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2289,7 +2289,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2300,7 +2300,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2311,7 +2311,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2322,7 +2322,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2333,7 +2333,7 @@ "category": "System", "shortDescription": "Mag 3 enabled", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2344,7 +2344,7 @@ "category": "System", "shortDescription": "ID of Magnetometer the calibration is for", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2467,7 +2467,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 30 }, @@ -2478,7 +2478,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between X component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2489,7 +2489,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2500,7 +2500,7 @@ "category": "System", "shortDescription": "Magnetometer X-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2511,7 +2511,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Y component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2522,7 +2522,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2533,7 +2533,7 @@ "category": "System", "shortDescription": "Magnetometer Y-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2544,7 +2544,7 @@ "category": "System", "shortDescription": "Coefficient describing linear relationship between Z component of magnetometer in body frame axis and either current or throttle depending on value of CAL_MAG_COMP_TYP Unit for throttle-based compensation is [G] and for current-based compensation [G/kA]", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2555,7 +2555,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis offset", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2566,7 +2566,7 @@ "category": "System", "shortDescription": "Magnetometer Z-axis scaling factor", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -2595,7 +2595,7 @@ "description": "Current-based compensation (battery_status instance 1)" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2606,7 +2606,7 @@ "category": "System", "shortDescription": "Primary mag ID", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2632,7 +2632,7 @@ "description": "Six side calibration" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 34, "maxValue": 63 }, @@ -2645,7 +2645,7 @@ "longDescription": "This parameter sets the delay between image integration start and strobe firing", "units": "ms", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 100 }, @@ -2667,7 +2667,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2680,7 +2680,7 @@ "longDescription": "Enables camera capture feedback", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2707,7 +2707,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2718,7 +2718,7 @@ "category": "Standard", "shortDescription": "UAVCAN CAN bus bitrate", "defaultValue": 1e+06, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 20000, "maxValue": 1e+06 }, @@ -2730,7 +2730,7 @@ "shortDescription": "UAVCAN Node ID", "longDescription": "Read the specs at http://uavcan.org to learn more about Node ID.", "defaultValue": 120, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 125 }, @@ -2743,7 +2743,7 @@ "longDescription": "Setting this parameter to 162128 will disable the check for an airspeed sensor. The sensor driver will not be started and it cannot be calibrated. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 162128 }, @@ -2756,7 +2756,7 @@ "longDescription": "Setting this parameter to 782097 will disable the buzzer audio notification. Setting this parameter to 782090 will disable the startup tune, while keeping all others enabled.", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 782097 }, @@ -2769,7 +2769,7 @@ "longDescription": "Setting this parameter to 284953 will disable the engine failure detection. If the aircraft is in engine failure mode the engine failure flag will be set to healthy WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 284953, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 284953 }, @@ -2782,7 +2782,7 @@ "longDescription": "Setting this parameter to 121212 will disable the flight termination action if triggered by the FailureDetector logic or if FMU is lost. This circuit breaker does not affect the RC loss, data link loss, geofence, and takeoff failure detection safety logic.", "defaultValue": 121212, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 121212 }, @@ -2795,7 +2795,7 @@ "longDescription": "Setting this parameter to 22027 will disable IO safety. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 22027 }, @@ -2808,7 +2808,7 @@ "longDescription": "Setting this parameter to 140253 will disable the rate controller uORB publication. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 140253 }, @@ -2821,7 +2821,7 @@ "longDescription": "Setting this parameter to 894281 will disable the power valid checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 894281 }, @@ -2834,7 +2834,7 @@ "longDescription": "Setting this parameter to 197848 will disable the USB connected checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 197848 }, @@ -2847,7 +2847,7 @@ "longDescription": "Setting this parameter to 201607 will disable the position and velocity accuracy checks in the commander. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 201607 }, @@ -2860,7 +2860,7 @@ "longDescription": "Setting this parameter to 159753 will enable arming in fixed-wing mode for VTOLs. WARNING: ENABLING THIS CIRCUIT BREAKER IS AT OWN RISK", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 159753 }, @@ -2872,7 +2872,7 @@ "shortDescription": "Arm authorization parameters, this uint32_t will be split between starting from the LSB: - 8bits to authorizer system id - 16bits to authentication method parameter, this will be used to store a timeout for the first 2 methods but can be used to another parameter for other new authentication methods. - 7bits to authentication method - one arm = 0 - two step arm = 1 * the MSB bit is not used to avoid problems in the conversion between int and uint", "longDescription": "Default value: (10 << 0 | 1000 << 8 | 0 << 24) = 256010 - authorizer system id = 10 - authentication method parameter = 10000msec of timeout - authentication method = during arm", "defaultValue": 256010, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2884,7 +2884,7 @@ "shortDescription": "Require arm authorization to arm", "longDescription": "The default allows to arm the vehicle without a arm authorization.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2896,7 +2896,7 @@ "shortDescription": "Require all the ESCs to be detected to arm", "longDescription": "This param is specific for ESCs reporting status. Normal ESCs configurations are not affected by the change of this param.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -2909,7 +2909,7 @@ "units": "m/s", "defaultValue": 0.0022, "increment": 0.0001, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.001, "maxValue": 0.01 }, @@ -2922,7 +2922,7 @@ "units": "rad", "defaultValue": 0.0011, "increment": 0.0001, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.0001, "maxValue": 0.0017 }, @@ -2934,7 +2934,7 @@ "shortDescription": "Maximum EKF height innovation test ratio that will allow arming", "defaultValue": 1, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -2946,7 +2946,7 @@ "shortDescription": "Maximum EKF position innovation test ratio that will allow arming", "defaultValue": 0.5, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -2958,7 +2958,7 @@ "shortDescription": "Maximum EKF velocity innovation test ratio that will allow arming", "defaultValue": 0.5, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -2970,7 +2970,7 @@ "shortDescription": "Maximum EKF yaw innovation test ratio that will allow arming", "defaultValue": 0.5, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -2983,7 +2983,7 @@ "units": "m/s/s", "defaultValue": 0.7, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -2996,7 +2996,7 @@ "units": "rad/s", "defaultValue": 0.25, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.02, "maxValue": 0.3 }, @@ -3008,7 +3008,7 @@ "shortDescription": "Maximum magnetic field inconsistency between units that will allow arming Set -1 to disable the check", "units": "deg", "defaultValue": 30, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 3, "maxValue": 180 }, @@ -3020,7 +3020,7 @@ "shortDescription": "Enable mag strength preflight check", "longDescription": "Deny arming if the estimator detects a strong magnetic disturbance (check enabled by EKF2_MAG_CHECK)", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3032,7 +3032,7 @@ "shortDescription": "Require valid mission to arm", "longDescription": "The default allows to arm the vehicle without a valid mission.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3044,7 +3044,7 @@ "shortDescription": "Arm switch is only a button", "longDescription": "The default uses the arm switch as real switch. If parameter set button gets handled like stick arming.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3056,7 +3056,7 @@ "shortDescription": "Allow arming without GPS", "longDescription": "The default allows to arm the vehicle without GPS signal.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3070,7 +3070,7 @@ "units": "%", "defaultValue": 90, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -1, "maxValue": 100 }, @@ -3083,7 +3083,7 @@ "longDescription": "A non-zero, positive value specifies the time-out period in seconds after which the vehicle will be automatically disarmed in case a landing situation has been detected during this period. A zero or negative value means that automatic disarming triggered by landing detection is disabled.", "units": "s", "defaultValue": 2, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -3096,7 +3096,7 @@ "longDescription": "A non-zero, positive value specifies the time after arming, in seconds, within which the vehicle must take off (after which it will automatically disarm). A zero or negative value means that automatic disarming triggered by a pre-takeoff timeout is disabled.", "units": "s", "defaultValue": 10, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -3110,7 +3110,7 @@ "units": "s", "defaultValue": 10, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 5, "maxValue": 300 }, @@ -3124,7 +3124,7 @@ "units": "A/%", "defaultValue": 5, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 50 }, @@ -3138,7 +3138,7 @@ "units": "norm", "defaultValue": 0.5, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -3152,7 +3152,7 @@ "units": "s", "defaultValue": 10, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 60 }, @@ -3165,7 +3165,7 @@ "longDescription": "This number is incremented automatically after every flight on disarming in order to remember the next flight UUID. The first flight is 0.", "defaultValue": 0, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -3235,7 +3235,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3305,7 +3305,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3375,7 +3375,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3445,7 +3445,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3515,7 +3515,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3585,7 +3585,7 @@ "description": "Follow Me" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3615,7 +3615,7 @@ "description": "Developer" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3628,7 +3628,7 @@ "longDescription": "After this amount of seconds without datalink the data link lost mode triggers", "units": "s", "defaultValue": 120, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 60, "maxValue": 3600 }, @@ -3641,7 +3641,7 @@ "longDescription": "After a data link loss: after this this amount of seconds with a healthy datalink the 'datalink loss' flag is set back to false", "units": "s", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 60 }, @@ -3655,7 +3655,7 @@ "units": "m", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 15 }, @@ -3669,7 +3669,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 5, "maxValue": 25 }, @@ -3682,7 +3682,7 @@ "units": "s", "defaultValue": 5, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 30 }, @@ -3695,7 +3695,7 @@ "longDescription": "A non-zero, positive value specifies the timeframe in seconds within failure detector is allowed to put the vehicle into a lockdown state if attitude exceeds the limits defined in FD_FAIL_P and FD_FAIL_R. The check is not executed for flight modes that do support acrobatic maneuvers, e.g: Acro (MC/FW), Rattitude and Manual (FW). A zero or negative value means that the check is disabled.", "units": "s", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 5 }, @@ -3722,7 +3722,7 @@ "description": "Return at critical level, land at emergency level" } ], - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3734,7 +3734,7 @@ "shortDescription": "Enable Motor Testing", "longDescription": "If set, enables the motor test interface via MAVLink (DO_MOTOR_TEST), that allows spinning the motors for testing purposes.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3772,7 +3772,7 @@ "description": "Lockdown" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3822,7 +3822,7 @@ "description": "Lockdown" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3833,7 +3833,7 @@ "category": "Standard", "shortDescription": "Flag to enable obstacle avoidance", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3846,7 +3846,7 @@ "units": "s", "defaultValue": 0.5, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 60 }, @@ -3868,7 +3868,7 @@ "description": "Land/Terminate. Assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to TERMINATION." } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3882,7 +3882,7 @@ "units": "sec", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 100 }, @@ -3895,7 +3895,7 @@ "longDescription": "This is the horizontal position error (EPH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.", "units": "m", "defaultValue": 5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -3908,7 +3908,7 @@ "longDescription": "This is the vertical position error (EPV) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.", "units": "m", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -3921,7 +3921,7 @@ "longDescription": "This sets the rate that the loss of position probation time grows when position checks are failing. The default value has been optimised for rotary wing applications. For fixed wing applications a value of 0 should be used.", "defaultValue": 10, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3935,7 +3935,7 @@ "units": "sec", "defaultValue": 30, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 100 }, @@ -3947,7 +3947,7 @@ "shortDescription": "Required number of redundant power modules", "longDescription": "This configures a check to verify the expected number of 5V rail power supplies are present. By default only one is expected. Note: CBRK_SUPPLY_CHK disables all power checks including this one.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 4 }, @@ -3973,7 +3973,7 @@ "description": "Always" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -3985,7 +3985,7 @@ "shortDescription": "RC input arm/disarm command duration", "longDescription": "The default value of 1000 requires the stick to be held in the arm or disarm position for 1 second.", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 100, "maxValue": 1500 }, @@ -4011,7 +4011,7 @@ "description": "Virtual RC by Joystick" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -4025,7 +4025,7 @@ "units": "s", "defaultValue": 0.5, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 35 }, @@ -4037,7 +4037,7 @@ "shortDescription": "Enable RC stick override of auto and/or offboard modes", "longDescription": "When RC stick override is enabled, moving the RC sticks immediately gives control back to the pilot (switches to manual position mode): bit 0: Enable for auto modes (except for in critical battery reaction), bit 1: Enable for offboard mode. Only has an effect on multicopters, and VTOLS in multicopter mode.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3 }, @@ -4051,7 +4051,7 @@ "units": "%", "defaultValue": 12, "increment": 0.05, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 5, "maxValue": 40 }, @@ -4073,7 +4073,7 @@ "description": "Mission (if valid)" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4086,7 +4086,7 @@ "longDescription": "This is the horizontal velocity error (EVH) threshold that will trigger a failsafe. The default is appropriate for a multicopter. Can be increased for a fixed-wing.", "units": "m/s", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4099,7 +4099,7 @@ "longDescription": "Only used in Position mode.", "units": "seconds", "defaultValue": 0.4, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -4112,7 +4112,7 @@ "longDescription": "Only used in Position mode. Collision avoidance is disabled by setting this parameter to a negative value", "units": "meters", "defaultValue": -1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 15 }, @@ -4124,7 +4124,7 @@ "shortDescription": "Boolean to allow moving into directions where there is no sensor data (outside FOV)", "longDescription": "Only used in Position mode.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4137,7 +4137,7 @@ "longDescription": "Only used in Position mode.", "units": "[deg]", "defaultValue": 30, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 90 }, @@ -4172,7 +4172,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4186,7 +4186,7 @@ "units": "%", "defaultValue": 0.055, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -4241,7 +4241,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4254,7 +4254,7 @@ "units": "m/s/s", "defaultValue": 0.2, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.5 }, @@ -4266,7 +4266,7 @@ "shortDescription": "Maximum IMU accel magnitude that allows IMU bias learning. If the magnitude of the IMU accelerometer vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale factor errors on the delta velocity bias estimates", "units": "m/s/s", "defaultValue": 25, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 20, "maxValue": 200 }, @@ -4278,7 +4278,7 @@ "shortDescription": "Maximum IMU gyro angular rate magnitude that allows IMU bias learning. If the magnitude of the IMU angular rate vector exceeds this value, the EKF delta velocity state estimation will be inhibited. This reduces the adverse effect of rapid rotation rates and associated errors on the delta velocity bias estimates", "units": "rad/s", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 2, "maxValue": 20 }, @@ -4290,7 +4290,7 @@ "shortDescription": "Accelerometer bias learning limit. The ekf delta velocity bias states will be limited to within a range equivalent to +- of this value", "units": "m/s/s", "defaultValue": 0.4, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.8 }, @@ -4302,7 +4302,7 @@ "shortDescription": "Time constant used by acceleration and angular rate magnitude checks used to inhibit delta velocity bias learning. The vector magnitude of angular rate and acceleration used to check if learning should be inhibited has a peak hold filter applied to it with an exponential decay. This parameter controls the time constant of the decay", "units": "s", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -4314,7 +4314,7 @@ "shortDescription": "Process noise for IMU accelerometer bias prediction", "units": "m/s**3", "defaultValue": 0.003, - "decimalPlaces": "6", + "decimalPlaces": 6, "minValue": 0, "maxValue": 0.01 }, @@ -4326,7 +4326,7 @@ "shortDescription": "Accelerometer noise for covariance prediction", "units": "m/s/s", "defaultValue": 0.35, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 1 }, @@ -4339,7 +4339,7 @@ "longDescription": "Set bits in the following positions to enable: 0 : Set to true to use GPS data if available 1 : Set to true to use optical flow data if available 2 : Set to true to inhibit IMU delta velocity bias estimation 3 : Set to true to enable vision position fusion 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true. 5 : Set to true to enable multi-rotor drag specific force fusion 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used 7 : Set to true to enable GPS yaw fusion. Cannot be used if bit position 4 is true.", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 511 }, @@ -4352,7 +4352,7 @@ "units": "rad", "defaultValue": 0.1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 0.5 }, @@ -4364,7 +4364,7 @@ "shortDescription": "Airspeed fusion threshold. A value of zero will deactivate airspeed fusion. Any other positive value will determine the minimum airspeed which will still be fused. Set to about 90% of the vehicles stall speed. Both airspeed fusion and sideslip fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_FUSE_BETA to activate sideslip fusion", "units": "m/s", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -4376,7 +4376,7 @@ "shortDescription": "Upper limit on airspeed along individual axes used to correct baro for position error effects", "units": "m/s", "defaultValue": 20, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 5, "maxValue": 50 }, @@ -4389,7 +4389,7 @@ "units": "ms", "defaultValue": 100, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -4402,7 +4402,7 @@ "units": "ms", "defaultValue": 5, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -4415,7 +4415,7 @@ "units": "ms", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -4428,7 +4428,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4440,7 +4440,7 @@ "shortDescription": "Measurement noise for barometric altitude", "units": "m", "defaultValue": 3.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 15 }, @@ -4452,7 +4452,7 @@ "shortDescription": "X-axis ballistic coefficient used by the multi-rotor specific drag force model. This should be adjusted to minimise variance of the X-axis drag specific force innovation sequence", "units": "kg/m**2", "defaultValue": 25, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 100 }, @@ -4464,7 +4464,7 @@ "shortDescription": "Y-axis ballistic coefficient used by the multi-rotor specific drag force model. This should be adjusted to minimise variance of the Y-axis drag specific force innovation sequence", "units": "kg/m**2", "defaultValue": 25, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 100 }, @@ -4477,7 +4477,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4489,7 +4489,7 @@ "shortDescription": "Noise for synthetic sideslip fusion", "units": "m/s", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -4502,7 +4502,7 @@ "longDescription": "Set bits in the following positions to enable functions. 0 : Set to true to use the declination from the geo_lookup library when the GPS position becomes available, set to false to always use the EKF2_MAG_DECL value. 1 : Set to true to save the EKF2_MAG_DECL parameter to the value returned by the EKF when the vehicle disarms. 2 : Set to true to always use the declination as an observation when 3-axis magnetometer fusion is being used.", "defaultValue": 7, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 7 }, @@ -4514,7 +4514,7 @@ "shortDescription": "Specific drag force observation noise variance used by the multi-rotor specific drag force model. Increasing it makes the multi-rotor wind estimates adjust more slowly", "units": "(m/sec**2)**2", "defaultValue": 2.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.5, "maxValue": 10 }, @@ -4526,7 +4526,7 @@ "shortDescription": "Measurement noise for airspeed fusion", "units": "m/s", "defaultValue": 1.4, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.5, "maxValue": 5 }, @@ -4538,7 +4538,7 @@ "shortDescription": "Measurement noise for vision angle observations used to lower bound or replace the uncertainty included in the message", "units": "rad", "defaultValue": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.05, "maxValue": 3.40282e+38 }, @@ -4550,7 +4550,7 @@ "shortDescription": "Gate size for vision position fusion Sets the number of standard deviations used by the innovation consistency test", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4562,7 +4562,7 @@ "shortDescription": "Measurement noise for vision position observations used to lower bound or replace the uncertainty included in the message", "units": "m", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -4575,7 +4575,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4587,7 +4587,7 @@ "shortDescription": "Measurement noise for vision velocity observations used to lower bound or replace the uncertainty included in the message", "units": "m/s", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -4600,7 +4600,7 @@ "units": "ms", "defaultValue": 175, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -4612,7 +4612,7 @@ "shortDescription": "Whether to set the external vision observation noise from the parameter or from vision message", "longDescription": "If set to true the observation noise is set from the parameters directly, if set to false the measurement noise is taken from the vision message and the parameter are used as a lower bound.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4624,7 +4624,7 @@ "shortDescription": "X position of VI sensor focal point in body frame (forward axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4636,7 +4636,7 @@ "shortDescription": "Y position of VI sensor focal point in body frame (right axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4648,7 +4648,7 @@ "shortDescription": "Z position of VI sensor focal point in body frame (down axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4660,7 +4660,7 @@ "shortDescription": "Boolean determining if synthetic sideslip measurements should fused", "longDescription": "A value of 1 indicates that fusion is active Both sideslip fusion and airspeed fusion must be active for the EKF to continue navigating after loss of GPS. Use EKF2_ARSP_THR to activate airspeed fusion.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4673,7 +4673,7 @@ "units": "rad/sec", "defaultValue": 0.1, "rebootRequired": true, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.2 }, @@ -4686,7 +4686,7 @@ "longDescription": "Sets the value of deadzone applied to negative baro innovations. Deadzone is enabled when EKF2_GND_EFF_DZ > 0.", "units": "M", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 10 }, @@ -4699,7 +4699,7 @@ "longDescription": "Sets the maximum distance to the ground level where negative baro innovations are expected.", "units": "M", "defaultValue": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 5 }, @@ -4711,7 +4711,7 @@ "shortDescription": "Integer bitmask controlling GPS checks", "longDescription": "Set bits to 1 to enable checks. Checks enabled by the following bit positions 0 : Minimum required sat count set by EKF2_REQ_NSATS 1 : Minimum required PDOP set by EKF2_REQ_PDOP 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV 4 : Maximum allowed speed error set by EKF2_REQ_SACC 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT", "defaultValue": 245, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 511 }, @@ -4724,7 +4724,7 @@ "units": "ms", "defaultValue": 110, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -4736,7 +4736,7 @@ "shortDescription": "Multi GPS Blending Control Mask", "longDescription": "Set bits in the following positions to set which GPS accuracy metrics will be used to calculate the blending weight. Set to zero to disable and always used first GPS instance. 0 : Set to true to use speed accuracy 1 : Set to true to use horizontal position accuracy 2 : Set to true to use vertical position accuracy", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 7 }, @@ -4748,7 +4748,7 @@ "shortDescription": "X position of GPS antenna in body frame (forward axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4760,7 +4760,7 @@ "shortDescription": "Y position of GPS antenna in body frame (right axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4772,7 +4772,7 @@ "shortDescription": "Z position of GPS antenna in body frame (down axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4785,7 +4785,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4797,7 +4797,7 @@ "shortDescription": "Measurement noise for gps position", "units": "m", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 10 }, @@ -4810,7 +4810,7 @@ "longDescription": "Sets the longest time constant that will be applied to the calculation of GPS position and height offsets used to correct data from multiple GPS data for steady state position differences.", "units": "s", "defaultValue": 10, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 100 }, @@ -4823,7 +4823,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4835,7 +4835,7 @@ "shortDescription": "Measurement noise for gps horizontal velocity", "units": "m/s", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 5 }, @@ -4847,7 +4847,7 @@ "shortDescription": "Default value of true airspeed used in EKF-GSF AHRS calculation. If no airspeed measurements are avalable, the EKF-GSF AHRS calculation will assume this value of true airspeed when compensating for centripetal acceleration during turns. Set to zero to disable centripetal acceleration compensation during fixed wing flight modes", "units": "m/s", "defaultValue": 15, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 100 }, @@ -4859,7 +4859,7 @@ "shortDescription": "Process noise for IMU rate gyro bias prediction", "units": "rad/s**2", "defaultValue": 0.001, - "decimalPlaces": "6", + "decimalPlaces": 6, "minValue": 0, "maxValue": 0.01 }, @@ -4871,7 +4871,7 @@ "shortDescription": "Rate gyro noise for covariance prediction", "units": "rad/s", "defaultValue": 0.015, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.0001, "maxValue": 0.1 }, @@ -4884,7 +4884,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 2.6, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -4896,7 +4896,7 @@ "shortDescription": "Measurement noise for magnetic heading fusion", "units": "rad", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 1 }, @@ -4927,7 +4927,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4945,7 +4945,7 @@ "description": "System Primary" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -4957,7 +4957,7 @@ "shortDescription": "X position of IMU in body frame (forward axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4969,7 +4969,7 @@ "shortDescription": "Y position of IMU in body frame (right axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4981,7 +4981,7 @@ "shortDescription": "Z position of IMU in body frame (down axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -4993,7 +4993,7 @@ "shortDescription": "ID of Magnetometer the learned bias is for", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5007,7 +5007,7 @@ "defaultValue": 0, "rebootRequired": true, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -0.5, "maxValue": 0.5 }, @@ -5021,7 +5021,7 @@ "defaultValue": 0, "rebootRequired": true, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -0.5, "maxValue": 0.5 }, @@ -5035,7 +5035,7 @@ "defaultValue": 0, "rebootRequired": true, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -0.5, "maxValue": 0.5 }, @@ -5046,7 +5046,7 @@ "category": "Standard", "shortDescription": "Maximum fraction of learned mag bias saved at each disarm. Smaller values make the saved mag bias learn slower from flight to flight. Larger values make it learn faster. Must be > 0.0 and <= 1.0", "defaultValue": 0.2, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -5059,7 +5059,7 @@ "units": "mGauss**2", "defaultValue": 2.5e-07, "rebootRequired": true, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5071,7 +5071,7 @@ "shortDescription": "Horizontal acceleration threshold used by automatic selection of magnetometer fusion method. This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered horizontal acceleration is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion", "units": "m/s**2", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 5 }, @@ -5083,7 +5083,7 @@ "shortDescription": "Process noise for body magnetic field prediction", "units": "Gauss/s", "defaultValue": 0.0001, - "decimalPlaces": "6", + "decimalPlaces": 6, "minValue": 0, "maxValue": 0.1 }, @@ -5095,7 +5095,7 @@ "shortDescription": "Magnetic field strength test selection", "longDescription": "When set, the EKF checks the strength of the magnetic field to decide whether the magnetometer data is valid. If GPS data is received, the magnetic field is compared to a World Magnetic Model (WMM), otherwise an average value is used. This check is useful to reject occasional hard iron disturbance.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5108,7 +5108,7 @@ "units": "deg", "defaultValue": 0, "volatile": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5121,7 +5121,7 @@ "units": "ms", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -5133,7 +5133,7 @@ "shortDescription": "Process noise for earth magnetic field prediction", "units": "Gauss/s", "defaultValue": 0.001, - "decimalPlaces": "6", + "decimalPlaces": 6, "minValue": 0, "maxValue": 0.1 }, @@ -5146,7 +5146,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -5158,7 +5158,7 @@ "shortDescription": "Measurement noise for magnetometer 3-axis fusion", "units": "Gauss", "defaultValue": 0.05, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.001, "maxValue": 1 }, @@ -5197,7 +5197,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5209,7 +5209,7 @@ "shortDescription": "Yaw rate threshold used by automatic selection of magnetometer fusion method. This parameter is used when the magnetometer fusion method is set automatically (EKF2_MAG_TYPE = 0). If the filtered yaw rate is greater than this parameter value, then the EKF will use 3-axis magnetomer fusion", "units": "rad/s", "defaultValue": 0.25, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -5222,7 +5222,7 @@ "units": "ms", "defaultValue": 20, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 10, "maxValue": 50 }, @@ -5235,7 +5235,7 @@ "longDescription": "If the vehicle is on ground, is not moving as determined by the motion test controlled by EKF2_MOVE_TEST and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground.", "units": "m", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -5247,7 +5247,7 @@ "shortDescription": "Vehicle movement test threshold", "longDescription": "Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter.", "defaultValue": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.1, "maxValue": 10 }, @@ -5259,7 +5259,7 @@ "shortDescription": "Measurement noise for non-aiding position hold", "units": "m", "defaultValue": 10, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.5, "maxValue": 50 }, @@ -5271,7 +5271,7 @@ "shortDescription": "Maximum lapsed time from last fusion of measurements that constrain velocity drift before the EKF will report the horizontal nav solution as invalid", "units": "uSec", "defaultValue": 5e+06, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 500000, "maxValue": 1e+07 }, @@ -5284,7 +5284,7 @@ "units": "ms", "defaultValue": 5, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -5297,7 +5297,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -5310,7 +5310,7 @@ "longDescription": "(when it's reported quality metric is at the minimum set by EKF2_OF_QMIN). The following condition must be met: EKF2_OF_N_MAXN >= EKF2_OF_N_MIN", "units": "rad/s", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.05, "maxValue": 3.40282e+38 }, @@ -5322,7 +5322,7 @@ "shortDescription": "Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum", "units": "rad/s", "defaultValue": 0.15, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.05, "maxValue": 3.40282e+38 }, @@ -5334,7 +5334,7 @@ "shortDescription": "X position of optical flow focal point in body frame (forward axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5346,7 +5346,7 @@ "shortDescription": "Y position of optical flow focal point in body frame (right axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5358,7 +5358,7 @@ "shortDescription": "Z position of optical flow focal point in body frame (down axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5369,7 +5369,7 @@ "category": "Standard", "shortDescription": "Optical Flow data will only be used if the sensor reports a quality metric >= EKF2_OF_QMIN", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 255 }, @@ -5380,7 +5380,7 @@ "category": "Standard", "shortDescription": "Static pressure position error coefficient for the negative X axis. This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.5, "maxValue": 0.5 }, @@ -5391,7 +5391,7 @@ "category": "Standard", "shortDescription": "Static pressure position error coefficient for the positive X axis This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forward flight, then this will be a negative number", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.5, "maxValue": 0.5 }, @@ -5402,7 +5402,7 @@ "category": "Standard", "shortDescription": "Pressure position error coefficient for the negative Y axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the negative Y (LH) body axis. If the baro height estimate rises during sideways flight to the left, then this will be a negative number", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.5, "maxValue": 0.5 }, @@ -5413,7 +5413,7 @@ "category": "Standard", "shortDescription": "Pressure position error coefficient for the positive Y axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the positive Y (RH) body axis. If the baro height estimate rises during sideways flight to the right, then this will be a negative number", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.5, "maxValue": 0.5 }, @@ -5424,7 +5424,7 @@ "category": "Standard", "shortDescription": "Static pressure position error coefficient for the Z axis. This is the ratio of static pressure error to dynamic pressure generated by a wind relative velocity along the Z body axis", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.5, "maxValue": 0.5 }, @@ -5436,7 +5436,7 @@ "shortDescription": "Required EPH to use GPS", "units": "m", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 2, "maxValue": 100 }, @@ -5448,7 +5448,7 @@ "shortDescription": "Required EPV to use GPS", "units": "m", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 2, "maxValue": 100 }, @@ -5462,7 +5462,7 @@ "units": "s", "defaultValue": 10, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.1, "maxValue": 3.40282e+38 }, @@ -5474,7 +5474,7 @@ "shortDescription": "Maximum horizontal drift speed to use GPS", "units": "m/s", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -5485,7 +5485,7 @@ "category": "Standard", "shortDescription": "Required satellite count to use GPS", "defaultValue": 6, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 4, "maxValue": 12 }, @@ -5496,7 +5496,7 @@ "category": "Standard", "shortDescription": "Required PDOP to use GPS", "defaultValue": 2.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1.5, "maxValue": 5 }, @@ -5508,7 +5508,7 @@ "shortDescription": "Required speed accuracy to use GPS", "units": "m/s", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.5, "maxValue": 5 }, @@ -5520,7 +5520,7 @@ "shortDescription": "Maximum vertical drift speed to use GPS", "units": "m/s", "defaultValue": 0.2, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1.5 }, @@ -5542,7 +5542,7 @@ "description": "Range aid enabled" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5555,7 +5555,7 @@ "longDescription": "If the vehicle absolute altitude exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled).", "units": "m", "defaultValue": 5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 10 }, @@ -5568,7 +5568,7 @@ "longDescription": "A lower value means HAGL needs to be more stable in order to use range finder for height estimation in range aid mode", "units": "SD", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 5 }, @@ -5581,7 +5581,7 @@ "longDescription": "If the vehicle horizontal speed exceeds this value then the estimator will not fuse range measurements to estimate it's height. This only applies when range aid mode is activated (EKF2_RNG_AID = enabled).", "units": "m/s", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 2 }, @@ -5594,7 +5594,7 @@ "units": "ms", "defaultValue": 5, "rebootRequired": true, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 300 }, @@ -5607,7 +5607,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -5619,7 +5619,7 @@ "shortDescription": "Measurement noise for range finder fusion", "units": "m", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -5631,7 +5631,7 @@ "shortDescription": "Range sensor pitch offset", "units": "rad", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -0.75, "maxValue": 0.75 }, @@ -5643,7 +5643,7 @@ "shortDescription": "X position of range finder origin in body frame (forward axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5655,7 +5655,7 @@ "shortDescription": "Y position of range finder origin in body frame (right axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5667,7 +5667,7 @@ "shortDescription": "Z position of range finder origin in body frame (down axis with origin relative to vehicle centre of gravity)", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5680,7 +5680,7 @@ "longDescription": "Specifies the increase in range finder noise with range.", "units": "m/m", "defaultValue": 0.05, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 0.2 }, @@ -5693,7 +5693,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -5705,7 +5705,7 @@ "shortDescription": "Time constant of the position output prediction and smoothing filter. Controls how tightly the output track the EKF states", "units": "s", "defaultValue": 0.25, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 1 }, @@ -5717,7 +5717,7 @@ "shortDescription": "Time constant of the velocity output prediction and smoothing filter", "units": "s", "defaultValue": 0.25, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -3.40282e+38, "maxValue": 1 }, @@ -5729,7 +5729,7 @@ "shortDescription": "Magnitude of terrain gradient", "units": "m/m", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -5741,7 +5741,7 @@ "shortDescription": "Integer bitmask controlling fusion sources of the terrain estimator", "longDescription": "Set bits in the following positions to enable: 0 : Set to true to use range finder data if available 1 : Set to true to use optical flow data if available", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3 }, @@ -5753,7 +5753,7 @@ "shortDescription": "Terrain altitude process noise - accounts for instability in vehicle height estimate", "units": "m/s", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.5, "maxValue": 3.40282e+38 }, @@ -5765,7 +5765,7 @@ "shortDescription": "Process noise for wind velocity prediction", "units": "m/s/s", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -5778,7 +5778,7 @@ "longDescription": "Enable/disable event task for RC Loss. When enabled, an alarm tune will be played via buzzer or ESCs, if supported. The alarm will sound after a disarm, if the vehicle was previously armed and only if the vehicle had RC signal at some point. Particularly useful for locating crashed drones without a GPS sensor.", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5791,7 +5791,7 @@ "longDescription": "Enable/disable event task for displaying the vehicle status using arm-mounted LEDs. When enabled and if the vehicle supports it, LEDs will flash indicating various vehicle status changes. Currently PX4 has not implemented any specific status events. -", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5802,7 +5802,7 @@ "category": "Standard", "shortDescription": "EXFW_HDNG_P", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5813,7 +5813,7 @@ "category": "Standard", "shortDescription": "EXFW_PITCH_P", "defaultValue": 0.2, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5824,7 +5824,7 @@ "category": "Standard", "shortDescription": "EXFW_ROLL_P", "defaultValue": 0.2, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -5836,7 +5836,7 @@ "shortDescription": "Enable checks on ESCs that report their arming state. If enabled, failure detector will verify that all the ESCs have successfully armed when the vehicle has transitioned to the armed state. Timeout for receiving an acknowledgement from the ESCs is 0.3s, if no feedback is received the failure detector will auto disarm the vehicle", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5849,7 +5849,7 @@ "longDescription": "External ATS is required by ASTM F3322-18.", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5862,7 +5862,7 @@ "longDescription": "External ATS is required by ASTM F3322-18.", "units": "microseconds", "defaultValue": 1900, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -5875,7 +5875,7 @@ "longDescription": "Maximum pitch angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "units": "degrees", "defaultValue": 60, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 60, "maxValue": 180 }, @@ -5888,7 +5888,7 @@ "longDescription": "Seconds (decimal) that pitch has to exceed FD_FAIL_P before being considered as a failure.", "units": "s", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.02, "maxValue": 5 }, @@ -5901,7 +5901,7 @@ "longDescription": "Maximum roll angle before FailureDetector triggers the attitude_failure flag. The flag triggers flight termination (if @CBRK_FLIGHTTERM = 0), which sets outputs to their failsafe values. On takeoff the flag triggers lockdown (irrespective of @CBRK_FLIGHTTERM), which disarms motors but does not set outputs to failsafe values. Setting this parameter to 0 disables the check", "units": "degrees", "defaultValue": 60, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 60, "maxValue": 180 }, @@ -5914,7 +5914,7 @@ "longDescription": "Seconds (decimal) that roll has to exceed FD_FAIL_R before being considered as a failure.", "units": "s", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.02, "maxValue": 5 }, @@ -5927,7 +5927,7 @@ "longDescription": "This is the rate the controller is trying to achieve if the user applies full roll stick input in acro mode.", "units": "degrees", "defaultValue": 90, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 45, "maxValue": 720 }, @@ -5940,7 +5940,7 @@ "longDescription": "This is the body y rate the controller is trying to achieve if the user applies full pitch stick input in acro mode.", "units": "degrees", "defaultValue": 90, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 45, "maxValue": 720 }, @@ -5953,7 +5953,7 @@ "longDescription": "This is the body z rate the controller is trying to achieve if the user applies full yaw stick input in acro mode.", "units": "degrees", "defaultValue": 45, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 10, "maxValue": 180 }, @@ -5967,7 +5967,7 @@ "units": "m/s", "defaultValue": 20, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -5981,7 +5981,7 @@ "units": "m/s", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -5995,7 +5995,7 @@ "units": "m/s", "defaultValue": 15, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -6017,7 +6017,7 @@ "description": "Airspeed disabled" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -6029,7 +6029,7 @@ "shortDescription": "Enable airspeed scaling", "longDescription": "This enables a logic that automatically adjusts the output of the rate controller to take into account the real torque produced by an aerodynamic control surface given the current deviation from the trim airspeed (FW_AIRSPD_TRIM). Enable when using aerodynamic control surfaces (e.g.: plane) Disable when using rotor wings (e.g.: autogyro)", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -6041,7 +6041,7 @@ "shortDescription": "Whether to scale throttle by battery power level", "longDescription": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The fixed wing should constantly behave as if it was fully charged with reduced max thrust at lower battery percentages. i.e. if cruise speed is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -6055,7 +6055,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 150 }, @@ -6068,7 +6068,7 @@ "longDescription": "This increment is added to the pitch trim whenever flaps are fully deployed.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6081,7 +6081,7 @@ "longDescription": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MAX.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6094,7 +6094,7 @@ "longDescription": "This increment is added to TRIM_PITCH when airspeed is FW_AIRSPD_MIN.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6107,7 +6107,7 @@ "longDescription": "This increment is added to TRIM_ROLL whenever flaps are fully deployed.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6120,7 +6120,7 @@ "longDescription": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MAX.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6133,7 +6133,7 @@ "longDescription": "This increment is added to TRIM_ROLL when airspeed is FW_AIRSPD_MIN.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6146,7 +6146,7 @@ "longDescription": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MAX.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6159,7 +6159,7 @@ "longDescription": "This increment is added to TRIM_YAW when airspeed is FW_AIRSPD_MIN.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.25, "maxValue": 0.25 }, @@ -6172,7 +6172,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6186,7 +6186,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6199,7 +6199,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6213,7 +6213,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6227,7 +6227,7 @@ "units": "m/s", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -6240,7 +6240,7 @@ "longDescription": "Damping factor for L1 control.", "defaultValue": 0.75, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.6, "maxValue": 0.9 }, @@ -6254,7 +6254,7 @@ "units": "m", "defaultValue": 20, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 12, "maxValue": 50 }, @@ -6268,7 +6268,7 @@ "units": "deg/s", "defaultValue": 90, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -6282,7 +6282,7 @@ "units": "norm", "defaultValue": 1.3, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 1, "maxValue": 1.5 }, @@ -6295,7 +6295,7 @@ "units": "deg", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 15 }, @@ -6307,7 +6307,7 @@ "shortDescription": "Early landing configuration deployment", "longDescription": "When disabled, the landing configuration (flaps, landing airspeed, etc.) is only activated on the final approach to landing. When enabled, it is already activated when entering the final loiter-down (loiter-to-alt) waypoint before the landing approach. This shifts the (often large) altitude and airspeed errors caused by the configuration change away from the ground such that these are not so critical. It also gives the controller enough time to adapt to the new configuration such that the landing approach starts with a cleaner initial state.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -6320,7 +6320,7 @@ "units": "m", "defaultValue": 3, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 25 }, @@ -6334,7 +6334,7 @@ "units": "deg", "defaultValue": 15, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 45 }, @@ -6348,7 +6348,7 @@ "units": "deg", "defaultValue": 2.5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 15 }, @@ -6361,7 +6361,7 @@ "units": "m", "defaultValue": 15, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 30 }, @@ -6374,7 +6374,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 15 }, @@ -6387,7 +6387,7 @@ "longDescription": "Set this parameter to less than 1.0 to make the TECS throttle loop react faster during landing than during normal flight (i.e. giving efficiency and low motor wear at high altitudes but control accuracy during landing). During landing, the TECS throttle time constant (FW_T_THRO_CONST) is multiplied by this value.", "defaultValue": 1, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.2, "maxValue": 1 }, @@ -6401,7 +6401,7 @@ "units": "m", "defaultValue": -1, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -1, "maxValue": 30 }, @@ -6413,7 +6413,7 @@ "shortDescription": "Use terrain estimate during landing", "longDescription": "This is turned off by default and a waypoint or return altitude is normally used (or sea level for an arbitrary land position).", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -6427,7 +6427,7 @@ "units": "deg", "defaultValue": 45, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -6441,7 +6441,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -6455,7 +6455,7 @@ "units": "deg", "defaultValue": 45, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -6469,7 +6469,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6483,7 +6483,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -6497,7 +6497,7 @@ "units": "%/rad/s", "defaultValue": 0.5, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -6511,7 +6511,7 @@ "units": "%/rad", "defaultValue": 0.1, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 0.5 }, @@ -6524,7 +6524,7 @@ "longDescription": "The portion of the integrator part in the control surface deflection is limited to this value", "defaultValue": 0.4, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6538,7 +6538,7 @@ "units": "%/rad/s", "defaultValue": 0.08, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 1 }, @@ -6552,7 +6552,7 @@ "units": "deg", "defaultValue": 0, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -90, "maxValue": 90 }, @@ -6566,7 +6566,7 @@ "units": "deg", "defaultValue": 45, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 60 }, @@ -6580,7 +6580,7 @@ "units": "deg", "defaultValue": -45, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -60, "maxValue": 0 }, @@ -6594,7 +6594,7 @@ "units": "deg/s", "defaultValue": 60, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -6608,7 +6608,7 @@ "units": "deg/s", "defaultValue": 60, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -6622,7 +6622,7 @@ "units": "s", "defaultValue": 0.4, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.2, "maxValue": 1 }, @@ -6635,7 +6635,7 @@ "longDescription": "Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints", "defaultValue": 0.8, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6648,7 +6648,7 @@ "longDescription": "This gain can be used to counteract the \"adverse yaw\" effect for fixed wings. When the plane enters a roll it will tend to yaw the nose out of the turn. This gain enables the use of a yaw actuator (rudder, airbrakes, ...) to counteract this effect.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -6662,7 +6662,7 @@ "units": "%/rad/s", "defaultValue": 0.5, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -6676,7 +6676,7 @@ "units": "%/rad", "defaultValue": 0.1, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 0.2 }, @@ -6689,7 +6689,7 @@ "longDescription": "The portion of the integrator part in the control surface deflection is limited to this value.", "defaultValue": 0.2, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6703,7 +6703,7 @@ "units": "%/rad/s", "defaultValue": 0.05, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 1 }, @@ -6717,7 +6717,7 @@ "units": "deg", "defaultValue": 0, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -90, "maxValue": 90 }, @@ -6731,7 +6731,7 @@ "units": "deg", "defaultValue": 50, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 35, "maxValue": 65 }, @@ -6745,7 +6745,7 @@ "units": "deg/s", "defaultValue": 70, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -6759,7 +6759,7 @@ "units": "s", "defaultValue": 0.4, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.4, "maxValue": 1 }, @@ -6772,7 +6772,7 @@ "longDescription": "Automatically adjust throttle to account for decreased air density at higher altitudes. Start with a scale factor of 1.0 and adjust for different propulsion systems. When flying without airspeed sensor this will help to keep a constant performance over large altitude ranges. The default value of 0 will disable scaling.", "defaultValue": 0, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 10 }, @@ -6786,7 +6786,7 @@ "units": "norm", "defaultValue": 0.6, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6800,7 +6800,7 @@ "units": "norm", "defaultValue": 0.15, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.4 }, @@ -6814,7 +6814,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6828,7 +6828,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6842,7 +6842,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6854,7 +6854,7 @@ "shortDescription": "Throttle max slew rate", "longDescription": "Maximum slew rate for the commanded throttle", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -6868,7 +6868,7 @@ "units": "m/s", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 15 }, @@ -6880,7 +6880,7 @@ "shortDescription": "Height rate feed forward", "defaultValue": 0.8, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6892,7 +6892,7 @@ "shortDescription": "Height rate proportional factor", "defaultValue": 0.05, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -6905,7 +6905,7 @@ "longDescription": "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. Set this value to zero to completely disable all integrator action.", "defaultValue": 0.1, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 2 }, @@ -6918,7 +6918,7 @@ "longDescription": "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.", "defaultValue": 0, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 2 }, @@ -6931,7 +6931,7 @@ "longDescription": "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.", "defaultValue": 15, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 20 }, @@ -6945,7 +6945,7 @@ "units": "m/s", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 15 }, @@ -6959,7 +6959,7 @@ "units": "m/s", "defaultValue": 2, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 5 }, @@ -6972,7 +6972,7 @@ "longDescription": "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).", "defaultValue": 1, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 2 }, @@ -6986,7 +6986,7 @@ "units": "rad/s", "defaultValue": 2, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 10 }, @@ -6998,7 +6998,7 @@ "shortDescription": "Speed rate P factor", "defaultValue": 0.02, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 2 }, @@ -7012,7 +7012,7 @@ "units": "s", "defaultValue": 8, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 10 }, @@ -7025,7 +7025,7 @@ "longDescription": "This is the damping gain for the throttle demand loop. Increase to add damping to correct for oscillations in speed and height.", "defaultValue": 0.5, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 2 }, @@ -7039,7 +7039,7 @@ "units": "s", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 10 }, @@ -7053,7 +7053,7 @@ "units": "m/s/s", "defaultValue": 7, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 10 }, @@ -7067,7 +7067,7 @@ "units": "%/rad/s", "defaultValue": 0.2, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -7081,7 +7081,7 @@ "units": "%/rad", "defaultValue": 0.1, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 0.5 }, @@ -7094,7 +7094,7 @@ "longDescription": "The portion of the integrator part in the control surface deflection is limited to this value", "defaultValue": 1, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -7108,7 +7108,7 @@ "units": "%/rad/s", "defaultValue": 0.5, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 1 }, @@ -7119,7 +7119,7 @@ "category": "Standard", "shortDescription": "Enable wheel steering controller", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -7133,7 +7133,7 @@ "units": "deg/s", "defaultValue": 30, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -7147,7 +7147,7 @@ "units": "%/rad/s", "defaultValue": 0.3, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -7161,7 +7161,7 @@ "units": "%/rad", "defaultValue": 0.1, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 50 }, @@ -7174,7 +7174,7 @@ "longDescription": "The portion of the integrator part in the control surface deflection is limited to this value", "defaultValue": 0.2, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -7188,7 +7188,7 @@ "units": "%/rad/s", "defaultValue": 0.05, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 1 }, @@ -7202,7 +7202,7 @@ "units": "deg/s", "defaultValue": 50, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -7236,7 +7236,7 @@ "description": "Terminate" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 4 }, @@ -7258,7 +7258,7 @@ "description": "AMSL" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -7271,7 +7271,7 @@ "longDescription": "Set how many subsequent position measurements outside of the fence are needed before geofence violation is triggered", "defaultValue": -1, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": -1, "maxValue": 10 }, @@ -7285,7 +7285,7 @@ "units": "m", "defaultValue": 0, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 10000 }, @@ -7299,7 +7299,7 @@ "units": "m", "defaultValue": 0, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 10000 }, @@ -7321,7 +7321,7 @@ "description": "GPS" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -7334,7 +7334,7 @@ "longDescription": "Damping factor for L1 control.", "defaultValue": 0.75, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.6, "maxValue": 0.9 }, @@ -7348,7 +7348,7 @@ "units": "m", "defaultValue": 5, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 100 }, @@ -7362,7 +7362,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 50 }, @@ -7375,7 +7375,7 @@ "units": "rad", "defaultValue": 0.7854, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3.14159 }, @@ -7389,7 +7389,7 @@ "units": "%m/s", "defaultValue": 0.001, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 50 }, @@ -7403,7 +7403,7 @@ "units": "%m/s", "defaultValue": 3, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 50 }, @@ -7417,7 +7417,7 @@ "units": "%m/s", "defaultValue": 1, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 50 }, @@ -7430,7 +7430,7 @@ "units": "m/s", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -7444,7 +7444,7 @@ "units": "%m/s", "defaultValue": 2, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 50 }, @@ -7458,7 +7458,7 @@ "units": "%m/s", "defaultValue": 1, "increment": 0.005, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.005, "maxValue": 50 }, @@ -7471,7 +7471,7 @@ "units": "m/s", "defaultValue": 3, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 40 }, @@ -7493,7 +7493,7 @@ "description": "close the loop with gps speed" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -7507,7 +7507,7 @@ "units": "norm", "defaultValue": 0.1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -7521,7 +7521,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.4 }, @@ -7535,7 +7535,7 @@ "units": "norm", "defaultValue": 0.3, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -7549,7 +7549,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -7562,7 +7562,7 @@ "units": "m", "defaultValue": 2, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -7617,7 +7617,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -7672,7 +7672,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -7694,7 +7694,7 @@ "description": "Enable" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -7729,7 +7729,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 9 }, @@ -7743,7 +7743,7 @@ "units": "deg", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 360 }, @@ -7756,7 +7756,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "SD", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 10 }, @@ -7769,7 +7769,7 @@ "longDescription": "Sets the number of standard deviations used by the innovation consistency test.", "units": "normalized_thrust", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -7782,7 +7782,7 @@ "longDescription": "Reduce to make the hover thrust estimate more stable, increase if the real hover thrust is expected to change quickly over time.", "units": "normalized_thrust/s", "defaultValue": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.0001, "maxValue": 1 }, @@ -7796,7 +7796,7 @@ "units": "Hz", "defaultValue": 30, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1000 }, @@ -7810,7 +7810,7 @@ "units": "Hz", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1000 }, @@ -7824,7 +7824,7 @@ "units": "Hz", "defaultValue": 30, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1000 }, @@ -7838,7 +7838,7 @@ "units": "Hz", "defaultValue": 20, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -7852,7 +7852,7 @@ "units": "Hz", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1000 }, @@ -7892,7 +7892,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2000 }, @@ -7906,7 +7906,7 @@ "units": "Hz", "defaultValue": 200, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 100, "maxValue": 1000 }, @@ -7919,7 +7919,7 @@ "units": "u", "defaultValue": 18139, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 65535 }, @@ -7931,7 +7931,7 @@ "shortDescription": "INA226 Power Monitor Max Current", "defaultValue": 164, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 200 }, @@ -7943,7 +7943,7 @@ "shortDescription": "INA226 Power Monitor Shunt", "defaultValue": 0.0005, "increment": 1e-09, - "decimalPlaces": "10", + "decimalPlaces": 10, "minValue": 1e-09, "maxValue": 0.1 }, @@ -7998,7 +7998,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -8010,7 +8010,7 @@ "shortDescription": "Satellite radio read interval. Only required to be nonzero if data is not sent using a ring call", "units": "s", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 5000 }, @@ -8022,7 +8022,7 @@ "shortDescription": "Iridium SBD session timeout", "units": "s", "defaultValue": 60, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 300 }, @@ -8034,7 +8034,7 @@ "shortDescription": "Time [ms] the Iridium driver will wait for additional mavlink messages to combine them into one SBD message Value 0 turns the functionality off", "units": "ms", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 500 }, @@ -8045,7 +8045,7 @@ "category": "Standard", "shortDescription": "Launch detection", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -8059,7 +8059,7 @@ "units": "m/s/s", "defaultValue": 30, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -8073,7 +8073,7 @@ "units": "s", "defaultValue": 0, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 10 }, @@ -8087,7 +8087,7 @@ "units": "deg", "defaultValue": 30, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 45 }, @@ -8101,7 +8101,7 @@ "units": "s", "defaultValue": 0.05, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 5 }, @@ -8113,7 +8113,7 @@ "shortDescription": "RGB Led brightness limit", "longDescription": "Set to 0 to disable, 1 for minimum brightness up to 31 (max)", "defaultValue": 31, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 31 }, @@ -8125,7 +8125,7 @@ "shortDescription": "RGB Led brightness limit", "longDescription": "Set to 0 to disable, 1 for minimum brightness up to 15 (max)", "defaultValue": 15, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 15 }, @@ -8137,7 +8137,7 @@ "shortDescription": "BlinkM LED", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -8150,7 +8150,7 @@ "longDescription": "Maximum airspeed allowed in the landed state (m/s)", "units": "m/s", "defaultValue": 8, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 4, "maxValue": 20 }, @@ -8163,7 +8163,7 @@ "longDescription": "Maximum horizontal velocity allowed in the landed state (m/s)", "units": "m/s", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.5, "maxValue": 10 }, @@ -8176,7 +8176,7 @@ "longDescription": "Maximum vertical velocity allowed in the landed state (m/s up and down)", "units": "m/s", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.1, "maxValue": 20 }, @@ -8189,7 +8189,7 @@ "longDescription": "Maximum horizontal (x,y body axes) acceleration allowed in the landed state (m/s^2)", "units": "m/s^2", "defaultValue": 8, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 2, "maxValue": 15 }, @@ -8202,7 +8202,7 @@ "longDescription": "The system will obey this limit as a hard altitude limit. This setting will be consolidated with the GF_MAX_VER_DIST parameter. A negative value indicates no altitude limitation.", "units": "m", "defaultValue": -1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -1, "maxValue": 10000 }, @@ -8215,7 +8215,7 @@ "longDescription": "Multicopter threshold on the specific force measured by accelerometers in m/s^2 for free-fall detection", "units": "m/s^2", "defaultValue": 2, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 10 }, @@ -8228,7 +8228,7 @@ "longDescription": "Seconds (decimal) that freefall conditions have to met before triggering a freefall. Minimal value is limited by LAND_DETECTOR_UPDATE_RATE=50Hz in landDetector.h", "units": "s", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.02, "maxValue": 5 }, @@ -8241,7 +8241,7 @@ "longDescription": "Defines the commanded throttle value below which the land detector considers the vehicle to have \"low thrust\". This is one condition that is used to detect the ground contact state. The value is calculated as val = (MPC_THR_HOVER - MPC_THR_MIN) * LNDMC_LOW_T_THR + MPC_THR_MIN Increase this value if the system takes long time to detect landing.", "units": "norm", "defaultValue": 0.3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 0.9 }, @@ -8254,7 +8254,7 @@ "longDescription": "Maximum allowed angular velocity around each axis allowed in the landed state.", "units": "deg/s", "defaultValue": 20, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -8267,7 +8267,7 @@ "longDescription": "Maximum horizontal velocity allowed in the landed state (m/s)", "units": "m/s", "defaultValue": 1.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -8280,7 +8280,7 @@ "longDescription": "Maximum vertical velocity allowed in the landed state (m/s up and down)", "units": "m/s", "defaultValue": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -8293,7 +8293,7 @@ "longDescription": "Total flight time of this autopilot. Higher 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "defaultValue": 0, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -8306,7 +8306,7 @@ "longDescription": "Total flight time of this autopilot. Lower 32 bits of the value. Flight time in microseconds = (LND_FLIGHT_T_HI << 32) | LND_FLIGHT_T_LO.", "defaultValue": 0, "volatile": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -8319,7 +8319,7 @@ "longDescription": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz) Larger than data sheet to account for tilt error.", "units": "m/s^2/sqrt(Hz)", "defaultValue": 0.012, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 1e-05, "maxValue": 2 }, @@ -8332,7 +8332,7 @@ "longDescription": "Data sheet noise density = 150ug/sqrt(Hz) = 0.0015 m/s^2/sqrt(Hz)", "units": "m/s^2/sqrt(Hz)", "defaultValue": 0.02, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 1e-05, "maxValue": 2 }, @@ -8344,7 +8344,7 @@ "shortDescription": "Barometric presssure altitude z standard deviation", "units": "m", "defaultValue": 3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 100 }, @@ -8356,7 +8356,7 @@ "shortDescription": "Max EPH allowed for GPS initialization", "units": "m", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 5 }, @@ -8368,7 +8368,7 @@ "shortDescription": "Max EPV allowed for GPS initialization", "units": "m", "defaultValue": 5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 5 }, @@ -8379,7 +8379,7 @@ "category": "Standard", "shortDescription": "Enable publishing of a fake global position (e.g for AUTO missions using Optical Flow) by initializing the estimator to the LPE_LAT/LON parameters when global information is unavailable", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -8391,7 +8391,7 @@ "shortDescription": "Flow gyro high pass filter cut off frequency", "units": "Hz", "defaultValue": 0.001, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -8403,7 +8403,7 @@ "shortDescription": "Optical flow z offset from center", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -8414,7 +8414,7 @@ "category": "Standard", "shortDescription": "Optical flow minimum quality threshold", "defaultValue": 150, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 255 }, @@ -8426,7 +8426,7 @@ "shortDescription": "Optical flow rotation (roll/pitch) noise gain", "units": "m/s / (rad)", "defaultValue": 7, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 10 }, @@ -8438,7 +8438,7 @@ "shortDescription": "Optical flow angular velocity noise gain", "units": "m/s / (rad/s)", "defaultValue": 7, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 10 }, @@ -8450,7 +8450,7 @@ "shortDescription": "Optical flow scale", "units": "m", "defaultValue": 1.3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 10 }, @@ -8462,7 +8462,7 @@ "shortDescription": "Integer bitmask controlling data fusion", "longDescription": "Set bits in the following positions to enable: 0 : Set to true to fuse GPS data if available, also requires GPS for altitude init 1 : Set to true to fuse optical flow data if available 2 : Set to true to fuse vision position 3 : Set to true to enable landing target 4 : Set to true to fuse land detector 5 : Set to true to publish AGL as local position down component 6 : Set to true to enable flow gyro compensation 7 : Set to true to enable baro fusion default (145 - GPS, baro, land detector)", "defaultValue": 145, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 255 }, @@ -8474,7 +8474,7 @@ "shortDescription": "GPS delay compensaton", "units": "sec", "defaultValue": 0.29, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.4 }, @@ -8486,7 +8486,7 @@ "shortDescription": "GPS xy velocity standard deviation. EPV used if greater than this value", "units": "m/s", "defaultValue": 0.25, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 2 }, @@ -8498,7 +8498,7 @@ "shortDescription": "GPS z velocity standard deviation", "units": "m/s", "defaultValue": 0.25, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 2 }, @@ -8510,7 +8510,7 @@ "shortDescription": "Minimum GPS xy standard deviation, uses reported EPH if greater", "units": "m", "defaultValue": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 5 }, @@ -8522,7 +8522,7 @@ "shortDescription": "Minimum GPS z standard deviation, uses reported EPV if greater", "units": "m", "defaultValue": 3, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 200 }, @@ -8534,7 +8534,7 @@ "shortDescription": "Land detector xy velocity standard deviation", "units": "m/s", "defaultValue": 0.05, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 10 }, @@ -8546,7 +8546,7 @@ "shortDescription": "Land detector z standard deviation", "units": "m", "defaultValue": 0.03, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.001, "maxValue": 10 }, @@ -8558,7 +8558,7 @@ "shortDescription": "Local origin latitude for nav w/o GPS", "units": "deg", "defaultValue": 47.3977, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -90, "maxValue": 90 }, @@ -8570,7 +8570,7 @@ "shortDescription": "Lidar z offset from center of vehicle +down", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -8582,7 +8582,7 @@ "shortDescription": "Lidar z standard deviation", "units": "m", "defaultValue": 0.03, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 1 }, @@ -8594,7 +8594,7 @@ "shortDescription": "Local origin longitude for nav w/o GPS", "units": "deg", "defaultValue": 8.54559, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": -180, "maxValue": 180 }, @@ -8606,7 +8606,7 @@ "shortDescription": "Minimum landing target standard covariance, uses reported covariance if greater", "units": "m^2", "defaultValue": 0.0001, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -8618,7 +8618,7 @@ "shortDescription": "Accel bias propagation noise density", "units": "(m/s^2)/s/sqrt(Hz)", "defaultValue": 0.001, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": 0, "maxValue": 1 }, @@ -8631,7 +8631,7 @@ "longDescription": "Increase to trust measurements more. Decrease to trust model more.", "units": "m/s/sqrt(Hz)", "defaultValue": 0.1, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": 0, "maxValue": 1 }, @@ -8643,7 +8643,7 @@ "shortDescription": "Terrain random walk noise density, hilly/outdoor (0.1), flat/Indoor (0.001)", "units": "(m/s)/(sqrt(hz))", "defaultValue": 0.001, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -8656,7 +8656,7 @@ "longDescription": "Increase to trust measurements more. Decrease to trust model more.", "units": "(m/s)/s/sqrt(Hz)", "defaultValue": 0.1, - "decimalPlaces": "8", + "decimalPlaces": 8, "minValue": 0, "maxValue": 1 }, @@ -8668,7 +8668,7 @@ "shortDescription": "Sonar z offset from center of vehicle +down", "units": "m", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -8680,7 +8680,7 @@ "shortDescription": "Sonar z standard deviation", "units": "m", "defaultValue": 0.05, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 1 }, @@ -8692,7 +8692,7 @@ "shortDescription": "Terrain maximum percent grade, hilly/outdoor (100 = 45 deg), flat/Indoor (0 = 0 deg) Used to calculate increased terrain random walk nosie due to movement", "units": "%", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -8704,7 +8704,7 @@ "shortDescription": "Vicon position standard deviation", "units": "m", "defaultValue": 0.001, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.0001, "maxValue": 1 }, @@ -8717,7 +8717,7 @@ "longDescription": "Set to zero to enable automatic compensation from measurement timestamps", "units": "sec", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.1 }, @@ -8729,7 +8729,7 @@ "shortDescription": "Vision xy standard deviation", "units": "m", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 1 }, @@ -8741,7 +8741,7 @@ "shortDescription": "Vision z standard deviation", "units": "m", "defaultValue": 0.5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 100 }, @@ -8753,7 +8753,7 @@ "shortDescription": "Required velocity xy standard deviation to publish position", "units": "m/s", "defaultValue": 0.3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 1 }, @@ -8765,7 +8765,7 @@ "shortDescription": "Cut frequency for state publication", "units": "Hz", "defaultValue": 5, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 5, "maxValue": 1000 }, @@ -8777,7 +8777,7 @@ "shortDescription": "Required z standard deviation to publish altitude/ terrain", "units": "m", "defaultValue": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.3, "maxValue": 5 }, @@ -8790,7 +8790,7 @@ "longDescription": "Variance of acceleration measurement used for landing target position prediction. Higher values results in tighter following of the measurements and more lenient outlier rejection", "units": "(m/s^2)^2", "defaultValue": 10, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -8803,7 +8803,7 @@ "longDescription": "Variance of the landing target measurement from the driver. Higher values results in less agressive following of the measurement and a smoother output as well as fewer rejected measurements.", "units": "tan(rad)^2", "defaultValue": 0.005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": -3.40282e+38, "maxValue": 3.40282e+38 }, @@ -8825,7 +8825,7 @@ "description": "Stationary" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -8838,7 +8838,7 @@ "longDescription": "Initial variance of the relative landing target position in x and y direction", "units": "m^2", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.001, "maxValue": 3.40282e+38 }, @@ -8850,7 +8850,7 @@ "shortDescription": "Scale factor for sensor measurements in sensor x axis", "longDescription": "Landing target x measurements are scaled by this factor before being used", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -8862,7 +8862,7 @@ "shortDescription": "Scale factor for sensor measurements in sensor y axis", "longDescription": "Landing target y measurements are scaled by this factor before being used", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 3.40282e+38 }, @@ -8875,7 +8875,7 @@ "longDescription": "Initial variance of the relative landing target velocity in x and y direction", "units": "(m/s)^2", "defaultValue": 0.1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.001, "maxValue": 3.40282e+38 }, @@ -8930,7 +8930,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -8943,7 +8943,7 @@ "longDescription": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -8990,7 +8990,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9003,7 +9003,7 @@ "longDescription": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9017,7 +9017,7 @@ "units": "B/s", "defaultValue": 1200, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -9072,7 +9072,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9085,7 +9085,7 @@ "longDescription": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9132,7 +9132,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9145,7 +9145,7 @@ "longDescription": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9159,7 +9159,7 @@ "units": "B/s", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -9214,7 +9214,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9227,7 +9227,7 @@ "longDescription": "If enabled, forward incoming MAVLink messages to other MAVLink ports if the message is either broadcast or the target is not the autopilot. This allows for example a GCS to talk to a camera that is connected to the autopilot via MAVLink (on a different link than the GCS).", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9274,7 +9274,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9287,7 +9287,7 @@ "longDescription": "If enabled, MAVLink messages will be throttled according to `txbuf` field reported by radio_status. Requires a radio to send the mavlink message RADIO_STATUS.", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9301,7 +9301,7 @@ "units": "B/s", "defaultValue": 0, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2.14748e+09 }, @@ -9327,7 +9327,7 @@ "description": "Only multicast" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9339,7 +9339,7 @@ "shortDescription": "MAVLink component ID", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 250 }, @@ -9351,7 +9351,7 @@ "shortDescription": "Forward external setpoint messages", "longDescription": "If set to 1 incoming external setpoint messages will be directly forwarded to the controllers if in offboard control mode", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9363,7 +9363,7 @@ "shortDescription": "Parameter hash check", "longDescription": "Disabling the parameter hash check functionality will make the mavlink instance stream parameters continuously.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9375,7 +9375,7 @@ "shortDescription": "Hearbeat message forwarding", "longDescription": "The mavlink hearbeat message will not be forwarded if this parameter is set to 'disabled'. The main reason for disabling heartbeats to be forwarded is because they confuse dronekit.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9387,7 +9387,7 @@ "shortDescription": "Activate ODOMETRY loopback", "longDescription": "If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry' serving as a loopback of the received ODOMETRY messages on the Mavlink receiver.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9412,7 +9412,7 @@ "description": "Always use version 2" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9425,7 +9425,7 @@ "longDescription": "If the connected radio stops reporting RADIO_STATUS for a certain time, a warning is triggered and, if MAV_X_RADIO_CTL is enabled, the software-flow control is reset.", "units": "s", "defaultValue": 5, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 250 }, @@ -9437,7 +9437,7 @@ "shortDescription": "MAVLink SiK Radio ID", "longDescription": "When non-zero the MAVLink app will attempt to configure the SiK radio to this ID and re-set the parameter to 0. If the value is negative it will reset the complete radio config to factory defaults. Only applies if this mavlink instance is going through a SiK radio", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 240 }, @@ -9449,7 +9449,7 @@ "shortDescription": "MAVLink system ID", "defaultValue": 1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 250 }, @@ -9570,7 +9570,7 @@ "description": "Onboard ADSB peripheral" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 27 }, @@ -9582,7 +9582,7 @@ "shortDescription": "Use/Accept HIL GPS message even if not in HIL mode", "longDescription": "If set to 1 incoming HIL GPS messages are parsed.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9594,7 +9594,7 @@ "shortDescription": "Acro mode Expo factor for Roll and Pitch", "longDescription": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "defaultValue": 0.69, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -9606,7 +9606,7 @@ "shortDescription": "Acro mode Expo factor for Yaw", "longDescription": "Exponential factor for tuning the input curve shape. 0 Purely linear input curve 1 Purely cubic input curve", "defaultValue": 0.69, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -9619,7 +9619,7 @@ "units": "deg/s", "defaultValue": 720, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -9632,7 +9632,7 @@ "units": "deg/s", "defaultValue": 720, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -9644,7 +9644,7 @@ "shortDescription": "Acro mode SuperExpo factor for Roll and Pitch", "longDescription": "SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "defaultValue": 0.7, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.95 }, @@ -9656,7 +9656,7 @@ "shortDescription": "Acro mode SuperExpo factor for Yaw", "longDescription": "SuperExpo factor for refining the input curve shape tuned using MC_ACRO_EXPO_Y. 0 Pure Expo function 0.7 resonable shape enhancement for intuitive stick feel 0.95 very strong bent input curve only near maxima have effect", "defaultValue": 0.7, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.95 }, @@ -9669,7 +9669,7 @@ "units": "deg/s", "defaultValue": 540, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -9695,7 +9695,7 @@ "description": "Roll/Pitch/Yaw" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9707,7 +9707,7 @@ "shortDescription": "Battery power level scaler", "longDescription": "This compensates for voltage drop of the battery over time by attempting to normalize performance across the operating range of the battery. The copter should constantly behave as if it was fully charged with reduced max acceleration at lower battery percentages. i.e. if hover is at 0.5 throttle at 100% battery, it will still be 0.5 at 60% battery.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -9719,7 +9719,7 @@ "shortDescription": "Manual tilt input filter time constant Setting this parameter to 0 disables the filter", "units": "s", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 2 }, @@ -9732,7 +9732,7 @@ "longDescription": "Pitch rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "defaultValue": 0.003, "increment": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9744,7 +9744,7 @@ "shortDescription": "Pitch rate feedforward", "longDescription": "Improves tracking performance.", "defaultValue": 0, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9757,7 +9757,7 @@ "longDescription": "Pitch rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "defaultValue": 0.2, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9770,7 +9770,7 @@ "longDescription": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_PITCHRATE_K * (MC_PITCHRATE_P * error + MC_PITCHRATE_I * error_integral + MC_PITCHRATE_D * error_derivative) Set MC_PITCHRATE_P=1 to implement a PID in the ideal form. Set MC_PITCHRATE_K=1 to implement a PID in the parallel form.", "defaultValue": 1, "increment": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.01, "maxValue": 5 }, @@ -9784,7 +9784,7 @@ "units": "deg/s", "defaultValue": 220, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -9797,7 +9797,7 @@ "longDescription": "Pitch rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "defaultValue": 0.15, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 0.6 }, @@ -9811,7 +9811,7 @@ "units": "1/s", "defaultValue": 6.5, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 12 }, @@ -9824,7 +9824,7 @@ "longDescription": "Pitch rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large pitch moment trim changes.", "defaultValue": 0.3, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9837,7 +9837,7 @@ "longDescription": "Manual input needed in order to override attitude control rate setpoints and instead pass manual stick inputs as rate setpoints", "defaultValue": 0.8, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -9850,7 +9850,7 @@ "longDescription": "Roll rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "defaultValue": 0.003, "increment": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 0.01 }, @@ -9862,7 +9862,7 @@ "shortDescription": "Roll rate feedforward", "longDescription": "Improves tracking performance.", "defaultValue": 0, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9875,7 +9875,7 @@ "longDescription": "Roll rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "defaultValue": 0.2, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9888,7 +9888,7 @@ "longDescription": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_ROLLRATE_K * (MC_ROLLRATE_P * error + MC_ROLLRATE_I * error_integral + MC_ROLLRATE_D * error_derivative) Set MC_ROLLRATE_P=1 to implement a PID in the ideal form. Set MC_ROLLRATE_K=1 to implement a PID in the parallel form.", "defaultValue": 1, "increment": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0.01, "maxValue": 5 }, @@ -9902,7 +9902,7 @@ "units": "deg/s", "defaultValue": 220, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -9915,7 +9915,7 @@ "longDescription": "Roll rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "defaultValue": 0.15, "increment": 0.01, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.01, "maxValue": 0.5 }, @@ -9929,7 +9929,7 @@ "units": "1/s", "defaultValue": 6.5, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 12 }, @@ -9942,7 +9942,7 @@ "longDescription": "Roll rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large roll moment trim changes.", "defaultValue": 0.3, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9955,7 +9955,7 @@ "longDescription": "Yaw rate differential gain. Small values help reduce fast oscillations. If value is too big oscillations will appear again.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9968,7 +9968,7 @@ "longDescription": "Improves tracking performance.", "defaultValue": 0, "increment": 0.01, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9981,7 +9981,7 @@ "longDescription": "Yaw rate integral gain. Can be set to compensate static thrust difference or gravity center offset.", "defaultValue": 0.1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -9994,7 +9994,7 @@ "longDescription": "Global gain of the controller. This gain scales the P, I and D terms of the controller: output = MC_YAWRATE_K * (MC_YAWRATE_P * error + MC_YAWRATE_I * error_integral + MC_YAWRATE_D * error_derivative) Set MC_YAWRATE_P=1 to implement a PID in the ideal form. Set MC_YAWRATE_K=1 to implement a PID in the parallel form.", "defaultValue": 1, "increment": 0.0005, - "decimalPlaces": "4", + "decimalPlaces": 4, "minValue": 0, "maxValue": 5 }, @@ -10007,7 +10007,7 @@ "units": "deg/s", "defaultValue": 200, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 1800 }, @@ -10020,7 +10020,7 @@ "longDescription": "Yaw rate proportional gain, i.e. control output for angular speed error 1 rad/s.", "defaultValue": 0.2, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 0.6 }, @@ -10034,7 +10034,7 @@ "units": "1/s", "defaultValue": 2.8, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 5 }, @@ -10048,7 +10048,7 @@ "units": "1/s", "defaultValue": 0.4, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -10061,7 +10061,7 @@ "longDescription": "Yaw rate integrator limit. Can be set to increase the amount of integrator available to counteract disturbances or reduced to improve settling time after large yaw moment trim changes.", "defaultValue": 0.3, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -10083,7 +10083,7 @@ "description": "First Order Hold" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -10097,7 +10097,7 @@ "units": "m", "defaultValue": 900, "increment": 100, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 10000 }, @@ -10111,7 +10111,7 @@ "units": "m", "defaultValue": 900, "increment": 100, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 10000 }, @@ -10125,7 +10125,7 @@ "units": "m", "defaultValue": -1, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -1, "maxValue": 80 }, @@ -10147,7 +10147,7 @@ "description": "Enable" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -10161,7 +10161,7 @@ "units": "m", "defaultValue": 2.5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 80 }, @@ -10173,7 +10173,7 @@ "shortDescription": "Take-off waypoint required", "longDescription": "If set, the mission feasibility checker will check for a takeoff waypoint on the mission.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10186,7 +10186,7 @@ "units": "deg", "defaultValue": 12, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -10200,7 +10200,7 @@ "units": "s", "defaultValue": -1, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -1, "maxValue": 20 }, @@ -10211,7 +10211,7 @@ "category": "Standard", "shortDescription": "Test mode (Identify) of MKBLCTRL Driver", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10222,7 +10222,7 @@ "category": "Standard", "shortDescription": "Stabilize the mount (set to true for servo gimbal, false for passthrough). Does not affect MAVLINK_ROI input", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10263,7 +10263,7 @@ "description": "AUX6" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 6 }, @@ -10304,7 +10304,7 @@ "description": "AUX6" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 6 }, @@ -10345,7 +10345,7 @@ "description": "AUX6" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 6 }, @@ -10357,7 +10357,7 @@ "shortDescription": "Mavlink Component ID of the mount", "longDescription": "If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this component ID.", "defaultValue": 154, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10369,7 +10369,7 @@ "shortDescription": "Mavlink System ID of the mount", "longDescription": "If MNT_MODE_OUT is MAVLINK, mount configure/control commands will be sent with this target ID.", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10404,7 +10404,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 3 }, @@ -10426,7 +10426,7 @@ "description": "MAVLINK" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -10437,7 +10437,7 @@ "category": "Standard", "shortDescription": "Mixer value for selecting a locking mode if required for the gimbal (only in AUX output mode)", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -10448,7 +10448,7 @@ "category": "Standard", "shortDescription": "Mixer value for selecting normal mode if required by the gimbal (only in AUX output mode)", "defaultValue": -1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -10459,7 +10459,7 @@ "category": "Standard", "shortDescription": "Offset for pitch channel output in degrees", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -360, "maxValue": 360 }, @@ -10470,7 +10470,7 @@ "category": "Standard", "shortDescription": "Offset for roll channel output in degrees", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -360, "maxValue": 360 }, @@ -10481,7 +10481,7 @@ "category": "Standard", "shortDescription": "Offset for yaw channel output in degrees", "defaultValue": 0, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -360, "maxValue": 360 }, @@ -10492,7 +10492,7 @@ "category": "Standard", "shortDescription": "Range of pitch channel output in degrees (only in AUX output mode)", "defaultValue": 360, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 720 }, @@ -10503,7 +10503,7 @@ "category": "Standard", "shortDescription": "Range of roll channel output in degrees (only in AUX output mode)", "defaultValue": 360, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 720 }, @@ -10514,7 +10514,7 @@ "category": "Standard", "shortDescription": "Range of yaw channel output in degrees (only in AUX output mode)", "defaultValue": 360, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 720 }, @@ -10536,7 +10536,7 @@ "description": "Betaflight / Cleanflight" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10548,7 +10548,7 @@ "shortDescription": "Number of magnetic poles of the motors", "longDescription": "Specify the number of magnetic poles of the motors. It is required to compute the RPM value from the eRPM returned with the ESC telemetry. Either get the number from the motor spec sheet or count the magnets on the bell of the motor (not the stator magnets). Typical motors for 5 inch props have 14 poles.", "defaultValue": 14, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10561,7 +10561,7 @@ "longDescription": "Minimum time allowed for the motor input signal to pass through a range of 1000 PWM units. A value x means that the motor signal can only go from 1000 to 2000 PWM in maximum x seconds. Zero means that slew rate limiting is disabled.", "units": "s/(1000*PWM)", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -10574,7 +10574,7 @@ "units": "m/s/s", "defaultValue": 3, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 15 }, @@ -10588,7 +10588,7 @@ "units": "m/s/s", "defaultValue": 3, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 15 }, @@ -10602,7 +10602,7 @@ "units": "m/s/s", "defaultValue": 5, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 15 }, @@ -10615,7 +10615,7 @@ "units": "m/s/s", "defaultValue": 4, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 15 }, @@ -10641,7 +10641,7 @@ "description": "Terrain hold" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -10655,7 +10655,7 @@ "units": "m/s/s", "defaultValue": 5, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.5, "maxValue": 10 }, @@ -10666,7 +10666,7 @@ "category": "Standard", "shortDescription": "Deadzone of sticks where position hold is enabled", "defaultValue": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -10678,7 +10678,7 @@ "shortDescription": "Maximum horizontal velocity for which position hold is enabled (use 0 to disable check)", "units": "m/s", "defaultValue": 0.8, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3 }, @@ -10690,7 +10690,7 @@ "shortDescription": "Maximum vertical velocity for which position hold is enabled (use 0 to disable check)", "units": "m/s", "defaultValue": 0.6, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 3 }, @@ -10704,7 +10704,7 @@ "units": "m/s/s/s", "defaultValue": 4, "increment": 1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 1, "maxValue": 80 }, @@ -10718,7 +10718,7 @@ "units": "m/s/s/s", "defaultValue": 8, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.5, "maxValue": 500 }, @@ -10732,7 +10732,7 @@ "units": "m/s/s/s", "defaultValue": 8, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 30 }, @@ -10745,7 +10745,7 @@ "longDescription": "Below this altitude: - descending velocity gets limited to a value between \"MPC_Z_VEL_MAX\" and \"MPC_LAND_SPEED\" - horizontal velocity gets limited to a value between \"MPC_VEL_MANUAL\" and \"MPC_LAND_VEL_XY\" for a smooth descent and landing experience. Value needs to be higher than \"MPC_LAND_ALT2\"", "units": "m", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 122 }, @@ -10758,7 +10758,7 @@ "longDescription": "Below this altitude descending and horizontal velocities get limited to \"MPC_LAND_SPEED\" and \"MPC_LAND_VEL_XY\", respectively. Value needs to be lower than \"MPC_LAND_ALT1\"", "units": "m", "defaultValue": 2, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 122 }, @@ -10779,7 +10779,7 @@ "description": "User assisted descent speed" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 1 }, @@ -10791,7 +10791,7 @@ "shortDescription": "Landing descend rate", "units": "m/s", "defaultValue": 0.7, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.6, "maxValue": 3.40282e+38 }, @@ -10803,7 +10803,7 @@ "shortDescription": "Maximum horizontal position mode velocity when close to ground/home altitude Set the value higher than the otherwise expected maximum to disable any slowdown", "units": "m/s", "defaultValue": 10, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 3.40282e+38 }, @@ -10817,7 +10817,7 @@ "units": "norm", "defaultValue": 0.08, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -10829,7 +10829,7 @@ "shortDescription": "Maximal tilt angle in manual or altitude mode", "units": "deg", "defaultValue": 35, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 90 }, @@ -10841,7 +10841,7 @@ "shortDescription": "Max manual yaw rate", "units": "deg/s", "defaultValue": 150, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 400 }, @@ -10853,7 +10853,7 @@ "shortDescription": "Manual yaw rate input filter time constant Setting this parameter to 0 disables the filter", "units": "s", "defaultValue": 0.08, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 5 }, @@ -10879,7 +10879,7 @@ "description": "Smooth position control (Jerk optimized)" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10892,7 +10892,7 @@ "longDescription": "For altitude controlled modes the time from arming the motors until a takeoff is possible gets forced to be at least MPC_SPOOLUP_TIME seconds to ensure the motors and propellers can sppol up and reach idle speed before getting commanded to spin faster. This delay is particularly useful for vehicles with slow motor spin-up e.g. because of large propellers.", "units": "s", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 10 }, @@ -10914,7 +10914,7 @@ "description": "No Rescale" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -10928,7 +10928,7 @@ "units": "norm", "defaultValue": 0.5, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.1, "maxValue": 0.8 }, @@ -10942,7 +10942,7 @@ "units": "norm", "defaultValue": 1, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -10956,7 +10956,7 @@ "units": "norm", "defaultValue": 0.12, "increment": 0.01, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0.05, "maxValue": 1 }, @@ -10969,7 +10969,7 @@ "longDescription": "Limits maximum tilt in AUTO and POSCTRL modes during flight.", "units": "deg", "defaultValue": 45, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 20, "maxValue": 89 }, @@ -10982,7 +10982,7 @@ "longDescription": "Limits maximum tilt angle on landing.", "units": "deg", "defaultValue": 12, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 10, "maxValue": 89 }, @@ -10994,7 +10994,7 @@ "shortDescription": "Position control smooth takeoff ramp time constant", "longDescription": "Increasing this value will make automatic and manual takeoff slower. If it's too slow the drone might scratch the ground and tip over. A time constant of 0 disables the ramp", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 5 }, @@ -11006,7 +11006,7 @@ "shortDescription": "Takeoff climb rate", "units": "m/s", "defaultValue": 1.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 1, "maxValue": 5 }, @@ -11018,7 +11018,7 @@ "shortDescription": "Hover thrust source selector", "longDescription": "Set false to use the fixed parameter MPC_THR_HOVER Set true to use the value computed by the hover thrust estimator", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11030,7 +11030,7 @@ "shortDescription": "Low pass filter cut freq. for numerical velocity derivative", "units": "Hz", "defaultValue": 5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -11043,7 +11043,7 @@ "units": "m/s", "defaultValue": 10, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 3, "maxValue": 20 }, @@ -11057,7 +11057,7 @@ "units": "m/s", "defaultValue": 5, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 3, "maxValue": 20 }, @@ -11069,7 +11069,7 @@ "shortDescription": "Manual position control stick exponential curve sensitivity", "longDescription": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "defaultValue": 0.6, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -11080,7 +11080,7 @@ "category": "Standard", "shortDescription": "Proportional gain for horizontal position error", "defaultValue": 0.95, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 2 }, @@ -11091,7 +11091,7 @@ "category": "Standard", "shortDescription": "Proportional gain for horizontal trajectory position error", "defaultValue": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.1, "maxValue": 1 }, @@ -11103,7 +11103,7 @@ "shortDescription": "Differential gain for horizontal velocity error. Small values help reduce fast oscillations. If value is too big oscillations will appear again", "longDescription": "defined as correction acceleration in m/s^2 per m/s^2 velocity derivative", "defaultValue": 0.2, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.1, "maxValue": 2 }, @@ -11115,7 +11115,7 @@ "shortDescription": "Integral gain for horizontal velocity error", "longDescription": "defined as correction acceleration in m/s^2 per m velocity integral Non-zero value allows to eliminate steady state errors in the presence of disturbances like wind.", "defaultValue": 0.4, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 60 }, @@ -11129,7 +11129,7 @@ "units": "m/s", "defaultValue": 12, "increment": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 20 }, @@ -11141,7 +11141,7 @@ "shortDescription": "Proportional gain for horizontal velocity error", "longDescription": "defined as correction acceleration in m/s^2 per m/s velocity error", "defaultValue": 1.8, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 1.2, "maxValue": 3 }, @@ -11155,7 +11155,7 @@ "units": "deg/s", "defaultValue": 45, "increment": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 360 }, @@ -11167,7 +11167,7 @@ "shortDescription": "Manual control stick yaw rotation exponential curve", "longDescription": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "defaultValue": 0.6, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -11201,7 +11201,7 @@ "description": "towards waypoint (yaw first)" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 4 }, @@ -11213,7 +11213,7 @@ "shortDescription": "Manual control stick vertical exponential curve", "longDescription": "The higher the value the less sensitivity the stick has around zero while still reaching the maximum value with full stick deflection. 0 Purely linear input curve (default) 1 Purely cubic input curve", "defaultValue": 0.6, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -11224,7 +11224,7 @@ "category": "Standard", "shortDescription": "Proportional gain for vertical position error", "defaultValue": 1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1.5 }, @@ -11236,7 +11236,7 @@ "shortDescription": "Differential gain for vertical velocity error", "longDescription": "defined as correction acceleration in m/s^2 per m/s^2 velocity derivative", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2 }, @@ -11248,7 +11248,7 @@ "shortDescription": "Integral gain for vertical velocity error", "longDescription": "defined as correction acceleration in m/s^2 per m velocity integral Non zero value allows hovering thrust estimation on stabilized or autonomous takeoff.", "defaultValue": 2, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.2, "maxValue": 2 }, @@ -11261,7 +11261,7 @@ "longDescription": "Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).", "units": "m/s", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0.5, "maxValue": 4 }, @@ -11274,7 +11274,7 @@ "longDescription": "Maximum vertical velocity in AUTO mode and endpoint for stabilized modes (ALTCTRL, POSCTRL).", "units": "m/s", "defaultValue": 3, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.5, "maxValue": 8 }, @@ -11286,7 +11286,7 @@ "shortDescription": "Proportional gain for vertical velocity error", "longDescription": "defined as correction acceleration in m/s^2 per m/s velocity error", "defaultValue": 4, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 2, "maxValue": 8 }, @@ -11300,7 +11300,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.05, "maxValue": 200 }, @@ -11314,7 +11314,7 @@ "units": "m", "defaultValue": 600, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -50, "maxValue": 3.40282e+38 }, @@ -11327,7 +11327,7 @@ "longDescription": "Latitude of airfield home waypoint", "units": "deg * 1e7", "defaultValue": -2.65848e+08, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -9e+08, "maxValue": 9e+08 }, @@ -11340,7 +11340,7 @@ "longDescription": "Longitude of airfield home waypoint", "units": "deg * 1e7", "defaultValue": 1.51842e+09, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1.8e+09, "maxValue": 1.8e+09 }, @@ -11378,7 +11378,7 @@ "description": "Lockdown" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11389,7 +11389,7 @@ "category": "Standard", "shortDescription": "Force VTOL mode takeoff and land", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11402,7 +11402,7 @@ "longDescription": "The distance in meters to follow the target at", "units": "meters", "defaultValue": 8, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 3.40282e+38 }, @@ -11415,7 +11415,7 @@ "longDescription": "The side to follow the target from (front right = 0, behind = 1, front = 2, front left = 3)", "units": "n/a", "defaultValue": 1, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 3 }, @@ -11427,7 +11427,7 @@ "shortDescription": "Dynamic filtering algorithm responsiveness to target movement lower numbers increase the responsiveness to changing long lat but also ignore less noise", "units": "n/a", "defaultValue": 0.5, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -11440,7 +11440,7 @@ "longDescription": "Altitude acceptance used for the last waypoint before a fixed-wing landing. This is usually smaller than the standard vertical acceptance because close to the ground higher accuracy is required.", "units": "m", "defaultValue": 5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.05, "maxValue": 200 }, @@ -11454,7 +11454,7 @@ "units": "m", "defaultValue": 10, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.05, "maxValue": 200 }, @@ -11468,7 +11468,7 @@ "units": "s", "defaultValue": 0, "increment": 1, - "decimalPlaces": "0", + "decimalPlaces": 0, "minValue": 0, "maxValue": 3600 }, @@ -11482,7 +11482,7 @@ "units": "deg", "defaultValue": 0, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": -30, "maxValue": 30 }, @@ -11496,7 +11496,7 @@ "units": "deg", "defaultValue": 15, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 30 }, @@ -11510,7 +11510,7 @@ "units": "norm", "defaultValue": 0, "increment": 0.05, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 1 }, @@ -11524,7 +11524,7 @@ "units": "m", "defaultValue": 50, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 25, "maxValue": 1000 }, @@ -11538,7 +11538,7 @@ "units": "m", "defaultValue": 0.8, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0.05, "maxValue": 200 }, @@ -11551,7 +11551,7 @@ "longDescription": "The minimum height in meters relative to home for following a target", "units": "meters", "defaultValue": 8, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 8, "maxValue": 3.40282e+38 }, @@ -11589,7 +11589,7 @@ "description": "Lockdown" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11623,7 +11623,7 @@ "description": "Position Hold mode" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11636,7 +11636,7 @@ "longDescription": "Defines the Radius where NAV TRAFFIC AVOID is Called For Manned Aviation", "units": "m", "defaultValue": 500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 500, "maxValue": 3.40282e+38 }, @@ -11649,7 +11649,7 @@ "longDescription": "Defines the Radius where NAV TRAFFIC AVOID is Called For Unmanned Aviation", "units": "m", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 10, "maxValue": 500 }, @@ -11676,7 +11676,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11698,7 +11698,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11711,7 +11711,7 @@ "longDescription": "Nmumber of signals per rotation of actuator", "defaultValue": 2, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 2.14748e+09 }, @@ -11724,7 +11724,7 @@ "units": "us", "defaultValue": 1e+06, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11737,7 +11737,7 @@ "longDescription": "Internal device counter is reset to 0 when overun this value, counter is able to store upto 6 digits reset of counter takes some time - measurement with reset has worse accurancy. 0 means reset counter after every measurement.", "defaultValue": 500000, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -11751,7 +11751,7 @@ "units": "s", "defaultValue": 5, "increment": 0.5, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 50 }, @@ -11765,7 +11765,7 @@ "units": "m", "defaultValue": 0.1, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -11779,7 +11779,7 @@ "units": "m", "defaultValue": 0.2, "increment": 0.1, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": 0, "maxValue": 10 }, @@ -11791,7 +11791,7 @@ "shortDescription": "Maximum number of search attempts", "longDescription": "Maximum number of times to seach for the landing target if it is lost during the precision landing.", "defaultValue": 3, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -11805,7 +11805,7 @@ "units": "m", "defaultValue": 10, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 100 }, @@ -11819,7 +11819,7 @@ "units": "s", "defaultValue": 10, "increment": 0.1, - "decimalPlaces": "1", + "decimalPlaces": 1, "minValue": 0, "maxValue": 100 }, @@ -11833,7 +11833,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11847,7 +11847,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11861,7 +11861,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11875,7 +11875,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11889,7 +11889,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11903,7 +11903,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11917,7 +11917,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11931,7 +11931,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11945,7 +11945,7 @@ "units": "us", "defaultValue": 1500, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2200 }, @@ -11959,7 +11959,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11973,7 +11973,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -11987,7 +11987,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12001,7 +12001,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12015,7 +12015,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12029,7 +12029,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12043,7 +12043,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12057,7 +12057,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12071,7 +12071,7 @@ "units": "us", "defaultValue": 2000, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1600, "maxValue": 2200 }, @@ -12085,7 +12085,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12099,7 +12099,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12113,7 +12113,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12127,7 +12127,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12141,7 +12141,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12155,7 +12155,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12169,7 +12169,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12183,7 +12183,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12197,7 +12197,7 @@ "units": "us", "defaultValue": 1000, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1400 }, @@ -12211,7 +12211,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12225,7 +12225,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12239,7 +12239,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12253,7 +12253,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12267,7 +12267,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12281,7 +12281,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12295,7 +12295,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12309,7 +12309,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12323,7 +12323,7 @@ "units": "Hz", "defaultValue": 50, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2000 }, @@ -12335,7 +12335,7 @@ "shortDescription": "Invert direction of auxiliary output channel 1", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12347,7 +12347,7 @@ "shortDescription": "Invert direction of auxiliary output channel 2", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12359,7 +12359,7 @@ "shortDescription": "Invert direction of auxiliary output channel 3", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12371,7 +12371,7 @@ "shortDescription": "Invert direction of auxiliary output channel 4", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12383,7 +12383,7 @@ "shortDescription": "Invert direction of auxiliary output channel 5", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12395,7 +12395,7 @@ "shortDescription": "Invert direction of auxiliary output channel 6", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12407,7 +12407,7 @@ "shortDescription": "Invert direction of auxiliary output channel 7", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12419,7 +12419,7 @@ "shortDescription": "Invert direction of auxiliary output channel 8", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -12431,7 +12431,7 @@ "shortDescription": "Trim value for auxiliary output channel 1", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12443,7 +12443,7 @@ "shortDescription": "Trim value for auxiliary output channel 2", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12455,7 +12455,7 @@ "shortDescription": "Trim value for auxiliary output channel 3", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12467,7 +12467,7 @@ "shortDescription": "Trim value for auxiliary output channel 4", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12479,7 +12479,7 @@ "shortDescription": "Trim value for auxiliary output channel 5", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12491,7 +12491,7 @@ "shortDescription": "Trim value for auxiliary output channel 6", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12503,7 +12503,7 @@ "shortDescription": "Trim value for auxiliary output channel 7", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12515,7 +12515,7 @@ "shortDescription": "Trim value for auxiliary output channel 8", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -12529,7 +12529,7 @@ "units": "us", "defaultValue": 900, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2200 }, @@ -12543,7 +12543,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12557,7 +12557,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12571,7 +12571,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12585,7 +12585,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12599,7 +12599,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12613,7 +12613,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12627,7 +12627,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12641,7 +12641,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12655,7 +12655,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12669,7 +12669,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12683,7 +12683,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12697,7 +12697,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12711,7 +12711,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12725,7 +12725,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12739,7 +12739,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12753,7 +12753,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12767,7 +12767,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12781,7 +12781,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12795,7 +12795,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12809,7 +12809,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12823,7 +12823,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12837,7 +12837,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12851,7 +12851,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12865,7 +12865,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12879,7 +12879,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12893,7 +12893,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12907,7 +12907,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12921,7 +12921,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12935,7 +12935,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12949,7 +12949,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12963,7 +12963,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12977,7 +12977,7 @@ "units": "us", "defaultValue": -1, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2200 }, @@ -12989,7 +12989,7 @@ "shortDescription": "Invert direction of main output channel 1", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13001,7 +13001,7 @@ "shortDescription": "Invert direction of main output channel 2", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13013,7 +13013,7 @@ "shortDescription": "Invert direction of main output channel 3", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13025,7 +13025,7 @@ "shortDescription": "Invert direction of main output channel 4", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13037,7 +13037,7 @@ "shortDescription": "Invert direction of main output channel 5", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13049,7 +13049,7 @@ "shortDescription": "Invert direction of main output channel 6", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13061,7 +13061,7 @@ "shortDescription": "Invert direction of main output channel 7", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13073,7 +13073,7 @@ "shortDescription": "Invert direction of main output channel 8", "longDescription": "Enable to invert the channel. Warning: Use this parameter when connected to a servo only. For a brushless motor, invert manually two phases to reverse the direction.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13085,7 +13085,7 @@ "shortDescription": "Trim value for main output channel 1", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13097,7 +13097,7 @@ "shortDescription": "Trim value for main output channel 2", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13109,7 +13109,7 @@ "shortDescription": "Trim value for main output channel 3", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13121,7 +13121,7 @@ "shortDescription": "Trim value for main output channel 4", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13133,7 +13133,7 @@ "shortDescription": "Trim value for main output channel 5", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13145,7 +13145,7 @@ "shortDescription": "Trim value for main output channel 6", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13157,7 +13157,7 @@ "shortDescription": "Trim value for main output channel 7", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13169,7 +13169,7 @@ "shortDescription": "Trim value for main output channel 8", "longDescription": "Set to normalized offset", "defaultValue": 0, - "decimalPlaces": "2", + "decimalPlaces": 2, "minValue": -0.2, "maxValue": 0.2 }, @@ -13183,7 +13183,7 @@ "units": "us", "defaultValue": 2000, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1600, "maxValue": 2200 }, @@ -13197,7 +13197,7 @@ "units": "us", "defaultValue": 1000, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1400 }, @@ -13211,7 +13211,7 @@ "units": "Hz", "defaultValue": 400, "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 2000 }, @@ -13223,7 +13223,7 @@ "shortDescription": "S.BUS out", "longDescription": "Set to 1 to enable S.BUS version 1 output instead of RSSI.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13269,7 +13269,7 @@ "description": "0x87" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 128, "maxValue": 135 }, @@ -13316,7 +13316,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 2400, "maxValue": 460800 }, @@ -13328,7 +13328,7 @@ "shortDescription": "Encoder counts per revolution", "longDescription": "Number of encoder counts for one revolution. The roboclaw treats analog encoders (potentiometers) as having 2047 counts per rev. The default value of 1200 corresponds to the default configuration of the Aion R1 rover.", "defaultValue": 1200, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 2.14748e+09 }, @@ -13341,7 +13341,7 @@ "longDescription": "How long to wait, in Milliseconds, between reading wheel encoder values over Uart from the Roboclaw", "units": "ms", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 1000 }, @@ -13396,7 +13396,7 @@ } ], "rebootRequired": true, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -2.14748e+09, "maxValue": 2.14748e+09 }, @@ -13409,7 +13409,7 @@ "longDescription": "How long to wait, in Milliseconds, between writing actuator controls over Uart to the Roboclaw", "units": "ms", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1, "maxValue": 1000 }, @@ -13421,7 +13421,7 @@ "shortDescription": "RC channel 10 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13434,7 +13434,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13447,7 +13447,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13469,7 +13469,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13482,7 +13482,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13494,7 +13494,7 @@ "shortDescription": "RC channel 11 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13507,7 +13507,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13520,7 +13520,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13542,7 +13542,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13555,7 +13555,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13567,7 +13567,7 @@ "shortDescription": "RC channel 12 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13580,7 +13580,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13593,7 +13593,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13615,7 +13615,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13628,7 +13628,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13640,7 +13640,7 @@ "shortDescription": "RC channel 13 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13653,7 +13653,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13666,7 +13666,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13688,7 +13688,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13701,7 +13701,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13713,7 +13713,7 @@ "shortDescription": "RC channel 14 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13726,7 +13726,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13739,7 +13739,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13761,7 +13761,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13774,7 +13774,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13786,7 +13786,7 @@ "shortDescription": "RC channel 15 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13799,7 +13799,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13812,7 +13812,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13834,7 +13834,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13847,7 +13847,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13859,7 +13859,7 @@ "shortDescription": "RC channel 16 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13872,7 +13872,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13885,7 +13885,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13907,7 +13907,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13920,7 +13920,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -13932,7 +13932,7 @@ "shortDescription": "RC channel 17 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -13945,7 +13945,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -13958,7 +13958,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -13980,7 +13980,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -13993,7 +13993,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14005,7 +14005,7 @@ "shortDescription": "RC channel 18 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14018,7 +14018,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14031,7 +14031,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14053,7 +14053,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14066,7 +14066,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14079,7 +14079,7 @@ "longDescription": "The +- range of this value around the trim value will be considered as zero.", "units": "us", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14092,7 +14092,7 @@ "longDescription": "Maximum value for RC channel 1", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14105,7 +14105,7 @@ "longDescription": "Minimum value for RC channel 1", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14127,7 +14127,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14140,7 +14140,7 @@ "longDescription": "Mid point value (same as min for throttle)", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14153,7 +14153,7 @@ "longDescription": "The +- range of this value around the trim value will be considered as zero.", "units": "us", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14166,7 +14166,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14179,7 +14179,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14201,7 +14201,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14214,7 +14214,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14227,7 +14227,7 @@ "longDescription": "The +- range of this value around the trim value will be considered as zero.", "units": "us", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14240,7 +14240,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14253,7 +14253,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14275,7 +14275,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14288,7 +14288,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14301,7 +14301,7 @@ "longDescription": "The +- range of this value around the trim value will be considered as zero.", "units": "us", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14314,7 +14314,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14327,7 +14327,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14349,7 +14349,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14362,7 +14362,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14374,7 +14374,7 @@ "shortDescription": "RC channel 5 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14387,7 +14387,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14400,7 +14400,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14422,7 +14422,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14435,7 +14435,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14447,7 +14447,7 @@ "shortDescription": "RC channel 6 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14460,7 +14460,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14473,7 +14473,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14495,7 +14495,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14508,7 +14508,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14520,7 +14520,7 @@ "shortDescription": "RC channel 7 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14533,7 +14533,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14546,7 +14546,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14568,7 +14568,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14581,7 +14581,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14593,7 +14593,7 @@ "shortDescription": "RC channel 8 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 10, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14606,7 +14606,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14619,7 +14619,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14641,7 +14641,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14654,7 +14654,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14666,7 +14666,7 @@ "shortDescription": "RC channel 9 dead zone", "longDescription": "The +- range of this value around the trim value will be considered as zero.", "defaultValue": 0, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 100 }, @@ -14679,7 +14679,7 @@ "longDescription": "Maximum value for this channel.", "units": "us", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 1500, "maxValue": 2200 }, @@ -14692,7 +14692,7 @@ "longDescription": "Minimum value for this channel.", "units": "us", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 1500 }, @@ -14714,7 +14714,7 @@ "description": "Normal" } ], - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": -1, "maxValue": 1 }, @@ -14727,7 +14727,7 @@ "longDescription": "Mid point value (has to be set to the same as min for throttle channel).", "units": "us", "defaultValue": 1500, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 800, "maxValue": 2200 }, @@ -14739,7 +14739,7 @@ "shortDescription": "Threshold for selecting acro mode", "longDescription": "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 channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channelth negative : true when channel 0", "defaultValue": 1000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2000 }, @@ -17660,7 +17660,7 @@ "shortDescription": "Min input value for RSSI reading", "longDescription": "Only used if RC_RSSI_PWM_CHAN > 0", "defaultValue": 2000, - "decimalPlaces": "3", + "decimalPlaces": 3, "minValue": 0, "maxValue": 2000 }, @@ -17672,7 +17672,7 @@ "shortDescription": "Threshold for the stabilize switch", "longDescription": "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 channelth negative : true when channel