diff --git a/qgcresources.qrc b/qgcresources.qrc index 3a748fd40a30c9c6e75d9fbff7a01c7286ad220e..cc3b28fba4f74d078fdc496b3989fc31b6bc950f 100644 --- a/qgcresources.qrc +++ b/qgcresources.qrc @@ -209,4 +209,7 @@ src/AutoPilotPlugins/PX4/ParameterFactMetaData.xml + + src/FirmwarePlugin/APM/apm.pdef.xml + diff --git a/src/FactSystem/FactMetaData.cc b/src/FactSystem/FactMetaData.cc index 08dba2d0280363accbef398343d2bb05dd30aa95..a1c9efa6810083e11f266dfbaf29f417f0e0aab8 100644 --- a/src/FactSystem/FactMetaData.cc +++ b/src/FactSystem/FactMetaData.cc @@ -121,7 +121,9 @@ void FactMetaData::setMin(const QVariant& min) _min = min; _minIsDefaultForType = false; } else { - qWarning() << "Attempt to set min below allowable value"; + qWarning() << "Attempt to set min below allowable value for fact: " << name() + << ", value attempted: " << min + << ", type: " << type() << ", min for type: " << _minForType(); _min = _minForType(); } } @@ -189,7 +191,7 @@ QVariant FactMetaData::_maxForType(void) const bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, QVariant& typedValue, QString& errorString) { - bool convertOk; + bool convertOk = false; errorString.clear(); @@ -236,7 +238,7 @@ bool FactMetaData::convertAndValidate(const QVariant& value, bool convertOnly, Q } if (!convertOk) { - errorString = "Invalid number"; + errorString += "Invalid number"; } return convertOk && errorString.isEmpty(); diff --git a/src/FactSystem/ParameterLoader.cc b/src/FactSystem/ParameterLoader.cc index 9933cab4368c04baba5eb82080139c5abdbb4165..587df5949b2af58f5ce0daacc185d3e9234bc3cd 100644 --- a/src/FactSystem/ParameterLoader.cc +++ b/src/FactSystem/ParameterLoader.cc @@ -254,7 +254,7 @@ void ParameterLoader::_parameterUpdate(int uasId, int componentId, QString param fact->_containerSetRawValue(value); if (setMetaData) { - _vehicle->firmwarePlugin()->addMetaDataToFact(fact); + _vehicle->firmwarePlugin()->addMetaDataToFact(fact, _vehicle->vehicleType()); } _dataMutex.unlock(); diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index fb646a506be1c1d3c30825a9beea052f3f360e1d..37184ecb453f7b332e0aa5a7a74e32586da81b42 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -405,11 +405,12 @@ bool APMFirmwarePlugin::sendHomePositionToVehicle(void) return true; } -void APMFirmwarePlugin::addMetaDataToFact(Fact* fact) +void APMFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { - _parameterMetaData.addMetaDataToFact(fact); + _parameterMetaData.addMetaDataToFact(fact, vehicleType); } + QList APMFirmwarePlugin::supportedMissionCommands(void) { QList list; diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h index a092f61cd3eb54a29c2830978c5176e34c738bd2..2e0ce6be125e038c614ab0af403d1720b7f30e04 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.h @@ -89,7 +89,7 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual void addMetaDataToFact(Fact* fact); + virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } virtual QList supportedMissionCommands(void); diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.cc b/src/FirmwarePlugin/APM/APMParameterMetaData.cc index 2ab725937a32a467e74f34dedd4cce0d47af0312..49c1bb853bd098e067a2d18704597e9e060c3ce4 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.cc +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.cc @@ -35,8 +35,8 @@ QGC_LOGGING_CATEGORY(APMParameterMetaDataLog, "APMParameterMetaDataLog") -bool APMParameterMetaData::_parameterMetaDataLoaded = false; -QMap APMParameterMetaData::_mapParameterName2FactMetaData; +bool APMParameterMetaData::_parameterMetaDataLoaded = false; +QMap APMParameterMetaData::_vehicleTypeToParametersMap; APMParameterMetaData::APMParameterMetaData(QObject* parent) : QObject(parent) @@ -49,7 +49,8 @@ APMParameterMetaData::APMParameterMetaData(QObject* parent) : /// @param type Type for Fact which dictates the QVariant type as well /// @param convertOk Returned: true: conversion success, false: conversion failure /// @return Returns the correctly type QVariant -QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk) +QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, + FactMetaData::ValueType_t type, bool* convertOk) { QVariant var(string); @@ -78,29 +79,384 @@ QVariant APMParameterMetaData::_stringToTypedVariant(const QString& string, Fact return var; } +QString APMParameterMetaData::mavTypeToString(MAV_TYPE vehicleTypeEnum) +{ + QString vehicleName; + + switch(vehicleTypeEnum) { + case MAV_TYPE_FIXED_WING: + vehicleName = "ArduPlane"; + break; + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_SUBMARINE: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + vehicleName = "ArduCopter"; + break; + case MAV_TYPE_ANTENNA_TRACKER: + vehicleName = "Antenna Tracker"; + case MAV_TYPE_GENERIC: + case MAV_TYPE_GCS: + case MAV_TYPE_AIRSHIP: + case MAV_TYPE_FREE_BALLOON: + case MAV_TYPE_ROCKET: + break; + case MAV_TYPE_GROUND_ROVER: + case MAV_TYPE_SURFACE_BOAT: + vehicleName = "ArduRover"; + break; + case MAV_TYPE_FLAPPING_WING: + case MAV_TYPE_KITE: + case MAV_TYPE_ONBOARD_CONTROLLER: + case MAV_TYPE_VTOL_DUOROTOR: + case MAV_TYPE_VTOL_QUADROTOR: + case MAV_TYPE_VTOL_TILTROTOR: + case MAV_TYPE_VTOL_RESERVED2: + case MAV_TYPE_VTOL_RESERVED3: + case MAV_TYPE_VTOL_RESERVED4: + case MAV_TYPE_VTOL_RESERVED5: + case MAV_TYPE_GIMBAL: + case MAV_TYPE_ENUM_END: + default: + break; + } + return vehicleName; +} + /// Load Parameter Fact meta data /// /// The meta data comes from firmware parameters.xml file. -void APMParameterMetaData::_loadParameterFactMetaData(void) +void APMParameterMetaData::_loadParameterFactMetaData() { if (_parameterMetaDataLoaded) { return; } _parameterMetaDataLoaded = true; - // FIXME: NYI + QRegExp parameterCategories = QRegExp("ArduCopter|ArduPlane|APMrover2|AntennaTracker"); + QString currentCategory; + + QString parameterFilename; + + // Fixme:: always picking up the bundled xml, we would like to update it from web + // just not sure right now as the xml is in bad shape. + if (parameterFilename.isEmpty() || !QFile(parameterFilename).exists()) { + parameterFilename = ":/FirmwarePlugin/APM/apm.pdef.xml"; + } + + qCDebug(APMParameterMetaDataLog) << "Loading parameter meta data:" << parameterFilename; + + QFile xmlFile(parameterFilename); + Q_ASSERT(xmlFile.exists()); + + bool success = xmlFile.open(QIODevice::ReadOnly); + Q_UNUSED(success); + Q_ASSERT(success); + + QXmlStreamReader xml(xmlFile.readAll()); + xmlFile.close(); + if (xml.hasError()) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, reading failed: " << xml.errorString(); + return; + } + + QString errorString; + bool badMetaData = true; + QStack xmlState; + APMFactMetaDataRaw* rawMetaData = NULL; + + xmlState.push(XmlStateNone); + + QMap groupMembers; //used to remove groups with single item + + while (!xml.atEnd()) { + if (xml.isStartElement()) { + QString elementName = xml.name().toString(); + + if (elementName.isEmpty()) { + // skip empty elements + } else if (elementName == "paramfile") { + if (xmlState.top() != XmlStateNone) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, paramfile matched"; + } + xmlState.push(XmlstateParamFileFound); + // we don't really do anything with this element + } else if (elementName == "vehicles") { + if (xmlState.top() != XmlstateParamFileFound) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, vehicles matched"; + return; + } + xmlState.push(XmlStateFoundVehicles); + } else if (elementName == "libraries") { + if (xmlState.top() != XmlstateParamFileFound) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, libraries matched"; + return; + } + currentCategory = "libraries"; + xmlState.push(XmlStateFoundLibraries); + } else if (elementName == "parameters") { + if (xmlState.top() != XmlStateFoundVehicles && xmlState.top() != XmlStateFoundLibraries) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameters matched" + << "but we don't have proper vehicle or libraries yet"; + return; + } + + if (xml.attributes().hasAttribute("name")) { + // we will handle metadata only for specific MAV_TYPEs and libraries + const QString nameValue = xml.attributes().value("name").toString(); + if (nameValue.contains(parameterCategories)) { + xmlState.push(XmlStateFoundParameters); + currentCategory = nameValue; + } else if(xmlState.top() == XmlStateFoundLibraries) { + // we handle all libraries section under the same category libraries + // so not setting currentCategory + xmlState.push(XmlStateFoundParameters); + } else { + qCDebug(APMParameterMetaDataLog) << "not interested in this block of parameters skip"; + if (skipXMLBlock(xml, "parameters")) { + qCWarning(APMParameterMetaDataLog) << "something wrong with the xml, skip of the xml failed"; + return; + } + xml.readNext(); + continue; + } + } + } else if (elementName == "param") { + if (xmlState.top() != XmlStateFoundParameters) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, element param matched" + << "while we are not yet in parameters"; + return; + } + xmlState.push(XmlStateFoundParameter); + + if (!xml.attributes().hasAttribute("name")) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, parameter attribute name missing"; + return; + } + + QString name = xml.attributes().value("name").toString(); + if (name.contains(':')) { + name = name.split(':').last(); + } + QString group = name.split('_').first(); + group = group.remove(QRegExp("[0-9]*$")); // remove any numbers from the end + + QString shortDescription = xml.attributes().value("humanName").toString(); + QString longDescription = xml.attributes().value("docmentation").toString(); + QString userLevel = xml.attributes().value("user").toString(); + + qCDebug(APMParameterMetaDataLog) << "Found parameter name:" << name + << "short Desc:" << shortDescription + << "longDescription:" << longDescription + << "user level: " << userLevel + << "group: " << group; + + Q_ASSERT(!rawMetaData); + rawMetaData = new APMFactMetaDataRaw(); + if (_vehicleTypeToParametersMap[currentCategory].contains(name)) { + // We can't trust the meta dafa since we have dups + qCWarning(APMParameterMetaDataLog) << "Duplicate parameter found:" << name; + badMetaData = true; + } else { + qCDebug(APMParameterMetaDataLog) << "inserting metadata for field" << name; + _vehicleTypeToParametersMap[currentCategory][name] = rawMetaData; + rawMetaData->name = name; + rawMetaData->group = group; + rawMetaData->shortDescription = shortDescription; + rawMetaData->longDescription = longDescription; + + groupMembers[group] << name; + } - // Static meta data should load all MAV_TYPEs from single meta data file in such a way that the loader - // has multiple sets of static meta data + } else { + // We should be getting meta data now + if (xmlState.top() != XmlStateFoundParameter) { + qCWarning(APMParameterMetaDataLog) << "Badly formed XML, while reading parameter fields wrong state"; + return; + } + if (!badMetaData) { + if (!parseParameterAttributes(xml, rawMetaData)) { + qCDebug(APMParameterMetaDataLog) << "Badly formed XML, failed to read parameter attributes"; + return; + } + continue; + } + } + } else if (xml.isEndElement()) { + QString elementName = xml.name().toString(); + + if (elementName == "param" && xmlState.top() == XmlStateFoundParameter) { + // Done loading this parameter + // Reset for next parameter + qCDebug(APMParameterMetaDataLog) << "done loading parameter"; + rawMetaData = NULL; + badMetaData = false; + xmlState.pop(); + } else if (elementName == "parameters") { + qCDebug(APMParameterMetaDataLog) << "end of parameters for category: " << currentCategory; + correctGroupMemberships(_vehicleTypeToParametersMap[currentCategory], groupMembers); + groupMembers.clear(); + xmlState.pop(); + } else if (elementName == "vehicles") { + qCDebug(APMParameterMetaDataLog) << "vehicles end here, libraries will follow"; + xmlState.pop(); + } + } + xml.readNext(); + } +} + +void APMParameterMetaData::correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, + QMap& groupMembers) +{ + foreach(const QString& groupName, groupMembers.keys()) { + if (groupMembers[groupName].count() == 1) { + foreach(const QString& parameter, groupMembers.value(groupName)) { + parameterToFactMetaDataMap[parameter]->group = "others"; + } + } + } +} + +bool APMParameterMetaData::skipXMLBlock(QXmlStreamReader& xml, const QString& blockName) +{ + QString elementName; + do { + xml.readNext(); + elementName = xml.name().toString(); + } while ((elementName != blockName) && (xml.isEndElement())); + return !xml.isEndDocument(); +} + +bool APMParameterMetaData::parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw* rawMetaData) +{ + QString elementName = xml.name().toString(); + QList > values; + // as long as param doens't end + while (!(elementName == "param" && xml.isEndElement())) { + if (elementName.isEmpty()) { + // skip empty elements. Somehow I am getting lot of these. Dont know what to do with them. + } else if (elementName == "field") { + QString attributeName = xml.attributes().value("name").toString(); + if ( attributeName == "Range") { + QString range = xml.readElementText().trimmed(); + QStringList rangeList = range.split(' '); + if (rangeList.count() != 2) { + qCDebug(APMParameterMetaDataLog) << "space seperator didn't work',trying 'to' separator"; + rangeList = range.split("to"); + if (rangeList.count() != 2) { + qCDebug(APMParameterMetaDataLog) << " 'to' seperaator didn't work', trying '-' as seperator"; + rangeList = range.split('-'); + if (rangeList.count() != 2) { + qCWarning(APMParameterMetaDataLog) << "something wrong with range, all three separators have failed" << range; + } + } + } + rawMetaData->min = rangeList.first().trimmed(); + rawMetaData->max = rangeList.last().trimmed(); + + // sanitize min and max off any comments that they may have + if (rawMetaData->min.contains(' ')) { + rawMetaData->min = rawMetaData->min.split(' ').first(); + } + if(rawMetaData->max.contains(' ')) { + rawMetaData->max = rawMetaData->max.split(' ').first(); + } + qCDebug(APMParameterMetaDataLog) << "read field parameter " << "min: " << rawMetaData->min + << "max: " << rawMetaData->max; + } else if (attributeName == "Increment") { + QString increment = xml.readElementText(); + qCDebug(APMParameterMetaDataLog) << "read Increment: " << increment; + rawMetaData->incrementSize = increment; + } else if (attributeName == "Units") { + QString units = xml.readElementText(); + qCDebug(APMParameterMetaDataLog) << "read Units: " << units; + rawMetaData->units = units; + } + } else if (elementName == "values") { + // doing nothing individual value will follow anyway. May be used for sanity checking. + } else if (elementName == "value") { + QString valueValue = xml.attributes().value("code").toString(); + QString valueName = xml.readElementText(); + qCDebug(APMParameterMetaDataLog) << "read value parameter " << "value desc: " + << valueName << "code: " << valueValue; + values << QPair(valueValue, valueName); + rawMetaData->values = values; + } else { + qCWarning(APMParameterMetaDataLog) << "Unknown parameter element in XML: " << elementName; + } + xml.readNext(); + elementName = xml.name().toString(); + } + return true; } /// Override from FactLoad which connects the meta data to the fact -void APMParameterMetaData::addMetaDataToFact(Fact* fact) +void APMParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { _loadParameterFactMetaData(); - // FIXME: Will need to switch here based on _vehicle->firmwareType() to pull right set of meta data + const QString mavTypeString = mavTypeToString(vehicleType); + APMFactMetaDataRaw* rawMetaData = NULL; + + // 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()]; + } + + FactMetaData *metaData = new FactMetaData(fact->type(), fact); + + // we don't have data for this fact + if (!rawMetaData) { + fact->setMetaData(metaData); + qCDebug(APMParameterMetaDataLog) << "No metaData for " << fact->name() << "using generic metadata"; + return; + } + + metaData->setName(rawMetaData->name); + metaData->setGroup(rawMetaData->group); + + if (!rawMetaData->shortDescription.isEmpty()) { + metaData->setShortDescription(rawMetaData->shortDescription); + } + + if (!rawMetaData->longDescription.isEmpty()) { + metaData->setLongDescription(rawMetaData->longDescription); + } + + if (!rawMetaData->units.isEmpty()) { + metaData->setUnits(rawMetaData->units); + } + + if (!rawMetaData->min.isEmpty()) { + QVariant varMin; + QString errorString; + if (metaData->convertAndValidate(rawMetaData->min, true /* convertOnly */, varMin, errorString)) { + metaData->setMin(varMin); + } else { + qCDebug(APMParameterMetaDataLog) << "Invalid min value, name:" << metaData->name() + << " type:" << metaData->type() << " min:" << rawMetaData->min + << " error:" << errorString; + } + } + + if (!rawMetaData->max.isEmpty()) { + QVariant varMax; + QString errorString; + if (metaData->convertAndValidate(rawMetaData->max, true /* convertOnly */, varMax, errorString)) { + metaData->setMax(varMax); + } else { + qCDebug(APMParameterMetaDataLog) << "Invalid max value, name:" << metaData->name() << " type:" + << metaData->type() << " max:" << rawMetaData->max + << " error:" << errorString; + } + } - FactMetaData* metaData = new FactMetaData(fact->type(), fact); + // FixMe:: not handling values and increment size as their is no place for them in FactMetaData and no ui fact->setMetaData(metaData); } diff --git a/src/FirmwarePlugin/APM/APMParameterMetaData.h b/src/FirmwarePlugin/APM/APMParameterMetaData.h index 0290dfcd3338466b3da73a49c07abc0013bd5dd2..3d18b2c109e1ddd2e9f92b5d1c654127204ec414 100644 --- a/src/FirmwarePlugin/APM/APMParameterMetaData.h +++ b/src/FirmwarePlugin/APM/APMParameterMetaData.h @@ -26,6 +26,7 @@ #include #include +#include #include #include @@ -33,6 +34,20 @@ #include "AutoPilotPlugin.h" #include "Vehicle.h" +class APMFactMetaDataRaw +{ +public: + QString name; + QString group; + QString shortDescription; + QString longDescription; + QString min; + QString max; + QString incrementSize; + QString units; + QList > values; +}; + /// @file /// @author Don Gagne @@ -40,6 +55,8 @@ Q_DECLARE_LOGGING_CATEGORY(APMParameterMetaDataLog) /// Collection of Parameter Facts for PX4 AutoPilot +typedef QMap ParameterNametoFactMetaDataMap; + class APMParameterMetaData : public QObject { Q_OBJECT @@ -52,11 +69,15 @@ public: virtual QString getDefaultComponentIdParam(void) const { return QString("SYSID_SW_TYPE"); } // Overrides from ParameterLoader - static void addMetaDataToFact(Fact* fact); + static void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); + static void addMetaDataToFacts(QVariantMap &facts, MAV_TYPE vehicleType); private: enum { XmlStateNone, + XmlstateParamFileFound, + XmlStateFoundVehicles, + XmlStateFoundLibraries, XmlStateFoundParameters, XmlStateFoundVersion, XmlStateFoundGroup, @@ -65,11 +86,15 @@ private: }; - static void _loadParameterFactMetaData(void); + static void _loadParameterFactMetaData(); static QVariant _stringToTypedVariant(const QString& string, FactMetaData::ValueType_t type, bool* convertOk); + static bool skipXMLBlock(QXmlStreamReader& xml, const QString& blockName); + static bool parseParameterAttributes(QXmlStreamReader& xml, APMFactMetaDataRaw *rawMetaData); + static void correctGroupMemberships(ParameterNametoFactMetaDataMap& parameterToFactMetaDataMap, QMap& groupMembers); + static QString mavTypeToString(MAV_TYPE vehicleTypeEnum); static bool _parameterMetaDataLoaded; ///< true: parameter meta data already loaded - static QMap _mapParameterName2FactMetaData; ///< Maps from a parameter name to FactMetaData + static QMap _vehicleTypeToParametersMap; ///< Maps from a vehicle type to paramametertoFactMeta map> }; #endif diff --git a/src/FirmwarePlugin/APM/apm.pdef.xml b/src/FirmwarePlugin/APM/apm.pdef.xml new file mode 100644 index 0000000000000000000000000000000000000000..0a83916e723b9293d2c1e79287071990b2182928 --- /dev/null +++ b/src/FirmwarePlugin/APM/apm.pdef.xml @@ -0,0 +1,5859 @@ + + + + + + + + + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +1 10 +1 + + +0 10 +1 +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 1 +0.01 + + +0 5 +0.01 + + +0 15 +0.1 +Degrees + + +0 1000 +1 +meters + + +0 100 +1 +meters + + + +Disabled +FBWMixing +DirectMixing + + + + +Disabled +Enabled + + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s/s + + +0 127 +1 +0.1 seconds + + +-100 100 +1 +Percent + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s + + +0 127 +1 +percent + + +0 100 +Percent + + + + +0 45 +1 +degrees + + +centi-Degrees + + +0.1 +meters + + +0.1 +seconds + + +0 127 +1 +seconds + + + +Disabled +Enabled + + + + +Default +L1Controller + + + +0 1 +0.1 +Percent + + + +Automatic + + + +-32767 32767 +1 +Meters + + +1 32767 +1 +Meters + + +0 32767 +1 +Meters + + +-32767 32767 +1 +Meters + + + +None +GuidedMode +ReportOnly +GuidedModeThrPass + + + + + + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + + +NoAutoEnable +AutoEnable +AutoEnableDisableFloorOnly + + + + +FenceReturnPoint +NearestRallyPoint + + + + +Disabled +Enabled + + + +5 100 +1 +m/s + + +5 100 +1 +m/s + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 10000 +meters + + +1-10 +0.1 + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 127 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +925 1100 +1 + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +CIRCLE/no change(if already in AUTO|GUIDED|LOITER) +CIRCLE +FBWA + + + +1 100 +0.5 +seconds + + + +Continue +ReturnToLaunch +Glide + + + +1 300 +0.5 +seconds + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Heartbeat +HeartbeatAndREMRSSI +HeartbeatAndAUTO + + + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +Guided + + + +0 9000 +1 +centi-Degrees + + +0 9000 +1 +centi-Degrees + + +-9000 0 +1 +centi-Degrees + + +10 500 +1 +degrees/second + + +10 500 +1 +degrees/second + + + +Disabled +Enabled + + + +-100 100 +0.1 +Meters + + +10 360 +1 +degrees/second + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +UpUp +UpDown +DownUp +DownDown + + + + +Disabled +UpUp +UpDown +DownUp +DownDown + + + +0.5 1.2 + + + +Disabled +Enabled + + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,16:WHEN_DISARMED,19:IMU_RAW + +Disabled +APM2-Default +PX4/Pixhawk-Default + + + + + + + +cm/s + + +m/s + + +cm/s + + +centi-Degrees + + +centimeters + + +centimeters + + + +Disabled +Enabled + + + + + + +Disabled +UpUp +UpDown +DownUp +DownDown + + + +0 100 +Percent + + +0 100 +1 +m/s + + +0 100 +Percent + + +0 100 +1 +m/s + + +0 100 +Percent + + + + + +Disabled +Channel1 +Channel2 +Channel3 +Channel4 +Channel5 +Channel6 +Channel7 +Channel8 + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 90 +0.1 +degrees + + + +Disable +Enable - go HOME then land +Enable - go directly to landing sequence + + + + +Disable +Enable + + + +0:Disarm + +Disabled +Disarm + + + + + + +Disabled +Enabled + + + + + + + + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + + +Mission Planner and DroidPlanner + AP Planner 2 + + + + +Disabled +Enabled + + + +0 10 +.5 +Hz + + +0.0 1000.0 +10 +Centimeters + + +0.0 500.0 +10 + + + +None +FeedbackFromMid + + + +0 10 +1 +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 8000 +1 +Centimeters + + +0 2000 +50 +cm/s + + +0.01 2.0 +0.01 + + + +Disabled +Land +RTL + + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode + + + +100 900 + + + +Disabled +Enabled + + + + +Disabled +Mode1 +Mode2 +Mode1+2 +Mode3 +Mode1+3 +Mode2+3 +Mode1+2+3 +Mode4 +Mode1+4 +Mode2+4 +Mode1+2+4 +Mode3+4 +Mode1+3+4 +Mode2+3+4 +Mode1+2+3+4 +Mode5 +Mode1+5 +Mode2+5 +Mode1+2+5 +Mode3+5 +Mode1+3+5 +Mode2+3+5 +Mode1+2+3+5 +Mode4+5 +Mode1+4+5 +Mode2+4+5 +Mode1+2+4+5 +Mode3+4+5 +Mode1+3+4+5 +Mode2+3+4+5 +Mode1+2+3+4+5 +Mode6 +Mode1+6 +Mode2+6 +Mode1+2+6 +Mode3+6 +Mode1+3+6 +Mode2+3+6 +Mode1+2+3+6 +Mode4+6 +Mode1+4+6 +Mode2+4+6 +Mode1+2+4+6 +Mode3+4+6 +Mode1+3+4+6 +Mode2+3+4+6 +Mode1+2+3+4+6 +Mode5+6 +Mode1+5+6 +Mode2+5+6 +Mode1+2+5+6 +Mode3+5+6 +Mode1+3+5+6 +Mode2+3+5+6 +Mode1+2+3+5+6 +Mode4+5+6 +Mode1+4+5+6 +Mode2+4+5+6 +Mode1+2+4+5+6 +Mode3+4+5+6 +Mode1+3+4+5+6 +Mode2+3+4+5+6 +Mode1+2+3+4+5+6 + + + +-1 1000 +1 +Centimeters + + +0 3000 +10 +Centimeters + + + +Never change yaw +Face next waypoint +Face next waypoint except RTL +Face along GPS course + + + +0 60000 +1000 +ms + + +30 200 +10 +cm/s + + +50 500 +10 +Centimeters/Second + + +50 500 +10 +cm/s/s + + +0 300 +1 +Percent*10 + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always LAND + + + +925 1100 +1 +pwm + + +300 700 +1 +Percent*10 + + +0 300 +1 +pwm + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake + + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,16:WHEN_DISARMED,17:MOTBATT,18:IMU_FAST,19:IMU_RAW + +Default +Default+RCIN +Default+IMU +Default+Motors +NearlyAll-AC315 +NearlyAll +All+DisarmedLogging +All+FastATT +All+MotBatt +All+FastIMU +All+FastIMU+PID +All+FullIMU +Disabled + + + + +Normal Start-up +Start-up in ESC Calibration mode if throttle high +Start-up in ESC Calibration mode regardless of throttle +Disabled + + + + +None +Stab Roll/Pitch kP +Rate Roll/Pitch kP +Rate Roll/Pitch kI +Rate Roll/Pitch kD +Stab Yaw kP +Rate Yaw kP +Rate Yaw kD +Altitude Hold kP +Throttle Rate kP +Throttle Accel kP +Throttle Accel kI +Throttle Accel kD +Loiter Speed +Loiter Pos kP +Velocity XY kP +Velocity XY kI +WP Speed +Acro RollPitch kP +Acro Yaw kP +Heli Ext Gyro +OF Loiter kP +OF Loiter kI +OF Loiter kD +Declination +Circle Rate +RangeFinder Gain +Rate Pitch kP +Rate Pitch kI +Rate Pitch kD +Rate Roll kP +Rate Roll kI +Rate Roll kD +Rate Pitch FF +Rate Roll FF +Rate Yaw FF + + + +0 32767 + + +0 32767 + + + +Plus +X +V +H +V-Tail +A-Tail +Y6B (New) + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +ResetToArmedYaw +Super Simple Mode +Acro Trainer +Auto +AutoTune +Land +EPM +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake + + + +0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Sonar,6:RC,7:Voltage + +Disabled +Enabled +Skip Baro +Skip Compass +Skip GPS +Skip INS +Skip Params/Sonar +Skip RC +Skip Voltage + + + +0 127 +Seconds + + +1000 8000 +Centi-degrees + + +0 100 + +Very Soft +Soft +Medium +Crisp +Very Crisp + +1 + + +4 12 +deg/sec + + +2000 4500 +Centi-degrees + + + +No repositioning +Repositioning + + + + +Land +AltHold +Land even in Stabilize + + + +0.6:Strict, 0.8:Default, 1.0:Relaxed + + + +Disabled +Enabled + + + +50 490 +1 +Hz + + +1 10 + + +1 10 + + +0 3 +0.1 + + +0 3 +0.1 + + + +Disabled +Leveling +Leveling and Limited + + + + +Disabled +Very Low +Low +Medium +High +Very High + + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 4500 +10 +Percent*10 + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 4500 +10 +Percent*10 + + +0.150 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 4500 +10 +Percent*10 + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0 4500 +10 +cm/s/s + + +1.000 8.000 + + +0.500 1.500 + + +0.000 3.000 + + +0 1000 +Percent*10 + + +0.000 0.400 + + +1.000 100.000 +Hz + + +3.000 12.000 + + +3.000 12.000 + + +3.000 6.000 + + +1.000 3.000 + + +0.500 2.000 + + +0.100 5.000 + + +0.100 5.000 + + +0 1000 +cm/s + + +0:Roll,1:Pitch,2:Yaw + +All +Roll Only +Pitch Only +Yaw Only +Roll and Pitch +Roll and Yaw +Pitch and Yaw + + + +0.05 0.10 + + +0.001 0.006 + + + + +1 255 + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 20 +0.1 +seconds + + +0 20 +0.1 +seconds + + +0 100 +1 +degrees/second + + +0 20 +1 +seconds + + +-90 90 +0.000001 +degrees + + +-180 180 +0.000001 +degrees + + +0 10 +0.1 +seconds + + + +Position +OnOff +ContinuousRotation + + + +0 50 +0.1 +degrees/second + + +0 50 +0.1 +degrees/second + + +0 2 +0.01 +seconds + + +0 2 +0.01 +seconds + + +-10 10 +0.1 +degrees + + +-10 10 +0.1 +degrees + + +0 360 +0.1 +degrees + + +0 180 +0.1 +degrees + + +0 100 +1 +meters + + +1 255 + + + + + +Disabled +Default +Default+IMU + + + + + + +MANUAL +LEARNING +STEERING +HOLD +AUTO +RTL +GUIDED + + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 10 +1 +seconds + + +0:Steering + +None +Steering + + + + +Disabled +Enabled + + + + +Disabled +APM TriggerPin + Pixhawk TriggerPin + + + +0 20 +0.1 +m/s/s + + +0 100 +0.1 +m/s + + +0 100 +1 +percent + + +0 100 +0.1 +meters + + +0 100 +1 +percent + + +0 100 +1 +m/s + + +0 360 +1 +degrees + + + +Nothing +LearnWaypoint + + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +SkidSteeringOutput + + + + +Disabled +SkidSteeringInput + + + + +Nothing +RTL +HOLD + + + +seconds + + + +Disabled +Enabled + + + +925 1100 +1 + + + +Disabled +Enabled + + + +0 1000 +1 +centimeters + + +-45 45 +1 +centimeters + + +0 100 +0.1 +seconds + + +1 100 +1 + + + + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + +0 1000 +0.1 +meters + + +0.2 10 +0.1 +gravities + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +GCS Mavlink +Frsky D-PORT +Frsky S-PORT +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + +pascals +1 + + +degrees celsius +1 + + +meters +0.1 + + + +FirstBaro +2ndBaro +3rdBaro + + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + +True + + + +Disabled +Enabled + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + +True + + +-100 90 +Degrees +True + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None +All +External only + + + + +Disabled +log every sample +log every 5 samples + +True + + +0:GPS, 1:SBAS, 2:Galileo, 3:Beidou, 4:IMES, 5:QZSS, 6:GLOSNASS + +Leave as currently configured +GPS-NoSBAS +GPS+SBAS +Galileo-NoSBAS +Galileo+SBAS +Beidou +GPS+IMES+QZSS+SBAS (Japan Only) +GLONASS +GLONASS+SBAS +GPS+GLONASS+SBAS + +True + + + +Do not save config +Save config + + + + + + +Servo +Relay + + + +0 50 +seconds + + +1000 2000 +pwm + + +1000 2000 +pwm + + +0 1000 +meters + + + +Low +High + + + + + + +Disabled +THR_MIN PWM when disarmed +0 PWM when disarmed + + + +0:All,1:Barometer,2:Compass,3:GPS,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available + +None +All +Barometer +Compass +GPS +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Failsafe +Board voltage +Battery Level +Airspeed +LoggingAvailable + + + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Off +On +NoChange + + + + + + +Disabled +Enabled + + + + +First Relay +Second Relay +Third Relay +Fourth Relay +Servo + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + +0 32000 +1 +Meters + + + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 32767 +meters + + +0 127 +1 +centimeters + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +0 127 +1 + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +meters/Volt +0.001 + + +Volts +0.001 + + + +Linear +Inverted +Hyperbolic + + + +centimeters +1 + + +centimeters +1 + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +milliseconds +1 + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +meters/Volt +0.001 + + +Volts +0.001 + + + +Linear +Inverted +Hyperbolic + + + +centimeters +1 + + +centimeters +1 + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +milliseconds +1 + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + + + + +Disable +Enable + + + +meters +1 + + + + + +Disabled +Enabled + + + + +None +Loiter +LoiterAndDescend + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable + + + + + +0.4 1.0 +0.1 +seconds + + +0.1 4.0 +0.1 + + +0 0.1 +0.01 + + +0 1.0 +0.05 + + +0 180 +1 +degrees/second + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + +0.4 1.0 +0.1 +seconds + + +0.1 3.0 +0.1 + + +0 0.1 +0.01 + + +0 0.5 +0.05 + + +0 100 +1 +degrees/second + + +0 100 +1 +degrees/second + + +0.7 1.5 +0.05 + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + +0 4 +0.25 + + +0 2 +0.25 + + +0 2 +0.25 + + +0.8 1.2 +0.05 + + +0 4500 +1 + + + + +0.4 1.0 +0.1 +seconds + + +0.1 10.0 +0.1 + + +0 1.0 +0.05 + + +0 0.1 +0.01 + + +0 4500 +1 + + +0 5 +0.1 +m/s + + +0.0 10.0 +0.1 + + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-3.142 3.142 +0.01 +Radians + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +FirstCompass +SecondCompass +ThirdCompass + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + + + + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +4 20 +0.1 + + + + + +Disabled +ShowSlips +ShowOverruns + + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Unknown +APM1-1280 +APM1-2560 +APM2 +SITL +PX4v1 +PX4v2 +Flymaple +Linux + + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0 127 +Hz + + +0 127 +Hz + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0.05 to 50 + + + +Never +Start-up only + + + + + +0.0 1.0 +.01 + + + +Disabled +Enabled + + + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 + + + +0.001 0.5 +.01 + + +0 10 +1 + + + +Disabled +Enabled +Enable EKF2 + + + + + + +Disable +Enable + + + + +Use +Don't Use + + + +0.1 + + +0.1 + + + + + + + + + +Disable +Enable + + + + + +1-60 +1 +seconds + + +0.6-1.0 +0.05 + + +0 to 0.1 +0.01 + + + + +0.1 20.0 +0.1 + + +0.1 10.0 +0.1 + + +3.0 10.0 +0.2 + + +0.1 1.0 +0.1 + + +0.0 0.5 +0.02 + + +1.0 10.0 +0.5 + + +1.0 5.0 +0.05 + + +0.5 2.0 +0.05 + + +5.0 30.0 +1.0 + + +0.0 2.0 +0.1 + + +0.1 1.0 +0.1 + + +0.0 20.0 +0.1 + + +-1 127 +1 + + +-1 to 100 +0.1 + + +0.0 2.0 +0.1 + + +0 45 +1 + + +-45 0 +1 + + +0.0 2.0 +0.1 + + +1.0 5.0 +0.2 + + +0.1 1.0 +0.1 + + +0 40 +1 + + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0 100 +1 + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + +0 0.5 +radians + + +0 0.5 +radians + + +0 0.5 +radians + + +0 2 +m/s + + +0 2 +m/s + + +0 2 +m/s + + +0 0.5 +radians/sec + + +0 0.5 +radians/sec + + +0 0.5 +radians/sec + + +0 10 + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +SMBus +Bebop + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +SMBus +Bebop + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + + + + +No PWMs +Two PWMs +Four PWMs +Six PWMs + + + + +Disabled +Enabled +Auto + + + + +Disabled +Enabled +Auto + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +-32767 to 32768 (any 16bit signed number) + + + +Disabled +Enabled + + + + + + + + + + + + + + + + + + + +meters + + +meters + + +millibar + + + + + + + + + + + + + +Disabled +Enabled + + + +-200 +200 +1 + + +-200 +200 +1 + + +-18000 +18000 +1 + + + + +0 32766 +1 + + + +Resume Mission +Restart Mission + + + + + + + +0.1 +kilometers + + + +DoNotIncludeHome +IncludeHome + + + + + +0.05 5.0 +0.05 + + +0.05 5.0 +0.05 + + +0.1 10.0 +0.1 +meters + + +0.1 10.0 +0.1 +meters + + +0.01 0.5 +0.01 + + +0.5 5.0 +0.1 +m/s + + +0.01 1.0 +0.1 + + +0.0 1.0 +0.1 + + +0.001 0.05 +0.001 +rad/s + + +0.05 1.0 +0.01 +m/s/s + + +0.0000001 0.00001 +rad/s + + +0.00001 0.001 +m/s/s + + +0.0001 0.01 +gauss/s + + +0.0001 0.01 +gauss/s + + +0 500 +10 +milliseconds + + +0 500 +10 +milliseconds + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS use optical flow + + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + +1 100 +1 + + + +Speed and Height +Acceleration +Never +Always + + + +100 500 +50 + + +10 50 +5 +meters + + +1 - 50 +1 + + +0.05 - 1.0 +0.05 +rad/s + + +1 - 100 +1 + + +0 - 500 +10 +milliseconds + + +1 - 100 +1 + + +1.0 - 4.0 +0.1 + + + +Trust EKF more +Trust DCM more + + + + +Use Baro +Use Range Finder + + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + + +Disabled +Enabled + + + + + + +Disabled +Enabled + + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS use optical flow + + + +0.05 5.0 +0.05 +m/s + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + +0 250 +10 +msec + + + +Use Baro +Use Range Finder +Use GPS + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +msec + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 - 1000 +25 + + +1.0 - 4.0 +0.1 +rad/s + + +0.05 - 1.0 +0.05 +rad/s + + +100 - 1000 +25 + + +0 - 250 +10 +msec + + +0.0001 0.01 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.0000001 0.00001 +rad/s + + +0.0000001 0.00001 +1/s + + +0.00001 0.001 +m/s/s + + +0.0001 0.01 +gauss/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +1 127 + + +50 200 +% + + + + + +None +PX4-PWM + + + +0.001 + + +1 + + +1 + + +0.1 + + + +None +PX4-PWM + + + +0.001 + + + + + +Disabled +AnalogPin +RCChannelPwmValue + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixhawk SBUS + + + +0 5.0 +0.01 +Volt + + +0 5.0 +0.01 +Volt + + + +Channel5 +Channel6 +Channel7 +Channel8 + + + + +0 2000 +Microseconds + + +0 2000 +Microseconds + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + + +Disabled +Enabled + + + +1000 2000 + + +1000 2000 + + +1000 2000 + + + +Never +every 15 seconds +every 30 seconds +once per minute + + + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + + + +0 500 +1 +Percent*10 + + +0 500 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + + +Disabled +Very Low +Low +Medium +High +Very High + + + + + +0 2000 +50 +cm/s + + +100 1000 +1 +cm + + +0 1000 +50 +cm/s + + +0 500 +10 +cm/s + + +0 2000 +50 +cm/s + + +50 500 +10 +cm/s/s + + +50 500 +10 +cm/s/s + + +500 5000 +1 +cm/s/s/s + + +100 981 +1 +cm/s/s + + +100 981 +1 +cm/s/s + + + + +0 10000 +100 +cm + + +-90 90 +1 +deg/s + + + + +500 18000 +100 +Centi-Degrees/Sec + + +0 72000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + + +0.5 5 +0.1 +Hz + + + + + +Disabled +Enabled + + + +0 100 +percentage + + +1000 2000 +ms + + +0 1000 +cm/s + + +0 100 +percentage + + + + + +Disabled +Enabled + + + + +None +Altitude +Circle +Altitude and Circle + + + + +Report Only +RTL or Land + + + +10 1000 +1 +Meters + + +30 10000 +Meters + + +1 10 +Meters + + + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + + +Servo only +Servo with ExtGyro +DirectDrive VarPitch +DirectDrive FixedPitch + + + + +3-Servo CCPM +H1 Mechanical Mixing + + + +0 1000 +1 +PWM + + +-90 90 +1 +Degrees + + +-10 10 +0.1 + + +0:NoFlybar 1:Flybar + + +0 1000 +1 +PWM + + +0 1000 +1 +PWM + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Reversed +Normal + + + +0 200 +pwm + + + + + +Reversed +Normal + + + + +Reversed +Normal + + + + +Reversed +Normal + + + +50, 125, 250 + + + + + +None +CompanionComputer +IRLock + + + +0 500 + + + diff --git a/src/FirmwarePlugin/FirmwarePlugin.h b/src/FirmwarePlugin/FirmwarePlugin.h index 4a05bdd879de6b9f8bb9e3db07277248e02df210..e6edfbc6853d656d1e4ab45012273a234508039c 100644 --- a/src/FirmwarePlugin/FirmwarePlugin.h +++ b/src/FirmwarePlugin/FirmwarePlugin.h @@ -79,7 +79,7 @@ public: /// @param[out] custom_mode Custom mode for SET_MODE mavlink message virtual bool setFlightMode(const QString& flightMode, uint8_t* base_mode, uint32_t* custom_mode) = 0; - /// FIXME: This isn't quite correct being here. All code for Joystick support is currently firmware specific + /// FIXME: This isn't quite correct being here. All code for Joystick suvehicleTypepport is currently firmware specific /// not just this. I'm going to try to change that. If not, this will need to be removed. /// Returns the number of buttons which are reserved for firmware use in the MANUAL_CONTROL mavlink /// message. For example PX4 Flight Stack reserves the first 8 buttons to simulate rc switches. @@ -108,7 +108,7 @@ public: virtual QString getDefaultComponentIdParam(void) const = 0; /// Adds the parameter meta data to the Fact - virtual void addMetaDataToFact(Fact* fact) = 0; + virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) = 0; /// List of supported mission commands. Empty list for all commands supported. virtual QList supportedMissionCommands(void) = 0; diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc index d4cd776de4e39ffd238aa865a05df0ed8b6f6254..7a6b17c5c4d3fb3dfdfbaf68c2f331cde7ae6491 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.cc @@ -112,8 +112,10 @@ bool GenericFirmwarePlugin::sendHomePositionToVehicle(void) return false; } -void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact) +void GenericFirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { + Q_UNUSED(vehicleType) + // Add default meta data FactMetaData* metaData = new FactMetaData(fact->type(), fact); fact->setMetaData(metaData); diff --git a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h index 9a01d1a0b62e8a3d22f4dc30a8376b4fa929ced5..bd17140beb9699019024365e9d22a2c7e7f7cd7f 100644 --- a/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h +++ b/src/FirmwarePlugin/Generic/GenericFirmwarePlugin.h @@ -45,7 +45,7 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual void addMetaDataToFact(Fact* fact); + virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual QString getDefaultComponentIdParam(void) const { return QString(); } virtual QList supportedMissionCommands(void); }; diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc index 116a875c3a9e2cb5e4c45405d9fcfcbdfdd21fb2..946f7cda7aa55666234edf9ca67d2ff54ec961d1 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.cc @@ -203,9 +203,9 @@ bool PX4FirmwarePlugin::sendHomePositionToVehicle(void) return false; } -void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact) +void PX4FirmwarePlugin::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { - _parameterMetaData.addMetaDataToFact(fact); + _parameterMetaData.addMetaDataToFact(fact, vehicleType); } QList PX4FirmwarePlugin::supportedMissionCommands(void) diff --git a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h index 99134ec0e96166b14069c5fea2efcdceb13ec2c7..07825896d290dade8356dd351a6938ccaea2d6e2 100644 --- a/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h +++ b/src/FirmwarePlugin/PX4/PX4FirmwarePlugin.h @@ -45,7 +45,7 @@ public: virtual void adjustMavlinkMessage(mavlink_message_t* message); virtual void initializeVehicle(Vehicle* vehicle); virtual bool sendHomePositionToVehicle(void); - virtual void addMetaDataToFact(Fact* fact); + virtual void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); virtual QString getDefaultComponentIdParam(void) const { return QString("SYS_AUTOSTART"); } virtual QList supportedMissionCommands(void); diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc index ce4ddf090b2d11081d4f5e042f195856bf9bcfe8..8d5dd4bcf9dad1ff1f1024b9fcfef3e3c58c3373 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.cc @@ -188,7 +188,7 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) QString name = xml.attributes().value("name").toString(); QString type = xml.attributes().value("type").toString(); - QString strDefault = xml.attributes().value("default").toString(); + QString strDefault = xml.attributes().value("default").toString(); qCDebug(PX4ParameterMetaDataLog) << "Found parameter name:" << name << " type:" << type << " default:" << strDefault; @@ -345,8 +345,10 @@ void PX4ParameterMetaData::_loadParameterFactMetaData(void) } /// Override from FactLoad which connects the meta data to the fact -void PX4ParameterMetaData::addMetaDataToFact(Fact* fact) +void PX4ParameterMetaData::addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType) { + Q_UNUSED(vehicleType) + _loadParameterFactMetaData(); if (_mapParameterName2FactMetaData.contains(fact->name())) { fact->setMetaData(_mapParameterName2FactMetaData[fact->name()]); diff --git a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h index c2d1822ef7d1d0f872f1b3748dd56368dc8001b7..c60fb8536467ecaf5e7b706d3954ce20b168f005 100644 --- a/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h +++ b/src/FirmwarePlugin/PX4/PX4ParameterMetaData.h @@ -47,7 +47,7 @@ class PX4ParameterMetaData : public QObject public: PX4ParameterMetaData(QObject* parent = NULL); - void addMetaDataToFact(Fact* fact); + void addMetaDataToFact(Fact* fact, MAV_TYPE vehicleType); private: enum {