diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponent.cc b/src/AutoPilotPlugins/APM/APMSafetyComponent.cc index 57af49679e4eae3424c134fde9b5e7d69e08296d..4e18a7359fc53a9cbc0b134abe1e0e29621ea05b 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponent.cc +++ b/src/AutoPilotPlugins/APM/APMSafetyComponent.cc @@ -30,20 +30,20 @@ QString APMSafetyComponent::name(void) const QString APMSafetyComponent::description(void) const { switch (_vehicle->vehicleType()) { - case MAV_TYPE_SUBMARINE: - return tr("Safety Setup is used to setup failsafe actions, leak detection, and arming checks."); - break; - case MAV_TYPE_GROUND_ROVER: - case MAV_TYPE_FIXED_WING: - case MAV_TYPE_QUADROTOR: - case MAV_TYPE_COAXIAL: - case MAV_TYPE_HELICOPTER: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_TRICOPTER: - default: - return tr("Safety Setup is used to setup triggers for Return to Land as well as the settings for Return to Land itself."); - break; + case MAV_TYPE_SUBMARINE: + return tr("Safety Setup is used to setup failsafe actions, leak detection, and arming checks."); + break; + case MAV_TYPE_GROUND_ROVER: + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + default: + return tr("Safety Setup is used to setup triggers for Return to Land as well as the settings for Return to Land itself."); + break; } } @@ -73,26 +73,22 @@ QUrl APMSafetyComponent::setupSource(void) const QString qmlFile; switch (_vehicle->vehicleType()) { - case MAV_TYPE_FIXED_WING: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentPlane.qml"); - break; - case MAV_TYPE_QUADROTOR: - case MAV_TYPE_COAXIAL: - case MAV_TYPE_HELICOPTER: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_TRICOPTER: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentCopter.qml"); - break; - case MAV_TYPE_SUBMARINE: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSub.qml"); - break; - case MAV_TYPE_GROUND_ROVER: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentRover.qml"); - break; - default: - qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml"); - break; + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + case MAV_TYPE_GROUND_ROVER: + qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponent.qml"); + break; + case MAV_TYPE_SUBMARINE: + qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSub.qml"); + break; + default: + qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml"); + break; } return QUrl::fromUserInput(qmlFile); @@ -103,26 +99,22 @@ QUrl APMSafetyComponent::summaryQmlSource(void) const QString qmlFile; switch (_vehicle->vehicleType()) { - case MAV_TYPE_FIXED_WING: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryPlane.qml"); - break; - case MAV_TYPE_QUADROTOR: - case MAV_TYPE_COAXIAL: - case MAV_TYPE_HELICOPTER: - case MAV_TYPE_HEXAROTOR: - case MAV_TYPE_OCTOROTOR: - case MAV_TYPE_TRICOPTER: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryCopter.qml"); - break; - case MAV_TYPE_SUBMARINE: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummarySub.qml"); - break; - case MAV_TYPE_GROUND_ROVER: - qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummaryRover.qml"); - break; - default: - qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml"); - break; + case MAV_TYPE_FIXED_WING: + case MAV_TYPE_QUADROTOR: + case MAV_TYPE_COAXIAL: + case MAV_TYPE_HELICOPTER: + case MAV_TYPE_HEXAROTOR: + case MAV_TYPE_OCTOROTOR: + case MAV_TYPE_TRICOPTER: + case MAV_TYPE_GROUND_ROVER: + qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummary.qml"); + break; + case MAV_TYPE_SUBMARINE: + qmlFile = QStringLiteral("qrc:/qml/APMSafetyComponentSummarySub.qml"); + break; + default: + qmlFile = QStringLiteral("qrc:/qml/APMNotSupported.qml"); + break; } return QUrl::fromUserInput(qmlFile); diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponent.qml b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml new file mode 100644 index 0000000000000000000000000000000000000000..d3e3ba1735b8dce909cfbf2679b2ea5310e1045b --- /dev/null +++ b/src/AutoPilotPlugins/APM/APMSafetyComponent.qml @@ -0,0 +1,778 @@ +/**************************************************************************** + * + * (c) 2009-2016 QGROUNDCONTROL PROJECT + * + * QGroundControl is licensed according to the terms in the file + * COPYING.md in the root of the source code directory. + * + ****************************************************************************/ + +import QtQuick 2.3 +import QtQuick.Controls 1.2 +import QtGraphicalEffects 1.0 +import QtQuick.Layouts 1.2 + +import QGroundControl.FactSystem 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Palette 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.ScreenTools 1.0 + +SetupPage { + id: safetyPage + pageComponent: safetyPageComponent + + Component { + id: safetyPageComponent + + Flow { + id: flowLayout + width: availableWidth + spacing: _margins + + FactPanelController { id: controller; factPanel: safetyPage.viewPanel } + + QGCPalette { id: ggcPal; colorGroupEnabled: true } + + property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR") + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) + property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") + property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0 + property bool _batt2MonitorEnabled: _batt2MonitorAvailable ? _batt2Monitor.rawValue !== 0 : false + property bool _batt1ParamsAvailable: controller.parameterExists(-1, "BATT_CAPACITY") + property bool _batt2ParamsAvailable: controller.parameterExists(-1, "BATT2_CAPACITY") + + property Fact _failsafeBatt1LowAct: controller.getParameterFact(-1, "BATT_FS_LOW_ACT", false /* reportMissing */) + property Fact _failsafeBatt2LowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */) + property Fact _failsafeBatt1CritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */) + property Fact _failsafeBatt2CritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */) + property Fact _failsafeBatt1Mah: controller.getParameterFact(-1, "BATT_LOW_MAH", false /* reportMissing */) + property Fact _failsafeBatt2Mah: controller.getParameterFact(-1, "BATT2_LOW_MAH", false /* reportMissing */) + property Fact _failsafeBatt1Voltage: controller.getParameterFact(-1, "BATT_LOW_VOLT", false /* reportMissing */) + property Fact _failsafeBatt2Voltage: controller.getParameterFact(-1, "BATT2_LOW_VOLT", false /* reportMissing */) + + property Fact _armingCheck: controller.getParameterFact(-1, "ARMING_CHECK") + + property real _margins: ScreenTools.defaultFontPixelHeight + property bool _showIcon: !ScreenTools.isTinyScreen + + ExclusiveGroup { id: fenceActionRadioGroup } + ExclusiveGroup { id: landLoiterRadioGroup } + ExclusiveGroup { id: returnAltRadioGroup } + + Column { + spacing: _margins / 2 + visible: _batt1MonitorEnabled && _batt1ParamsAvailable + + QGCLabel { + text: qsTr("Battery1 Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: batteryFailsafeColumn.x + batteryFailsafeColumn.width + _margins + height: batteryFailsafeColumn.y + batteryFailsafeColumn.height + _margins + color: ggcPal.windowShade + + Column { + id: batteryFailsafeColumn + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + spacing: _margins + + GridLayout { + id: gridLayout + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + QGCLabel { text: qsTr("Battery low action:") } + FactComboBox { + fact: _failsafeBatt1LowAct + indexModel: false + Layout.fillWidth: true + } + + QGCLabel { + text: qsTr("Battery critical action:") + } + FactComboBox { + fact: _failsafeBatt1CritAct + indexModel: false + Layout.fillWidth: true + } + + QGCCheckBox { + text: qsTr("Voltage threshold:") + checked: _failsafeBatt1Voltage.value != 0 + onClicked: _failsafeBatt1Voltage.value = checked ? 10.5 : 0 + } + FactTextField { + fact: _failsafeBatt1Voltage + showUnits: true + Layout.fillWidth: true + } + + QGCCheckBox { + text: qsTr("MAH threshold:") + checked: _failsafeBatt1Mah.value != 0 + onClicked: _failsafeBatt1Mah.value = checked ? 600 : 0 + } + FactTextField { + fact: _failsafeBatt1Mah + showUnits: true + Layout.fillWidth: true + } + } // GridLayout + } // Column + } // Rectangle + } // Column - Battery Failsafe Settings + + Column { + spacing: _margins / 2 + visible: _batt2MonitorEnabled && _batt2ParamsAvailable + + QGCLabel { + text: qsTr("Battery2 Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: failsafeSettings + width: battery2FailsafeColumn.x + battery2FailsafeColumn.width + _margins + height: battery2FailsafeColumn.y + battery2FailsafeColumn.height + _margins + color: ggcPal.windowShade + + Column { + id: battery2FailsafeColumn + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + spacing: _margins + + GridLayout { + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + visible: _batt2MonitorEnabled && _failsafeBatt2LowActAvailable + + QGCLabel { text: qsTr("Battery low action:") } + FactComboBox { + fact: _failsafeBatt2LowAct + indexModel: false + Layout.fillWidth: true + } + + QGCLabel { + text: qsTr("Battery critical action:") + } + FactComboBox { + fact: _failsafeBatt2CritAct + indexModel: false + Layout.fillWidth: true + } + + QGCCheckBox { + text: qsTr("Voltage threshold:") + checked: _failsafeBatt2Voltage.value != 0 + onClicked: _failsafeBatt2Voltage.value = checked ? 10.5 : 0 + } + FactTextField { + fact: _failsafeBatt2Voltage + showUnits: true + Layout.fillWidth: true + } + + QGCCheckBox { + text: qsTr("MAH threshold:") + checked: _failsafeBatt2Mah.value != 0 + onClicked: _failsafeBatt2Mah.value = checked ? 600 : 0 + } + FactTextField { + fact: _failsafeBatt2Mah + showUnits: true + Layout.fillWidth: true + } + } // GridLayout + } // Column + } // Rectangle + } // Column - Battery2 Failsafe Settings + + Component { + id: planeGeneralFS + + Column { + spacing: _margins / 2 + + property Fact _failsafeThrEnable: controller.getParameterFact(-1, "THR_FAILSAFE") + property Fact _failsafeThrValue: controller.getParameterFact(-1, "THR_FS_VALUE") + property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABL") + + QGCLabel { + text: qsTr("Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: fsColumn.x + fsColumn.width + _margins + height: fsColumn.y + fsColumn.height + _margins + color: qgcPal.windowShade + + ColumnLayout { + id: fsColumn + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + + RowLayout { + QGCCheckBox { + id: throttleEnableCheckBox + text: qsTr("Throttle PWM threshold:") + checked: _failsafeThrEnable.value === 1 + + onClicked: _failsafeThrEnable.value = (checked ? 1 : 0) + } + + FactTextField { + fact: _failsafeThrValue + showUnits: true + enabled: throttleEnableCheckBox.checked + } + } + + QGCCheckBox { + text: qsTr("GCS failsafe") + checked: _failsafeGCSEnable.value != 0 + onClicked: _failsafeGCSEnable.value = checked ? 1 : 0 + } + } + } // Rectangle - Failsafe trigger settings + } // Column - Failsafe trigger settings + } + + Loader { + sourceComponent: controller.vehicle.fixedWing ? planeGeneralFS : undefined + } + + Component { + id: roverGeneralFS + + Column { + spacing: _margins / 2 + + property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE") + property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE") + property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE") + property Fact _failsafeAction: controller.getParameterFact(-1, "FS_ACTION") + property Fact _failsafeCrashCheck: controller.getParameterFact(-1, "FS_CRASH_CHECK") + + QGCLabel { + id: failsafeLabel + text: qsTr("Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: failsafeSettings + width: fsGrid.x + fsGrid.width + _margins + height: fsGrid.y + fsGrid.height + _margins + color: ggcPal.windowShade + + GridLayout { + id: fsGrid + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + columns: 2 + + QGCLabel { text: qsTr("Ground Station failsafe:") } + FactComboBox { + Layout.fillWidth: true + fact: _failsafeGCSEnable + indexModel: false + } + + QGCLabel { text: qsTr("Throttle failsafe:") } + FactComboBox { + Layout.fillWidth: true + fact: _failsafeThrEnable + indexModel: false + } + + QGCLabel { text: qsTr("PWM threshold:") } + FactTextField { + Layout.fillWidth: true + fact: _failsafeThrValue + } + + QGCLabel { text: qsTr("Failsafe Crash Check:") } + FactComboBox { + Layout.fillWidth: true + fact: _failsafeCrashCheck + indexModel: false + } + } + } // Rectangle - Failsafe Settings + } // Column - Failsafe Settings + } + + Loader { + sourceComponent: controller.vehicle.rover ? roverGeneralFS : undefined + } + + Component { + id: copterGeneralFS + + Column { + spacing: _margins / 2 + + property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE") + property Fact _failsafeBattLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT", false /* reportMissing */) + property Fact _failsafeBattMah: controller.getParameterFact(-1, "r.BATT_LOW_MAH", false /* reportMissing */) + property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "r.BATT_LOW_VOLT", false /* reportMissing */) + property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE") + property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE") + + QGCLabel { + text: qsTr("General Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: generalFailsafeColumn.x + generalFailsafeColumn.width + _margins + height: generalFailsafeColumn.y + generalFailsafeColumn.height + _margins + color: ggcPal.windowShade + + Column { + id: generalFailsafeColumn + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + spacing: _margins + + GridLayout { + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + + QGCLabel { text: qsTr("Ground Station failsafe:") } + FactComboBox { + fact: _failsafeGCSEnable + indexModel: false + Layout.fillWidth: true + } + + QGCLabel { text: qsTr("Throttle failsafe:") } + QGCComboBox { + model: [qsTr("Disabled"), qsTr("Always RTL"), + qsTr("Continue with Mission in Auto Mode"), qsTr("Always Land")] + currentIndex: _failsafeThrEnable.value + Layout.fillWidth: true + + onActivated: _failsafeThrEnable.value = index + } + + QGCLabel { text: qsTr("PWM threshold:") } + FactTextField { + fact: _failsafeThrValue + showUnits: true + Layout.fillWidth: true + } + } // GridLayout + } // Column + } // Rectangle - Failsafe Settings + } // Column - General Failsafe Settings + } + + Loader { + sourceComponent: controller.vehicle.multiRotor ? copterGeneralFS : undefined + } + + Component { + id: copterGeoFence + + Column { + spacing: _margins / 2 + + property Fact _fenceAction: controller.getParameterFact(-1, "FENCE_ACTION") + property Fact _fenceAltMax: controller.getParameterFact(-1, "FENCE_ALT_MAX") + property Fact _fenceEnable: controller.getParameterFact(-1, "FENCE_ENABLE") + property Fact _fenceMargin: controller.getParameterFact(-1, "FENCE_MARGIN") + property Fact _fenceRadius: controller.getParameterFact(-1, "FENCE_RADIUS") + property Fact _fenceType: controller.getParameterFact(-1, "FENCE_TYPE") + + QGCLabel { + id: geoFenceLabel + text: qsTr("GeoFence") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: geoFenceSettings + width: fenceAltMaxField.x + fenceAltMaxField.width + _margins + height: fenceAltMaxField.y + fenceAltMaxField.height + _margins + color: ggcPal.windowShade + + QGCCheckBox { + id: circleGeo + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + text: qsTr("Circle GeoFence enabled") + checked: _fenceEnable.value != 0 && _fenceType.value & 2 + + onClicked: { + if (checked) { + if (_fenceEnable.value == 1) { + _fenceType.value |= 2 + } else { + _fenceEnable.value = 1 + _fenceType.value = 2 + } + } else if (altitudeGeo.checked) { + _fenceType.value &= ~2 + } else { + _fenceEnable.value = 0 + _fenceType.value = 0 + } + } + } + + QGCCheckBox { + id: altitudeGeo + anchors.topMargin: _margins / 2 + anchors.left: circleGeo.left + anchors.top: circleGeo.bottom + text: qsTr("Altitude GeoFence enabled") + checked: _fenceEnable.value != 0 && _fenceType.value & 1 + + onClicked: { + if (checked) { + if (_fenceEnable.value == 1) { + _fenceType.value |= 1 + } else { + _fenceEnable.value = 1 + _fenceType.value = 1 + } + } else if (circleGeo.checked) { + _fenceType.value &= ~1 + } else { + _fenceEnable.value = 0 + _fenceType.value = 0 + } + } + } + + QGCRadioButton { + id: geoReportRadio + anchors.margins: _margins + anchors.left: parent.left + anchors.top: altitudeGeo.bottom + text: qsTr("Report only") + exclusiveGroup: fenceActionRadioGroup + checked: _fenceAction.value == 0 + + onClicked: _fenceAction.value = 0 + } + + QGCRadioButton { + id: geoRTLRadio + anchors.topMargin: _margins / 2 + anchors.left: circleGeo.left + anchors.top: geoReportRadio.bottom + text: qsTr("RTL or Land") + exclusiveGroup: fenceActionRadioGroup + checked: _fenceAction.value == 1 + + onClicked: _fenceAction.value = 1 + } + + QGCLabel { + id: fenceRadiusLabel + anchors.left: circleGeo.left + anchors.baseline: fenceRadiusField.baseline + text: qsTr("Max radius:") + } + + FactTextField { + id: fenceRadiusField + anchors.topMargin: _margins + anchors.left: fenceAltMaxField.left + anchors.top: geoRTLRadio.bottom + fact: _fenceRadius + showUnits: true + } + + QGCLabel { + id: fenceAltMaxLabel + anchors.left: circleGeo.left + anchors.baseline: fenceAltMaxField.baseline + text: qsTr("Max altitude:") + } + + FactTextField { + id: fenceAltMaxField + anchors.topMargin: _margins / 2 + anchors.leftMargin: _margins + anchors.left: fenceAltMaxLabel.right + anchors.top: fenceRadiusField.bottom + fact: _fenceAltMax + showUnits: true + } + } // Rectangle - GeoFence Settings + } // Column - GeoFence Settings + } + + Loader { + sourceComponent: controller.vehicle.multiRotor ? copterGeoFence : undefined + } + + Component { + id: copterRTL + + Column { + spacing: _margins / 2 + + property Fact _landSpeedFact: controller.getParameterFact(-1, "LAND_SPEED") + property Fact _rtlAltFact: controller.getParameterFact(-1, "RTL_ALT") + property Fact _rtlLoitTimeFact: controller.getParameterFact(-1, "RTL_LOIT_TIME") + property Fact _rtlAltFinalFact: controller.getParameterFact(-1, "RTL_ALT_FINAL") + + QGCLabel { + id: rtlLabel + text: qsTr("Return to Launch") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + id: rtlSettings + width: rltAltFinalField.x + rltAltFinalField.width + _margins + height: rltAltFinalField.y + rltAltFinalField.height + _margins + color: ggcPal.windowShade + + Image { + id: icon + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + height: ScreenTools.defaultFontPixelWidth * 20 + width: ScreenTools.defaultFontPixelWidth * 20 + sourceSize.width: width + mipmap: true + fillMode: Image.PreserveAspectFit + visible: false + source: "/qmlimages/ReturnToHomeAltitude.svg" + } + + ColorOverlay { + anchors.fill: icon + source: icon + color: ggcPal.text + visible: _showIcon + } + + QGCRadioButton { + id: returnAtCurrentRadio + anchors.margins: _margins + anchors.left: _showIcon ? icon.right : parent.left + anchors.top: parent.top + text: qsTr("Return at current altitude") + checked: _rtlAltFact.value == 0 + exclusiveGroup: returnAltRadioGroup + + onClicked: _rtlAltFact.value = 0 + } + + QGCRadioButton { + id: returnAltRadio + anchors.topMargin: _margins + anchors.left: returnAtCurrentRadio.left + anchors.top: returnAtCurrentRadio.bottom + text: qsTr("Return at specified altitude:") + exclusiveGroup: returnAltRadioGroup + checked: _rtlAltFact.value != 0 + + onClicked: _rtlAltFact.value = 1500 + } + + FactTextField { + id: rltAltField + anchors.leftMargin: _margins + anchors.left: returnAltRadio.right + anchors.baseline: returnAltRadio.baseline + fact: _rtlAltFact + showUnits: true + enabled: returnAltRadio.checked + } + + QGCCheckBox { + id: homeLoiterCheckbox + anchors.left: returnAtCurrentRadio.left + anchors.baseline: landDelayField.baseline + checked: _rtlLoitTimeFact.value > 0 + text: qsTr("Loiter above Home for:") + + onClicked: _rtlLoitTimeFact.value = (checked ? 60 : 0) + } + + FactTextField { + id: landDelayField + anchors.topMargin: _margins * 1.5 + anchors.left: rltAltField.left + anchors.top: rltAltField.bottom + fact: _rtlLoitTimeFact + showUnits: true + enabled: homeLoiterCheckbox.checked === true + } + + QGCRadioButton { + id: landRadio + anchors.left: returnAtCurrentRadio.left + anchors.baseline: landSpeedField.baseline + text: qsTr("Land with descent speed:") + checked: _rtlAltFinalFact.value == 0 + exclusiveGroup: landLoiterRadioGroup + + onClicked: _rtlAltFinalFact.value = 0 + } + + FactTextField { + id: landSpeedField + anchors.topMargin: _margins * 1.5 + anchors.top: landDelayField.bottom + anchors.left: rltAltField.left + fact: _landSpeedFact + showUnits: true + enabled: landRadio.checked + } + + QGCRadioButton { + id: finalLoiterRadio + anchors.left: returnAtCurrentRadio.left + anchors.baseline: rltAltFinalField.baseline + text: qsTr("Final loiter altitude:") + exclusiveGroup: landLoiterRadioGroup + + onClicked: _rtlAltFinalFact.value = _rtlAltFact.value + } + + FactTextField { + id: rltAltFinalField + anchors.topMargin: _margins / 2 + anchors.left: rltAltField.left + anchors.top: landSpeedField.bottom + fact: _rtlAltFinalFact + enabled: finalLoiterRadio.checked + showUnits: true + } + } // Rectangle - RTL Settings + } // Column - RTL Settings + } + + Loader { + sourceComponent: controller.vehicle.multiRotor ? copterRTL : undefined + } + + Component { + id: planeRTL + + Column { + spacing: _margins / 2 + + property Fact _rtlAltFact: controller.getParameterFact(-1, "ALT_HOLD_RTL") + + QGCLabel { + text: qsTr("Return to Launch") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: rltAltField.x + rltAltField.width + _margins + height: rltAltField.y + rltAltField.height + _margins + color: qgcPal.windowShade + + QGCRadioButton { + id: returnAtCurrentRadio + anchors.margins: _margins + anchors.left: parent.left + anchors.top: parent.top + text: qsTr("Return at current altitude") + checked: _rtlAltFact.value < 0 + exclusiveGroup: returnAltRadioGroup + + onClicked: _rtlAltFact.value = -1 + } + + QGCRadioButton { + id: returnAltRadio + anchors.topMargin: _margins / 2 + anchors.left: returnAtCurrentRadio.left + anchors.top: returnAtCurrentRadio.bottom + text: qsTr("Return at specified altitude:") + exclusiveGroup: returnAltRadioGroup + checked: _rtlAltFact.value >= 0 + + onClicked: _rtlAltFact.value = 10000 + } + + FactTextField { + id: rltAltField + anchors.leftMargin: _margins + anchors.left: returnAltRadio.right + anchors.baseline: returnAltRadio.baseline + fact: _rtlAltFact + showUnits: true + enabled: returnAltRadio.checked + } + } // Rectangle - RTL Settings + } // Column - RTL Settings + } + + Loader { + sourceComponent: controller.vehicle.fixedWing ? planeRTL : undefined + } + + Column { + spacing: _margins / 2 + + QGCLabel { + text: qsTr("Arming Checks") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: flowLayout.width + height: armingCheckInnerColumn.height + (_margins * 2) + color: ggcPal.windowShade + + Column { + id: armingCheckInnerColumn + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + anchors.right: parent.right + spacing: _margins + + FactBitmask { + id: armingCheckBitmask + anchors.left: parent.left + anchors.right: parent.right + firstEntryIsAll: true + fact: _armingCheck + } + + QGCLabel { + id: armingCheckWarning + anchors.left: parent.left + anchors.right: parent.right + wrapMode: Text.WordWrap + color: qgcPal.warningText + text: qsTr("Warning: Turning off arming checks can lead to loss of Vehicle control.") + visible: _armingCheck.value != 1 + } + } + } // Rectangle - Arming checks + } // Column - Arming Checks + } // Flow + } // Component - safetyPageComponent +} // SetupView diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentSummary.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentSummary.qml new file mode 100644 index 0000000000000000000000000000000000000000..cb9d510d248b33eacc358d44fb250601e1f02d9d --- /dev/null +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentSummary.qml @@ -0,0 +1,142 @@ +import QtQuick 2.3 +import QtQuick.Controls 1.2 + +import QGroundControl.FactSystem 1.0 +import QGroundControl.FactControls 1.0 +import QGroundControl.Controls 1.0 +import QGroundControl.Palette 1.0 + +FactPanel { + id: panel + anchors.fill: parent + color: qgcPal.windowShadeDark + + QGCPalette { id: qgcPal; colorGroupEnabled: enabled } + FactPanelController { id: controller; factPanel: panel } + + + property Fact _copterFenceAction: controller.getParameterFact(-1, "FENCE_ACTION", false /* reportMissing */) + property Fact _copterFenceEnable: controller.getParameterFact(-1, "FENCE_ENABLE", false /* reportMissing */) + property Fact _copterFenceType: controller.getParameterFact(-1, "FENCE_TYPE", false /* reportMissing */) + + property Fact _batt1Monitor: controller.getParameterFact(-1, "BATT_MONITOR") + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) + property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") + property bool _batt1MonitorEnabled: _batt1Monitor.rawValue !== 0 + property bool _batt2MonitorEnabled: _batt2MonitorAvailable && _batt2Monitor.rawValue !== 0 + + property Fact _batt1FSLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT", false /* reportMissing */) + property Fact _batt1FSCritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */) + property Fact _batt2FSLowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */) + property Fact _batt2FSCritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */) + property bool _batt1FSCritActAvailable: controller.parameterExists(-1, "BATT_FS_CRT_ACT") + + Column { + anchors.fill: parent + + VehicleSummaryRow { + labelText: qsTr("Arming Checks:") + valueText: fact.value & 1 ? qsTr("Enabled") : qsTr("Some disabled") + + property Fact fact: controller.getParameterFact(-1, "ARMING_CHECK") + } + + VehicleSummaryRow { + labelText: qsTr("Throttle failsafe:") + valueText: Fact.enumStringValue + visible: controller.vehicle.multiRotor + + property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("Throttle failsafe:") + valueText: fact.enumStringValue + visible: controller.vehicle.fixedWing + + property Fact fact: controller.getParameterFact(-1, "THR_FAILSAFE", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("Throttle failsafe:") + valueText: fact.enumStringValue + visible: controller.vehicle.rover + + property Fact fact: controller.getParameterFact(-1, "FS_THR_ENABLE", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("Failsafe Action:") + valueText: fact.enumStringValue + visible: controller.vehicle.rover + + property Fact fact: controller.getParameterFact(-1, "FS_ACTION", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("Failsafe Crash Check:") + valueText: fact.enumStringValue + visible: controller.vehicle.rover + + property Fact fact: controller.getParameterFact(-1, "FS_CRASH_CHECK", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("Batt1 low failsafe:") + valueText: _batt1MonitorEnabled ? _batt1FSLowAct.enumStringValue : "" + visible: _batt1MonitorEnabled + } + + VehicleSummaryRow { + labelText: qsTr("Batt1 critical failsafe:") + valueText: _batt1FSCritActAvailable ? _batt1FSCritAct.enumStringValue : "" + visible: _batt1FSCritActAvailable + } + + VehicleSummaryRow { + labelText: qsTr("Batt2 low failsafe:") + valueText: _batt2MonitorEnabled ? _batt2FSLowAct.enumStringValue : "" + visible: _batt2MonitorEnabled + } + + VehicleSummaryRow { + labelText: qsTr("Batt2 critical failsafe:") + valueText: _batt2MonitorEnabled ? _batt2FSCritAct.enumStringValue : "" + visible: _batt2MonitorEnabled + } + + VehicleSummaryRow { + labelText: qsTr("GeoFence:") + valueText: _copterFenceEnable.value == 0 || _copterFenceType == 0 ? + qsTr("Disabled") : + (_copterFenceType.value == 1 ? + qsTr("Altitude") : + (_copterFenceType.value == 2 ? qsTr("Circle") : qsTr("Altitude,Circle"))) + visible: controller.vehicle.multiRotor + } + + VehicleSummaryRow { + labelText: qsTr("GeoFence:") + valueText: _copterFenceAction.value == 0 ? + qsTr("Report only") : + (_copterFenceAction.value == 1 ? qsTr("RTL or Land") : qsTr("Unknown")) + visible: controller.vehicle.multiRotor && _copterFenceEnable.value !== 0 + } + + VehicleSummaryRow { + labelText: qsTr("RTL min alt:") + valueText: fact.value == 0 ? qsTr("current") : fact.valueString + " " + fact.units + visible: controller.vehicle.multiRotor + + property Fact fact: controller.getParameterFact(-1, "RTL_ALT", false /* reportMissing */) + } + + VehicleSummaryRow { + labelText: qsTr("RTL min alt:") + valueText: fact.value < 0 ? qsTr("current") : fact.valueString + " " + fact.units + visible: controller.vehicle.fixedWing + + property Fact fact: controller.getParameterFact(-1, "ALT_HOLD_RTL", false /* reportMissing */) + } + } +} diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 667c17728e9f7002866dfd521030525c53981b89..416a618514978c54d63249d4686c8125c81d9d62 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -785,6 +785,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); } else if (majorVersion == 3) { switch (minorVersion) { + case 0: + case 1: + case 2: case 3: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); case 4: @@ -792,11 +795,8 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) case 5: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); case 6: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"); default: - if (minorVersion < 3) { - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); - } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml"); } } return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); @@ -812,6 +812,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); } else if (majorVersion == 3) { switch (minorVersion) { + case 0: + case 1: + case 2: case 3: case 4: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); @@ -820,10 +823,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); case 7: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"); + case 8: default: - if (minorVersion < 3) { - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); - } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); } } return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); @@ -836,8 +838,12 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) case 0: case 1: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); - default: + case 2: + case 3: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); + case 4: + default: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml"); } } return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml index a072cb23bd537e304767f855492b3932e7e16494..6dc5898b6150168e35db0459caa88979938813b5 100644 --- a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml @@ -5,21 +5,12 @@ - -True - 1 255 1 255 - - -Disabled -Enabled - - 1 10 1 @@ -27,10 +18,11 @@ 0 30 1 -seconds +s +seconds -0:Roll,1:Pitch,2:Yaw +0:Roll,1:Pitch,2:Yaw,3:Steering,4:Landing 0 1 @@ -43,17 +35,20 @@ 0 15 0.1 -Degrees +deg +degrees 0 1000 1 -meters +m +meters 0 100 1 -meters +m +meters @@ -72,55 +67,70 @@ 0 30 0.1 m/s +meters per second 0 30 0.1 m/s/s +meters per square second 0 127 1 -0.1 seconds +ds +deciseconds -100 100 1 -Percent +% +percent 0 30 0.1 m/s +meters per second 0 30 0.1 m/s +meters per second - -0 127 + +-1 127 1 -percent +%/s +percent per second 0 10 0.5 -seconds +s +seconds 0 100 -Percent +% +percent 0 45 1 -degrees +deg +degrees - + 0:AUTO_ALWAYS,1:AUTO_LAND,2:AUTO_LOITER_TO_ALT,3:AUTO_LOITER_ALL,4:AUTO_WAYPOINTS,5:LOITER,6:RTL,7:CIRCLE,8:CRUISE,9:FBWB,10:GUIDED + +Never +AutoAlways +AutoLanding + @@ -136,27 +146,32 @@ -32767 32767 1 -Meters +m +meters 1 32767 1 -Meters +m +meters 0 32767 1 -Meters +m +meters -32767 32767 1 -Meters +m +meters -32767 32767 1 -Meters +m +meters @@ -174,17 +189,20 @@ 0 32767 1 -meters +m +meters 0 32767 1 -meters +m +meters 0 32767 1 -meters +m +meters @@ -209,11 +227,13 @@ 5 100 1 m/s +meters per second 5 100 1 m/s +meters per second @@ -229,37 +249,44 @@ 0 10000 -meters +m +meters 1 10 0.1 m/s +meters per second -100 100 1 -Percent +% +percent 0 100 1 -Percent +% +percent 0 100 1 -Percent +% +percent - + 0 127 1 -Percent +%/s +percent per second 0 100 1 -Percent +%/s +percent per second @@ -286,7 +313,8 @@ 0 100 1 -Percent +% +percent @@ -299,12 +327,14 @@ CIRCLE/no change(if already in AUTO|GUIDED|LOITER) CIRCLE FBWA +Disable 1 100 0.5 -seconds +s +seconds @@ -317,15 +347,8 @@ 1 300 0.5 -seconds - - -0.1 -Volts - - -50 -mAh +s +seconds @@ -501,27 +524,32 @@ 0 9000 1 -centi-Degrees +cdeg +centidegrees 0 9000 1 -centi-Degrees +cdeg +centidegrees -9000 0 1 -centi-Degrees +cdeg +centidegrees 10 500 1 -degrees/second +deg/s +degrees per second 10 500 1 -degrees/second +deg/s +degrees per second @@ -532,69 +560,21 @@ -100 100 0.1 -Meters +m +meters 10 360 1 -degrees/second - - - -Disabled -Enabled - - - - -Disabled -Enabled - +deg/s +degrees per second - + Disabled Enabled - - -Disabled -Enabled - - - - -Disabled -Enabled - - - - -Disabled -UpUp -UpDown -DownUp -DownDown -UpUpSwap -UpDownSwap -DownUpSwap -DownDownSwap - - - - -Disabled -UpUp -UpDown -DownUp -DownDown -UpUpSwap -UpDownSwap -DownUpSwap -DownDownSwap - - 0.5 1.2 @@ -606,13 +586,16 @@ -1000 1000 -percent +d% +decipercent --1000 1000 -percent +-100 100 +% +percent +True 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,19:IMU_RAW @@ -627,21 +610,27 @@ cm/s +centimeters per second m/s +meters per second cm/s +centimeters per second -centi-Degrees +cdeg +centidegrees -centimeters +cm +centimeters -centimeters +cm +centimeters @@ -649,38 +638,29 @@ Enabled - - - - -Disabled -UpUp -UpDown -DownUp -DownDown -UpUpSwap -UpDownSwap -DownUpSwap -DownDownSwap - + 0 100 -Percent +% +percent 0 100 1 m/s +meters per second 0 100 -Percent +% +percent 0 100 1 m/s +meters per second @@ -704,6 +684,7 @@ Disabled Enabled +True @@ -714,7 +695,8 @@ 0 90 0.1 -degrees +deg +degrees @@ -723,15 +705,10 @@ Enable - go directly to landing sequence - - -Disable -Enable - - -10 127 +10 127 m/s/s +meters per square second 0:Disarm @@ -744,1588 +721,1297 @@ Enabled - - - -True - - -True + -ArduPlane -AntennaTracker -Copter -Rover +NotEnforced +Enforced - -1 255 + +0 100 +1 +% +percent - + +0:Chan1,1:Chan2,2:Chan3,3:Chan4,4:Chan5,5:Chan6,6:Chan7,7:Chan8,8:Chan9,9:Chan10,10:Chan11,11:Chan12,12:Chan13,13:Chan14,14:Chan15,15:Chan16 + + +-1 127 -Mission Planner and DroidPlanner - AP Planner 2 +Never reset +Always reset +m +meters - + + + Disabled Enabled - -0 10 -.5 -Hz + +1 100 - -0.0 1000.0 -10 -Centimeters + +1 100000 - -0.0 500.0 -10 + +-1 16777215 - -0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection + -None -Feedback from mid stick -High throttle cancels landing -Disarm on land detection +NoInfo +Light +Small +Large +HighVortexlarge +Heavy +HighlyManuv +Rotocraft +RESERVED +Glider +LightAir +Parachute +UltraLight +RESERVED +UAV +Space +RESERVED +EmergencySurface +ServiceSurface +PointObstacle - -0 30 -1 -seconds - - -0:Roll,1:Pitch,2:Yaw + -None -Roll -Pitch -Yaw +NO_DATA +L15W23 +L25W28P5 +L25W34 +L35W33 +L35W38 +L45W39P5 +L45W45 +L55W45 +L55W52 +L65W59P5 +L65W67 +L75W72P5 +L75W80 +L85W80 +L85W90 - -0 8000 -1 -Centimeters - - -0.5 10.0 + -Disabled -Shallow -Steep +NoData +Left2m +Left4m +Left6m +Center +Right2m +Right4m +Right6m -.1 - - -0 2000 -50 -cm/s - - -0.01 2.0 -0.01 - + -Disabled -Land -RTL +NO_DATA +AppliedBySensor - -0.1 -Volts - - -50 -mAh - - + Disabled -Enabled always RTL -Enabled Continue with Mission in Auto Mode +Rx-Only +Tx-Only +Rx and Tx Enabled - -100 900 + +octal +octal - + +0:UAT_in,1:1090ES_in,2:UAT_out,3:1090ES_out -Disabled -Enabled +Unknown +Rx UAT only +Rx UAT and 1090ES +Rx&Tx UAT and 1090ES - - -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 + - -0 500 -10 -cm/s + - -50 500 -10 -Centimeters/Second + - -50 500 -10 -cm/s/s + - - -Disabled -Enabled always RTL -Enabled Continue with Mission in Auto Mode -Enabled always LAND - + - -925 1100 -1 -pwm + - -0 300 -1 -pwm - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - -Stabilize -Acro -AltHold -Auto -Guided -Loiter -RTL -Circle -Land -Drift -Sport -Flip -AutoTune -PosHold -Brake -Throw -Avoid_ADSB -Guided_NoGPS -SmartRTL - - - - - -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,17:MOTBATT,18:IMU_FAST,19:IMU_RAW - -Default -Default+RCIN -Default+IMU -Default+Motors -NearlyAll-AC315 -NearlyAll -All+FastATT -All+MotBatt -All+FastIMU -All+FastIMU+PID -All+FullIMU -Disabled - + +m +meters - - -Normal Start-up -Start-up in ESC Calibration mode if throttle high -Start-up in ESC Calibration mode regardless of throttle -Start-up and automatically calibrate ESCs -Disabled - + +m +meters - - -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 + +mbar +millibar - -0 32767 + - - -Plus -X -V -H -V-Tail -A-Tail -Y6B - + - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - - -Do Nothing -Flip -Simple Mode -RTL -Save Trim -Save WP -Camera Trigger -RangeFinder -Fence -Super Simple Mode -Acro Trainer -Sprayer -Auto -AutoTune -Land -Gripper -Parachute Enable -Parachute Release -Parachute 3pos -Auto Mission Reset -AttCon Feed Forward -AttCon Accel Limits -Retract Mount -Relay On/Off -Relay2 On/Off -Relay3 On/Off -Relay4 On/Off -Landing Gear -Lost Copter Sound -Motor Emergency Stop -Motor Interlock -Brake -Throw -Avoidance -PrecLoiter -Object Avoidance -ArmDisarm - - - -0 127 -Seconds + - -1000 8000 -Centi-degrees + - -0 100 - -Very Soft -Soft -Medium -Crisp -Very Crisp - -10 + - -4 12 -deg/sec + - -2000 4500 -Centi-degrees + +s +seconds - + + + +0.0 1.0 +.01 + + -No repositioning -Repositioning +Disabled +Enabled - + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s +meters per second + + +-0.1745 +0.1745 +0.01 +rad +radians + + +-0.1745 +0.1745 +0.01 +rad +radians + + +-0.1745 +0.1745 +0.01 +rad +radians + + -Land -AltHold -Land even in Stabilize +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 +Custom - -0.6:Strict, 0.8:Default, 1.0:Relaxed + +0.001 0.5 +.01 + + +0 10 +1 - + Disabled -Enabled +Enable EKF2 +Enable EKF3 - -50 490 + +-180 180 1 -Hz - - -1 10 - - -1 10 +deg +degrees - -0 3 -0.1 + +-180 180 +1 +deg +degrees - -0 3 -0.1 + +-180 180 +1 +deg +degrees - + + + Disabled -Leveling -Leveling and Limited +ArmingOnly +ArmOrDisarm - --0.5 1.0 + Disabled -Very Low -Low -Medium -High -Very High +THR_MIN PWM when disarmed +0 PWM when disarmed - -0.1 6.0 -0.1 + +0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration + +None +All +Barometer +Compass +GPS Lock +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Channels +Board voltage +Battery Level +Airspeed +LoggingAvailable +Hardware safety switch +GPS configuration + - -0.02 1.00 -0.01 + +0.25 3.0 +m/s/s +meters per square second - -0 4500 -10 -cm/s/s + +0.1 +V +volt - -1.000 8.000 + +0.1 +V +volt - -0.500 1.500 -0.05 + + + + +None +I2C-MS4525D0 +Analog +I2C-MS5525 +I2C-MS5525 (0x76) +I2C-MS5525 (0x77) +I2C-SDP3X + - -0.000 3.000 + + +Don't Use +use +UseWhenZeroThrottle + - -0 1000 -Percent*10 + +0.1 - -0.000 0.400 + +0.1 - -1.000 100.000 -Hz + - -1.000 3.000 + - -0.500 2.000 + - -0:Roll,1:Pitch,2:Yaw + -All -Roll Only -Pitch Only -Yaw Only -Roll and Pitch -Roll and Yaw -Pitch and Yaw +Disable +Enable - -0.05 0.10 - - -0.001 0.006 + - + -Stopped -Running +Bus0(internal) +Bus1(external) +Bus2(auxillary) - + -Do Not Use in RTL and Land -Use in RTL and Land +FirstSensor +2ndSensor - -0 5 - - + -Auto -Guided -RTL -Land -Brake -Throw +None +I2C-MS4525D0 +Analog +I2C-MS5525 +I2C-MS5525 (0x76) +I2C-MS5525 (0x77) +I2C-SDP3X - + -Upward Throw -Drop +Don't Use +use +UseWhenZeroThrottle - - -Disabled -Enabled - + +0.1 - -0:ADSBMavlinkProcessing + +0.1 - --0.5 1.0 - -Disabled -Very Low -Low -Medium -High -Very High - + - -0 1 + + + - + -Undefined -Quad -Hexa -Octa -OctaQuad -Y6 -Heli -Tri -SingleCopter -CoaxCopter +Disable +Enable - - - + - -True + -ArduPlane -AntennaTracker -Copter -Rover +Bus0(internal) +Bus1(external) +Bus2(auxillary) - -1 255 - - -1 255 - - -1 255 - - + + + Disabled Enabled - -0 20 -0.1 -seconds + + +Remain in AVOID_ADSB +Resume previous flight mode +RTL +Resume if AUTO else Loiter + - -0 20 -0.1 -seconds + - -0 100 -1 -degrees/second + +s +seconds - -0 20 -1 -seconds + +s +seconds - --90 90 -0.000001 -degrees + +m +meters - --180 180 -0.000001 -degrees + +m +meters - -0 10 -0.1 -seconds + +m +meters + + +m +meters + + +m +meters - + + + -Position -OnOff -ContinuousRotation +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell +UAVCAN-BatteryInfo +True - + -Position -OnOff -ContinuousRotation +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 +True - -0 50 -0.1 -degrees/second + + +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + +True - -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 + +A/V +ampere per volt - -0 360 -0.1 -degrees - - -0 100 -1 -meters + +V +volt - - -Barometer -GPS -GPS vehicle only - + +50 +mAh +milliampere hour - -1 10 + 1 -Hz +W +watt - --90 0 -1 -Degrees + - -0 90 + +0 120 1 -Degrees +s +seconds - -0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS + -Default -Disabled +Raw Voltage +Sag Compensated Voltage - -0.0 3.0 -0.01 - - -0.0 3.0 -0.01 - - -0 4000 -10 -Percent*10 - - -0.001 0.1 -0.001 - - -0.0 3.0 -0.01 - - -0.0 3.0 -0.01 - - -0 4000 -10 -Percent*10 - - -0.001 0.1 -0.001 + +0.1 +V +volt - -1 255 + +50 +mAh +milliampere hour - - - + +0.1 +V +volt - -True + +50 +mAh +milliampere hour - -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,19:IMU_RAW + -Disabled -APM2-Default -PX4/Pixhawk-Default +None +RTL +Land +Terminate - - - - - + -MANUAL -LEARNING -STEERING -HOLD -AUTO -RTL -GUIDED +None +RTL +Land +Terminate - -1 255 - - -1 255 - - + + + Disabled -Enabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell +UAVCAN-BatteryInfo +True - -0 30 -1 -seconds - - -0:Steering,1:Throttle + -None -Steering -Throttle +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 +True - + -Disabled -Enabled +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 +True - - -Disabled -APM TriggerPin0 -APM TriggerPin1 -APM TriggerPin2 -APM TriggerPin3 -APM TriggerPin4 -APM TriggerPin5 -APM TriggerPin6 -APM TriggerPin7 -APM TriggerPin8 -Pixhawk TriggerPin50 -Pixhawk TriggerPin51 -Pixhawk TriggerPin52 -Pixhawk TriggerPin53 -Pixhawk TriggerPin54 -Pixhawk TriggerPin55 - - - -0 20 -0.1 -m/s/s + - -0 100 -0.1 -m/s + +A/V +ampere per volt - -0 100 -1 -percent + +V +volt - -0 100 -0.1 -meters + +50 +mAh +milliampere hour - -0 100 + 1 -percent +W +watt - -0 100 -1 -m/s + - -0 360 + +0 120 1 -degrees +s +seconds - + -Nothing -LearnWaypoint +Raw Voltage +Sag Compensated Voltage - -0 100 -1 -Percent + +0.1 +V +volt - -0 100 -1 -Percent + +50 +mAh +milliampere hour - -0 100 -1 -Percent + +0.1 +V +volt - -0 100 -1 -Percent + +50 +mAh +milliampere hour - + -Disabled -SkidSteeringOutput +None +RTL +Land +Terminate - + -Disabled -SkidSteeringInput +None +RTL +Land +Terminate - + + + -Nothing -RTL -HOLD +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture +True - -seconds - - + Disabled Enabled +Auto +True - -925 1100 -1 + + +Disabled +Enabled +Auto + +True - + Disabled Enabled +True - + Disabled -HOLD -HoldAndDisarm +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz +True - -0 1000 -1 -centimeters + +-32768 32767 - --45 45 -1 -centimeters + +0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 + +Disabled +Enabled + +True - -0 100 -0.1 -seconds + +-1 80 +degC +degrees Celsius - -1 100 -1 + + +AUTO +PX4V1 +Pixhawk +Cube/Pixhawk2 +Pixracer +PixhawkMini +Pixhawk2Slim +VRBrain 5.1 +VRBrain 5.2 +VR Micro Brain 5.1 +VR Micro Brain 5.2 +VRBrain Core 1.0 +VRBrain 5.4 +Intel Aero FC +AUAV2.1 + +True - + + +Disabled +Enabled + +True - + +0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed - + + + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +None +CYRF6936 - + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +Auto +DSM2 +DSMX - + +0 4 + + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +NotDisabled +Disabled - + +0 16 + + +0 16 + + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +Disabled +Enabled - + +1 8 + + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +Disabled +MinChannel +MidChannel +MaxChannel +MinChannelCW +MidChannelCW +MaxChannelCW - + -Manual -LEARNING -STEERING -HOLD -Auto -RTL -Guided +Mode1 +Mode2 - -0 1000 -0.1 -meters - - -0.2 10 -0.1 -gravities - - - - + Disabled -Enabled +TestChan1 +TestChan2 +TestChan3 +TestChan4 +TestChan5 +TestChan6 +TestChan7 +TestChan8 - -1 100 + +0 16 - -1 100000 + +0 16 - --1 16777215 + +1 8 - + +0 40 + + +0 120 + + +0 31 + + + + +0:GPS,1:MAVLINK_SYSTEM_TIME,2:HW + + + + -NoInfo -Light -Small -Large -HighVortexlarge -Heavy -HighlyManuv -Rotocraft -RESERVED -Glider -LightAir -Parachute -UltraLight -RESERVED -UAV -Space -RESERVED -EmergencySurface -ServiceSurface -PointObstacle +Disabled +Enabled - + -NO_DATA -L15W23 -L25W28P5 -L25W34 -L35W33 -L35W38 -L45W39P5 -L45W45 -L55W45 -L55W52 -L65W59P5 -L65W67 -L75W72P5 -L75W80 -L85W80 -L85W90 +Disabled +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 - + -NoData -Left2m -Left4m -Left6m -Center -Right2m -Right4m -Right6m +Disabled +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 - + -NO_DATA -AppliedBySensor +Disabled +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 -Rx-Only -Tx-Only -Rx and Tx Enabled +Disabled +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 + +0 3600 + - - + + + +Servo +Relay + - + +0 50 +ds +deciseconds - + +1000 2000 +PWM +PWM in microseconds - + +1000 2000 +PWM +PWM in microseconds - + +0 1000 +m +meters - + + +Low +High + - + +0 10000 +ms +milliseconds - + +0 180 +deg +degrees - -meters + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + - -meters + + +TriggerLow +TriggerHigh + - -millibar + + +Always +Only when in AUTO + - + + + + +Disabled +UAVCAN + +True - + + + +1 250 - + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 - + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 - + +1 200 +Hz +hertz - + + + + +Disabled +UAVCAN + +True - -seconds + + + +1 250 + + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + + +1 200 +Hz +hertz - - -0.0 1.0 -.01 + + + +Disabled +UAVCAN + +True + + + + +1 250 - + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + + +1 200 +Hz +hertz + + + + Disabled -Enabled +First driver +Second driver +True - -0.1 0.4 -.01 + +10000 1000000 - -0.1 0.4 -.01 + + +Disabled +Major messages +All messages + - -0 127 -1 -m/s + + + + +Disabled +First driver +Second driver + +True - --0.1745 +0.1745 -0.01 -Radians + +10000 1000000 - --0.1745 +0.1745 -0.01 -Radians + + +Disabled +Major messages +All messages + - --0.1745 +0.1745 -0.01 -Radians + + + + +Disabled +First driver +Second driver + +True - + +10000 1000000 + + -None -Yaw45 -Yaw90 -Yaw135 -Yaw180 -Yaw225 -Yaw270 -Yaw315 -Roll180 -Roll180Yaw45 -Roll180Yaw90 -Roll180Yaw135 +Disabled +Major messages +All messages + + + + + + +Disabled +Enabled + + + + +First Relay +Second Relay +Third Relay +Fourth Relay +Servo + + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + +0 32000 +1 +m +meters + + +0 5000 +1 +ms +milliseconds + + + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-3.142 3.142 +0.01 +rad +radians + + + +Disabled +Internal-Learning +EKF-Learning + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 Pitch180 Roll180Yaw225 Roll180Yaw270 @@ -2337,7 +2023,7 @@ Roll270 Roll270Yaw45 Roll270Yaw90 -Roll270Yaw136 +Roll270Yaw135 Pitch90 Pitch270 Pitch180Yaw90 @@ -2352,1116 +2038,593 @@ Roll270Pitch270 Roll90Pitch180Yaw90 Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 - -0.001 0.5 -.01 - - -0 10 -1 - - + -Disabled -Enable EKF2 -Enable EKF3 +Internal +External +ForcedExternal - - - - -Disabled -THR_MIN PWM when disarmed -0 PWM when disarmed - + +-400 400 +1 +mGauss +milligauss - -0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration - -None -All -Barometer -Compass -GPS Lock -INS(INertial Sensors - accels & gyros) -Parameters(unused) -RC Failsafe -Board voltage -Battery Level -Airspeed -LoggingAvailable -Hardware safety switch -GPS configuration - + +-400 400 +1 +mGauss +milligauss - -0.25 3.0 -m/s/s + +-400 400 +1 +mGauss +milligauss - -0.1 -Volts + +-1000 1000 +1 +mGauss/A +milligauss per ampere - -0.1 -Volts + +-1000 1000 +1 +mGauss/A +milligauss per ampere - - - - -None -I2C-MS4525D0 -Analog -I2C-MS5525 - + +-1000 1000 +1 +mGauss/A +milligauss per ampere - + -Use -Don't Use +FirstCompass +SecondCompass +ThirdCompass - -0.1 - - -0.1 - - - - + +-400 400 +1 +mGauss +milligauss - + +-400 400 +1 +mGauss +milligauss - - -Disable -Enable - + +-400 400 +1 +mGauss +milligauss - + +-1000 1000 +1 +mGauss/A +milligauss per ampere - - -Bus0 -Bus1 - + +-1000 1000 +1 +mGauss/A +milligauss per ampere - - - -500 18000 -100 -Centi-Degrees/Sec + +-1000 1000 +1 +mGauss/A +milligauss per ampere - -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 +Enabled -1000 -Centi-Degrees/Sec/Sec - + -Disabled -Enabled - - - -3.000 12.000 - - -3.000 12.000 - - -3.000 6.000 - - -0.5 10.0 - - -0.08 0.30 -0.005 - - -0.01 0.5 -0.01 - - -0 1 -0.01 -Percent - - -0.0 0.02 -0.001 - - -1 100 -1 -Hz - - -0.08 0.30 -0.005 +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 + - -0.01 0.5 -0.01 + + +Internal +External +ForcedExternal + - -0 1 -0.01 -Percent + + +Disabled +Enabled + - -0.0 0.02 -0.001 + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 + - -1 100 -1 -Hz + + +Internal +External +ForcedExternal + - -0.10 0.50 -0.005 + - -0.010 0.05 -0.01 + - -0 1 -0.01 -Percent + - -0.000 0.02 -0.001 + - -1 100 -1 -Hz + - -0.1 0.25 + - -0.5 0.9 + - -0.5 0.9 + - - -Disabled 1 - + - -0 1000 -Centi-Degrees + - -0.08 0.35 -0.005 + - -0.01 0.6 -0.01 + - -0 1 -0.01 + - -0.001 0.03 -0.001 + - -1 20 -1 -Hz + - -0.08 0.35 -0.005 + - -0.01 0.6 -0.01 + - -0 1 -0.01 + - -0.001 0.03 -0.001 + +4 32 + +Very Strict +Strict +Default +Relaxed + +0.1 - -1 20 + +500 3000 1 -Hz - - -0.180 0.60 -0.005 - -0.01 0.06 -0.01 - - -0 1 -0.01 + +0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883 - -0.000 0.02 -0.001 - - -1 20 + +0 100 1 -Hz +% +percent - - + + Disabled Enabled - - -Remain in AVOID_ADSB -Resume previous flight mode -RTL -Resume if AUTO else Loiter - + +0 2 +0.01 - + - -seconds + - -seconds + - -meters + - -meters + - -meters + - -meters + - - - -0:StopAtFence,1:UseProximitySensor - -None -StopAtFence -UseProximitySensor -All - + - -0 4500 + + + - -3 30 -meters + + + - - + + Disabled -Analog Voltage Only -Analog Voltage and Current -Solo -Bebop -SMBus-Maxell +Enabled +True - + -Disabled -A0 -A1 -Pixhawk -A13 -PX4 +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS - - -Disabled -A1 -A2 -Pixhawk -A12 -PX4 - + +0.05 5.0 +0.05 +m/s +meters per second - + +0.05 5.0 +0.05 +m/s +meters per second - -Amps/Volt + +100 1000 +25 - -Volts + +0.1 10.0 +0.1 +m +meters - -50 -mAh + +100 1000 +25 - -1 -Watts - - - -Disabled -Analog Voltage Only -Analog Voltage and Current -Solo -Bebop -SMBus-Maxell - - - - -Disabled -A0 -A1 -Pixhawk -A13 -PX4 - - - - -Disabled -A1 -A2 -Pixhawk -A12 -PX4 - - - - - -Amps/Volt - - -Volts - - -50 -mAh - - -1 -Amps - - - - - -None -Pozyx - - - --90 90 -0.000001 -degrees - - --180 180 -0.000001 -degrees - - -0 10000 -1 -meters - - --180 +180 -1 -degrees - - - - - -No PWMs -Two PWMs -Four PWMs -Six PWMs -Three PWMs and One Capture - -True - - - -Disabled -Enabled -Auto - -True - - - -Disabled -Enabled -Auto - -True + +10 100 +5 +m +meters - - -Disabled -Enabled - + +0 250 +10 +ms +milliseconds True - + -Disabled -50Hz -75Hz -100Hz -150Hz -200Hz -250Hz -300Hz +Use Baro +Use Range Finder +Use GPS +Use Range Beacon True - --32767 32768 - - - -Disabled -Enabled -Dynamic ID/Update - - - -0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 - -Disabled -Enabled - -True + +0.1 10.0 +0.1 +m +meters - --1 80 -degreesC + +100 1000 +25 - - -AUTO -PX4V1 -Pixhawk -Pixhawk2 -Pixracer -PixhawkMini -Pixhawk2Slim -VRBrain 5.1 -VRBrain 5.2 -VR Micro Brain 5.1 -VR Micro Brain 5.2 -VRBrain Core 1.0 -VRBrain 5.4 - + +0 250 +10 +ms +milliseconds True - - - - -Disabled -Enabled - - - - -Disabled -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 -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 -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 - + +0.01 0.5 +0.01 +Gauss +gauss - + -Disabled -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 +When flying +When manoeuvring +Never +After first climb yaw reset +Always - -0 3600 - - - - - -Servo -Relay - + +100 1000 +25 - -0 50 -deciseconds + +0.5 5.0 +0.1 +m/s +meters per second - -1000 2000 -pwm + +100 1000 +25 - -1000 2000 -pwm + +0.1 10.0 +0.1 +m +meters - -0 1000 -meters + +100 1000 +25 - - -Low -High - - - -0 10000 -milliseconds - - -0 180 -Degrees - - - -Disabled -PX4 AUX1 -PX4 AUX2 -PX4 AUX3 -PX4 AUX4(fast capture) -PX4 AUX5 -PX4 AUX6 - - - - -TriggerLow -TriggerHigh - - - - - - -Disabled -Enabled - - - - -First Relay -Second Relay -Third Relay -Fourth Relay -Servo - - - -1000 2000 -1 -pwm - - -1000 2000 -1 -pwm - - -0 32000 -1 -Meters - - -0 5000 -1 -Milliseconds - - - - -0 10000 -100 -cm - - --90 90 -1 -deg/s - - - - --400 400 -1 -milligauss - - --400 400 -1 -milligauss - - --400 400 -1 -milligauss - - --3.142 3.142 -0.01 -Radians - - - -Disabled -Internal-Learning -EKF-Learning - - - - -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 -ForcedExternal - - - --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 - + +1.0 4.0 +0.1 +rad/s +radians per second - - -Internal -External -ForcedExternal - + +0.05 1.0 +0.05 +rad/s +radians per second - - -Disabled -Enabled - + +100 1000 +25 - - -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 - + +0 127 +10 +ms +milliseconds +True - - -Internal -External -ForcedExternal - + +0.0001 0.1 +0.0001 +rad/s +radians per second - + +0.01 1.0 +0.01 +m/s/s +meters per square second - + +0.00001 0.001 +rad/s/s +radians per square second - + +0.000001 0.001 +Hz +hertz - + +0.00001 0.001 +m/s/s/s +meters per cubic second - + +0.01 1.0 +0.1 +m/s/s +meters per square second - + +0.0 1.0 +0.1 - + +0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed - + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True - + +50 200 +% +percent - + +0.5 50.0 +m +meters - + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True - + +0.05 1.0 +0.05 +rad +radians - + +100 1000 +25 - + +10 50 +5 +cs +centiseconds - + +0.00001 0.01 +Gauss/s +gauss per second - + +0.00001 0.01 +Gauss/s +gauss per second - + +-1 70 +1 +% +percent - + +0 0.2 +0.01 - -4 32 - -Very Strict -Strict -Default -Relaxed - + +0.1 10.0 0.1 +m +meters + + +100 1000 +25 + + +0 127 +10 +ms +milliseconds +True + + +2.0 6.0 +0.5 +m/s +meters per second + + +0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF +True + + +0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position +True - - + + Disabled Enabled +True - + GPS 3D Vel and 2D Pos GPS 2D vel and 2D pos @@ -3469,67 +2632,71 @@ No GPS - + 0.05 5.0 0.05 m/s +meters per second - + 0.05 5.0 0.05 m/s +meters per second - + 100 1000 25 - + 0.1 10.0 0.1 m +meters - + 100 1000 25 - + 10 100 5 m +meters - -0 250 -10 -milliseconds - - + Use Baro Use Range Finder Use GPS Use Range Beacon +True - + 0.1 10.0 0.1 m +meters - + 100 1000 25 - + 0 250 10 -milliseconds +ms +milliseconds +True - + 0.01 0.5 0.01 -gauss +Gauss +gauss - + When flying When manoeuvring @@ -3537,1920 +2704,2212 @@ After first climb yaw reset Always +True - + 100 1000 25 - + 0.5 5.0 0.1 m/s +meters per second - + 100 1000 25 - + 0.1 10.0 0.1 m +meters - + 100 1000 25 - + 1.0 4.0 0.1 rad/s +radians per second - + 0.05 1.0 0.05 rad/s +radians per second - + 100 1000 25 - + 0 250 10 -milliseconds +ms +milliseconds +True - + 0.0001 0.1 0.0001 rad/s +radians per second - + 0.01 1.0 0.01 m/s/s +meters per square second - + 0.00001 0.001 rad/s/s +radians per square second - -0.000001 0.001 -1/s - - + 0.00001 0.001 m/s/s/s +meters per cubic second - + 0.01 1.0 0.1 m/s/s +meters per square second - + 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 + +0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed - + 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True - + 50 200 % +percent - + 0.5 50.0 m +meters - + 0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True - + 0.05 1.0 0.05 rad +radians - + 100 1000 25 - + 10 50 5 cs +centiseconds - + 0.00001 0.01 -gauss/s +Gauss/s +gauss per second - + 0.00001 0.01 -gauss/s +Gauss/s +gauss per second - + -1 70 1 % +percent - + 0 0.2 0.01 - + 0.1 10.0 0.1 m +meters - + 100 1000 25 - + 0 250 10 -milliseconds +ms +milliseconds +True - + 2.0 6.0 0.5 m/s +meters per second + + +0.5 2.5 +0.1 +m/s/s +meters per square second + + +0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF +True + + +0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position +True + + +0.05 0.5 +0.05 +m/s +meters per second + + +0.5 5.0 +0.1 +m/s +meters per second + + +0.01 1.0 +0.1 +m/s +meters per second - - + + Disabled Enabled - - -GPS 3D Vel and 2D Pos -GPS 2D vel and 2D pos -GPS 2D pos -No GPS - + +-200 +200 +1 - -0.05 5.0 -0.05 -m/s + +-200 +200 +1 - -0.05 5.0 -0.05 -m/s + +-18000 +18000 +1 - -100 1000 -25 + +m +meters - -0.1 10.0 -0.1 + m +meters - -100 1000 -25 + +m +meters - -10 100 -5 + +0 127 + + + + +True +True +1 +Pa +pascal + + +True +1 +degC +degrees Celsius + + +0.1 m +meters - + -Use Baro -Use Range Finder -Use GPS -Use Range Beacon +FirstBaro +2ndBaro +3rdBaro - -0.1 10.0 -0.1 -m + + +Disabled +Bus0 +Bus1 + - -100 1000 -25 + +1.0:Freshwater,1.024:Saltwater - -0 250 -10 -milliseconds + +True +True +1 +Pa +pascal + + +True +True +1 +Pa +pascal + + +0 100 +1 +% +percent + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +UAVCAN +SBF +GSOF +ERB +MAV +NOVA + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +UAVCAN +SBF +GSOF +ERB +MAV +NOVA + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + + + + +Disabled +UseBest +Blend + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + + + +-100 90 +deg +degrees + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None (0x0000) +All (0xFFFF) +External only (0xFF00) + + + + +Ignore +Always log +Stop logging when disarmed (SBF only) +Only log every five samples (uBlox only) + True - -0.01 0.5 -0.01 -gauss + +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 + + + + +Do not save config +Save config +Save only when needed + + + +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 + + + + +Disables automatic configuration +Enable automatic configuration + - + +50 200 -When flying -When manoeuvring -Never -After first climb yaw reset -Always +10Hz +8Hz +5Hz +ms +milliseconds - -100 1000 -25 + +50 200 + +10Hz +8Hz +5Hz + +ms +milliseconds - -0.5 5.0 -0.1 -m/s + +m +meters - -100 1000 -25 + +m +meters - -0.1 10.0 -0.1 + m +meters - -100 1000 -25 + +m +meters - -1.0 4.0 -0.1 -rad/s + +m +meters - -0.05 1.0 -0.05 -rad/s + +m +meters - -100 1000 -25 + +0 250 +ms +milliseconds +True - + 0 250 -10 -milliseconds +ms +milliseconds True - -0.0001 0.1 -0.0001 -rad/s + +0:Horiz Pos,1:Vert Pos,2:Speed - -0.01 1.0 -0.01 -m/s/s + +5.0 30.0 +s +seconds - -0.00001 0.001 -rad/s/s + + + + +Disabled +Enabled + - -0.00001 0.001 -m/s/s/s + + +None +Servo +EPM + - -0.01 1.0 -0.1 -m/s/s + +1000 2000 +PWM +PWM in microseconds - -0.0 1.0 -0.1 + +1000 2000 +PWM +PWM in microseconds - -0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + +1000 2000 +PWM +PWM in microseconds - -0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + +0 255 +s +seconds - -50 200 -% + +0 255 - -0.5 50.0 -m + + + + +Disabled +Enabled + - -0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +None +Chan1 +Chan2 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + - -0.05 1.0 -0.05 -rad + +0.1 5 +s +seconds - -100 1000 -25 + +1 10 +s +seconds - -10 50 -5 -cs + +100 100000 - -0.00001 0.01 -gauss/s + +1000 2000 - -0.00001 0.01 -gauss/s + +1000 2000 - --1 70 -1 -% + +1000 2000 - -0 0.2 -0.01 + +1000 2000 - -0.1 10.0 -0.1 -m + + +None +RPM1 +RPM2 + - -100 1000 -25 + +0 100 - -0 250 -10 -milliseconds -True + + + - -2.0 6.0 -0.5 -m/s + +rad/s +radians per second - -0.5 2.5 -0.1 -m/s/s + +rad/s +radians per second - - - - -Disabled -Enabled - + +rad/s +radians per second - -0:Altitude,1:Circle,2:Polygon - -None -Altitude -Circle -Altitude and Circle -Polygon -Altitude and Polygon -Circle and Polygon -All - + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second - - -Report Only -RTL or Land - + +rad/s +radians per second - -10 1000 -1 -Meters + +rad/s +radians per second - -30 10000 -Meters + +0.8 1.2 - -1 10 -Meters + +0.8 1.2 - -1 20 + +0.8 1.2 - - - - -Disabled -Enabled - + +-3.5 3.5 +m/s/s +meters per square second - --200 +200 -1 + +-3.5 3.5 +m/s/s +meters per square second - --200 +200 -1 + +-3.5 3.5 +m/s/s +meters per square second - --18000 +18000 -1 + +0.8 1.2 - -m + +0.8 1.2 - -m + +0.8 1.2 - -m + +-3.5 3.5 +m/s/s +meters per square second - -0 255 + +-3.5 3.5 +m/s/s +meters per square second - - - -True -True -1 -pascals + +-3.5 3.5 +m/s/s +meters per square second - -True -True -1 -degrees celsius + +0.8 1.2 - -0.1 -meters + +0.8 1.2 - - -FirstBaro -2ndBaro -3rdBaro - + +0.8 1.2 - - -Disabled -Bus0 - + +-3.5 3.5 +m/s/s +meters per square second - - - - -None -AUTO -uBlox -MTK -MTK19 -NMEA -SiRF -HIL -SwiftNav -PX4-UAVCAN -SBF -GSOF -QURT -ERB -MAV -NOVA - -True + +-3.5 3.5 +m/s/s +meters per square second - - -None -AUTO -uBlox -MTK -MTK19 -NMEA -SiRF -HIL -SwiftNav -PX4-UAVCAN -SBF -GSOF -QURT -ERB -MAV -NOVA - -True + +-3.5 3.5 +m/s/s +meters per square second - - -Portable -Stationary -Pedestrian -Automotive -Sea -Airborne1G -Airborne2G -Airborne4G - + +0 127 +Hz +hertz - + +0 127 +Hz +hertz + + Disabled Enabled - - -Any -FloatRTK -IntegerRTK - -True - - + Disabled Enabled -NoChange - --100 90 -Degrees - - + -send to first GPS -send to 2nd GPS -send to all +Disabled +Enabled - - -None -All -External only - + +0.05 50 - + -Disabled -log every sample -log every 5 samples +Never +Start-up only -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 +Don't adjust the trims +Assume first orientation was level +Assume ACC_BODYFIX is perfectly aligned to the vehicle - + -Do not save config -Save config -Save only when needed +IMU 1 +IMU 2 +IMU 3 - -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 - + +m +meters - - -Disables automatic configuration -Enable automatic configuration - + +m +meters - - -10Hz -8Hz -5Hz - -milliseconds + +m +meters - - -10Hz -8Hz -5Hz - -milliseconds + +m +meters - + m +meters - + m +meters - + m +meters - + m +meters - + m +meters - -m + +True - -0 250 -milliseconds + +True - -0 250 -milliseconds + +True - - - + +True + + +True + + +True + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU -Disabled -Enabled +FirstIMUOnly +FirstAndSecondIMU - + + + +32 + + +0:IMU1,1:IMU2,2:IMU3 None -Servo -EPM +First IMU +All - -1000 2000 -PWM + +0:Sensor-Rate Logging (sample at full sensor rate seen by AP) - -1000 2000 -PWM + +ms +milliseconds +10 - -1000 2000 -PWM + +1 - -0 255 -seconds + + + + +Disabled +Enabled + - -0 255 + +10 200 +Hz +hertz + + +5 50 +Hz +hertz + + +5 30 +dB +decibel - - --180 180 -1 -Degrees + + +0 5 +0.5 +m +meters - --180 180 + +0 90 +0.1 +deg +degrees + + +cdeg +centidegrees + + +0.1 +m +meters + + +0.1 +s +seconds + + +0 30 +0.1 +m +meters + + +0 10 +0.1 +s +seconds + + +0 30 +0.1 +m/s +meters per second + + +0 127 1 -Degrees +% +percent - --180 180 + +0 127 1 -Degrees +s +seconds - + -Servo only -Servo with ExtGyro -DirectDrive VarPitch -DirectDrive FixedPitch +Disabled +Servos to Neutral +Servos to Zero PWM - + -3-Servo CCPM -H1 Mechanical Mixing +Disabled +Enabled - -0 1000 -1 -PWM - - --90 90 -1 -Degrees - - --10 10 -0.1 + +0 100 +% +percent - + -NoFlybar -Flybar +Standard Glide Slope +Deepstall - -0 1000 -1 -PWM + + + +0 20 +m/s +meters per second - -0 1000 -1 -PWM + - -0 2000 + - -0 2000 + +10 200 +m +meters - - -Reversed -Normal - + +0 20 +m/s +meters per second - -1000 2000 -1 -PWM + +0 2 +s +seconds - -1000 2000 -1 + +900 2100 PWM +PWM in microseconds - -1000 2000 -1 -PWM + +5 20 +m/s +meters per second - - -Disabled -Passthrough -Max collective -Mid collective -Min collective - + +5 20 +m/s +meters per second - -0 1000 -10 -PWM + +5 50 +m +meters - - -Ch8 Input -SetPoint -Throttle Curve - + +0 1 - -0 500 -1 -pwm + +0 2.0 - -0 60 -Seconds + + + - -0 60 -Seconds + - -0 1000 -10 + - -0 500 -10 + - -0 1000 -10 + + + + +None +File +MAVLink +BothFileAndMAVLink + - -0 1000 -10 + - -0 18000 -100 -Centi-Degrees + + +Disabled +Enabled + - -0 10 -1 + + +Disabled +Enabled + - -1 1000 -10 + + +Disabled +Enabled + - -0 500 -10 + +kB +kilobytes - - + + +0 32766 +1 + + -Disabled -Enabled +Resume Mission +Restart Mission - + +0:Clear Mission on reboot + + + + -None -Chan1 -Chan2 -Chan3 -Chan4 -Chan5 -Chan6 -Chan7 -Chan8 -Chan9 -Chan10 -Chan11 -Chan12 -Chan13 -Chan14 -Chan15 -Chan16 +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point - -0.1 5 -Seconds + +-180.00 179.99 +1 +deg +degrees - -1 10 -Seconds + +-180.00 179.99 +1 +deg +degrees - -100 100000 + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees - -1000 2000 + +-180.00 179.99 +1 +deg +degrees - -1000 2000 + +-180.00 179.99 +1 +deg +degrees - -1000 2000 + + +Disabled +Enabled + - -1000 2000 + + +Disabled +Enabled + - + -None -RPM1 -RPM2 +Disabled +Enabled - -0 100 + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - - - -0 500 + +-18000 17999 1 -Percent*10 +cdeg +centidegrees - -0 500 + +-18000 17999 1 -Percent*10 +cdeg +centidegrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -500 1000 + +-18000 17999 1 -Percent*10 +cdeg +centidegrees - -500 1000 + +-18000 17999 1 -Percent*10 +cdeg +centidegrees - + Disabled -Very Low -Low -Medium -High -Very High +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 - - - + +-18000 17999 +1 +cdeg +centidegrees - -rad/s + +-18000 17999 +1 +cdeg +centidegrees - -rad/s + +0 100 +1 - -rad/s + +0.0 0.2 +.005 +s +seconds - -rad/s + +0.0 0.2 +.005 +s +seconds - -rad/s + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True - -rad/s + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + - -rad/s + +-180.00 179.99 +1 +deg +degrees - -rad/s + +-180.00 179.99 +1 +deg +degrees - -rad/s + +-180.00 179.99 +1 +deg +degrees - -0.8 1.2 + +-180.00 179.99 +1 +deg +degrees - -0.8 1.2 + +-180.00 179.99 +1 +deg +degrees - -0.8 1.2 + +-180.00 179.99 +1 +deg +degrees - --3.5 3.5 -m/s/s + + +Disabled +Enabled + - --3.5 3.5 -m/s/s + + +Disabled +Enabled + - --3.5 3.5 -m/s/s + + +Disabled +Enabled + - -0.8 1.2 + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.8 1.2 + +-18000 17999 +1 +cdeg +centidegrees - -0.8 1.2 + +-18000 17999 +1 +cdeg +centidegrees - --3.5 3.5 -m/s/s + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - --3.5 3.5 -m/s/s + +-18000 17999 +1 +cdeg +centidegrees - --3.5 3.5 -m/s/s + +-18000 17999 +1 +cdeg +centidegrees - -0.8 1.2 + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.8 1.2 + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees - -0.8 1.2 + +0.0 0.2 +.005 +s +seconds - --3.5 3.5 -m/s/s + +0.0 0.2 +.005 +s +seconds - --3.5 3.5 -m/s/s + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + - --3.5 3.5 -m/s/s + + + +1 60 +1 +s +seconds - -0 127 -Hz + +0.6 1.0 +0.05 - -0 127 -Hz + +0 0.1 +0.01 - + +0 89 +deg +degrees + + + + -Disabled -Enabled +Off +Low +Medium +High - + -Disabled -Enabled +Disable +Enable - + -Disabled -Enabled +Disable +Enable - -0.05 50 - - + -Never -Start-up only +Disable +ssd1306 +sh1106 - + -Don't adjust the trims -Assume first orientation was level -Assume ACC_BODYFIX is perfectly aligned to the vehicle +Disabled +Aircraft +Rover - + -IMU 1 -IMU 2 -IMU 3 +Disabled - -m - - -m - - -m + + + +0.4 1.0 +0.1 +s +seconds - -m + +0.1 3.0 +0.1 - -m + +0 0.1 +0.01 - -m + +0 0.5 +0.05 - -m + +0 100 +1 +deg/s +degrees per second - -m + +0 100 +1 +deg/s +degrees per second - -m + +0.7 1.5 +0.05 - -True + +0 4500 +1 - -True + +0.1 4.0 +0.1 - -True + + + + +Disable +Enable +Enable VTOL AUTO + - -True + +1000 8000 +cdeg +centidegrees - -True + +0 30000 +ms +milliseconds - -True + +50 500 +10 +cm/s +centimeters per second - + +50 500 +10 +cm/s/s +centimeters per square second - - - -0 5 -0.5 -meters + +50 500 +10 +Hz +hertz - -0 90 -0.1 -degrees + +800 2200 +1 +PWM +PWM in microseconds - -centi-Degrees + +800 2200 +1 +PWM +PWM in microseconds - + +0 100 0.1 -meters +m/s +meters per second - -0.1 -seconds + +50 500 +1 +deg/s +degrees per second - -0 30 -0.1 -meters + +30 200 +10 +cm/s +centimeters per second - -0 10 + +0.5 50 0.1 -seconds +m +meters - + 0 30 -0.1 -m/s - - -0 127 -1 -percent - - -0 127 1 -seconds +deg +degrees - + -Disabled -Servos to Neutral -Servos to Zero PWM +Undefined +Quad +Hexa +Octa +OctaQuad +Y6 +Tri + TailSitter - + -Disabled -Enabled +Plus +X +V +H +V-Tail +A-Tail +Y6B +Y6F - -0 100 -Percent + +0 0.5 +0.01 - - -Standard Glide Slope - + +0 1 +0.01 - - - -1000 2000 -1 -pwm + +0 10 +0.1 - -1000 2000 + +1 200 1 -pwm +m +meters - - - + -None -File -MAVLink -BothFileAndMAVLink +Disabled +Enabled - + + + +10 300 +1 +deg/s +degrees per second - + +20 80 +1 +deg +degrees + + Disabled Enabled - + Disabled -Enabled +ThrottleInput +FullInput - + +0 10 +0.25 + + Disabled Enabled - - - -0 32766 + +0 90 1 +deg +degrees - + -Resume Mission -Restart Mission +Continuous +Binary +VectoredYaw - - - + +5 80 + + +10 300 +1 +deg/s +degrees per second + + -Retracted -Neutral -MavLink Targeting -RC Targeting -GPS Point +MultiCopterInput +FixedWingInput - --180.00 179.99 -1 -Degrees + +0:Aileron,1:Elevator,2:Throttle,3:Rudder - --180.00 179.99 -1 -Degrees + + +Disabled +Channel1 +Channel2 +Channel3 +Channel4 +Channel5 +Channel6 +Channel7 +Channel8 + - --180.00 179.99 -1 -Degrees + +0 1 +0.01 - --180.00 179.99 -1 -Degrees + +0 1 +0.01 - --180.00 179.99 -1 -Degrees + +0 30 - --180.00 179.99 -1 -Degrees + +0 4 +0.1 - + + +AUTO +FIXED_WING +QUADROTOR +COAXIAL +HELICOPTER +AIRSHIP +FREE_BALLOON +ROCKET +GROUND_ROVER +SURFACE_BOAT +SUBMARINE +FLAPPING_WING +KITE +VTOL_DUOROTOR +VTOL_QUADROTOR +VTOL_TILTROTOR + + + +0:LevelTransition,1:AllowFWTakeoff,2:AllowFWLand + + +0.2 5 +0.1 +m/s/s +meters per square second + + + + +500 18000 +100 +cdeg/s +centidegrees per second + + +0 72000 Disabled -Enabled +VerySlow +Slow +Medium +Fast +1000 +cdeg/s/s +centidegrees per square second - + Disabled -Enabled +Enabled - + +0 180000 Disabled -Enabled +VerySlow +Slow +Medium +Fast + +1000 +cdeg/s/s +centidegrees per square second + + +0 180000 + +Disabled +VerySlow +Slow +Medium +Fast +1000 +cdeg/s/s +centidegrees per square second - + Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +Enabled - --18000 17999 -1 -Centi-Degrees + +3.000 12.000 - --18000 17999 -1 -Centi-Degrees + +3.000 12.000 - + +3.000 6.000 + + +0.5 10.0 + + +0 1080 Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +Slow +Medium +Fast - - --18000 17999 1 -Centi-Degrees +deg/s +degrees per second - --18000 17999 + +0 1080 + +Disabled +Slow +Medium +Fast + 1 -Centi-Degrees +deg/s +degrees per second - + +0 1080 Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +Slow +Medium +Fast - - --18000 17999 1 -Centi-Degrees +deg/s +degrees per second - --18000 17999 -1 -Centi-Degrees + +0 1 +0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp +0.01 +s +seconds - -0 100 -1 + +0.05 0.5 +0.005 - -0.0 0.2 -.005 -Seconds + +0.01 2.0 +0.01 - -0.0 0.2 -.005 -Seconds + +0 1 +0.01 +% +percent - - -None -Servo -3DR Solo -Alexmos Serial -SToRM32 MAVLink -SToRM32 Serial - -True + +0.0 0.02 +0.001 - - -Retracted -Neutral -MavLink Targeting -RC Targeting -GPS Point - + +0 0.5 +0.001 - --180.00 179.99 + +1 100 1 -Degrees +Hz +hertz - --180.00 179.99 -1 -Degrees + +0.05 0.50 +0.005 - --180.00 179.99 -1 -Degrees + +0.01 2.0 +0.01 - --180.00 179.99 -1 -Degrees + +0 1 +0.01 +% +percent - --180.00 179.99 -1 -Degrees + +0.0 0.02 +0.001 - --180.00 179.99 + +0 0.5 +0.001 + + +1 100 1 -Degrees +Hz +hertz - - -Disabled -Enabled - + +0.10 2.50 +0.005 - - -Disabled -Enabled - + +0.010 1.0 +0.01 - - -Disabled -Enabled - + +0 1 +0.01 +% +percent - - -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 - + +0.000 0.02 +0.001 - --18000 17999 -1 -Centi-Degrees + +0 0.5 +0.001 - --18000 17999 + +1 10 1 -Centi-Degrees +Hz +hertz - - -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 - + +0.1 0.25 - --18000 17999 -1 -Centi-Degrees + +0.5 0.9 - --18000 17999 + +0.1 0.9 + + + + +0 45 1 -Centi-Degrees +deg +degrees - - -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 - + +20 2000 +50 +cm/s +centimeters per second - --18000 17999 + +100 981 1 -Centi-Degrees +cm/s/s +centimeters per square second - --18000 17999 + +25 250 1 -Centi-Degrees - - -0.0 0.2 -.005 -Seconds +cm/s/s +centimeters per square second - -0.0 0.2 -.005 -Seconds + +500 5000 +1 +cm/s/s/s +centimeters per cubic second - - -None -Servo -3DR Solo -Alexmos Serial -SToRM32 MAVLink -SToRM32 Serial - + +0 2 +0.1 +s +seconds - - + + 0 500 -pwm +PWM +PWM in microseconds - + 0.25 0.8 - + 0.9:Low, 0.95:Default, 1.0:High - + 6 35 -Volts +V +volt - + 6 35 -Volts +V +volt - + 0 200 -Amps +A +ampere - + Normal OneShot OneShot125 -Brushed16kHz +Brushed +DShot150 +DShot300 +DShot600 +DShot1200 True - + 0 2000 +PWM +PWM in microseconds - + 0 2000 +PWM +PWM in microseconds - + 0.0:Low, 0.15:Default, 0.3:High - + 0.0:Low, 0.1:Default, 0.2:High - + 0 10 -Seconds +s +seconds - + 0.2 0.8 - + Disabled Learn LearnAndSave - + PWM enabled while disarmed PWM disabled while disarmed - + 5 80 1 -Degrees +deg +degrees - + 0 2 0.1 -Seconds - - - - -1 60 -1 -seconds - - -0.6 1.0 -0.05 - - -0 0.1 -0.01 - - - - - -Off -Low -Medium -High - - - - -Disable -Enable - - - - -Disable -Enable - - - - -Disable -ssd1306 -sh1106 - +s +seconds - - - - -Disabled -Enabled Always Land -Enabled Strict - + +0 5 +0.1 - + -None -CompanionComputer -IRLock -SITL_Gazebo -SITL +First battery +Second battery - -0 360 -1 -Centi-degrees - - --20 20 -1 -Centimeters - - --20 20 -1 -Centimeters - - - + + 0.5 5 0.1 Hz +hertz - - - - -None -LightWareSF40C -MAVLink -TeraRangerTower - - - - -Default -Upside Down - - - --180 180 -degrees - - -0 360 -degrees - - -0 45 -degrees - - -0 360 -degrees - - -0 45 -degrees - - -0 360 -degrees - - -0 45 -degrees - - -0 360 -degrees - - -0 45 -degrees - - -0 360 -degrees - - -0 45 -degrees - - -0 360 -degrees - - -0 45 -degrees - - - -None -LightWareSF40C -MAVLink - - - - -Default -Upside Down - - - --180 180 -degrees - - - - -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 + +1.000 3.000 - -0 100 -1 -degrees/second + +1.000 8.000 - -0.7 1.5 + +0.500 1.500 0.05 - -0 4500 -1 - - -0.1 4.0 -0.1 - - - - -0.08 0.30 -0.005 - - -0.01 0.5 -0.01 - - -0 1 -0.01 -Percent + +0.000 3.000 - -0.0 0.02 -0.001 + +0 1000 +d% +decipercent - -1 100 -1 + +0.000 0.400 + + +1.000 100.000 Hz +hertz - -0.08 0.30 -0.005 + +0.500 2.000 - -0.01 0.5 -0.01 + +0.1 6.0 +0.1 - -0 1 + +0.02 1.00 0.01 -Percent - -0.0 0.02 + +0.00 1.00 0.001 - -1 100 -1 -Hz + +0 4500 +10 +cm/s/s +centimeters per square second - -0.10 0.50 -0.005 + +0 100 +Hz +hertz - -0.010 0.05 -0.01 + +0 100 +Hz +hertz - -0 1 -0.01 -Percent + +0 45 +1 +deg +degrees - -0.000 0.02 -0.001 + + + +20 2000 +50 +cm/s +centimeters per second - -1 100 + +10 1000 1 -Hz +cm +centimeters - -0.1 0.25 + +10 1000 +50 +cm/s +centimeters per second - -0.5 0.9 + +10 500 +10 +cm/s +centimeters per second - -0.5 0.9 + +50 500 +10 +cm/s/s +centimeters per square second + + +50 500 +10 +cm/s/s +centimeters per square second + + + +Disable +Enable + @@ -5458,7 +4917,8 @@ 0.1 -kilometers +km +kilometers @@ -5467,21 +4927,31 @@ + + +0.0 120.0 +s +seconds + + - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5489,26 +4959,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5516,26 +4990,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5543,26 +5021,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5570,26 +5052,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5597,26 +5083,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5624,26 +5114,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5651,26 +5145,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5678,26 +5176,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5705,26 +5207,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5732,26 +5238,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5759,26 +5269,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5786,26 +5300,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5813,26 +5331,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5840,26 +5362,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5867,26 +5393,30 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -5894,9 +5424,10 @@ Reversed - + 0 200 -pwm +PWM +PWM in microseconds @@ -5920,6 +5451,16 @@ 1 True + +1 8 +1 +True + + +1 8 +1 +True + @@ -5927,18 +5468,20 @@ Disabled APM2 A9 pin APM1 relay +BB Blue GP0 pin 4 Pixhawk AUXOUT1 Pixhawk AUXOUT2 Pixhawk AUXOUT3 Pixhawk AUXOUT4 Pixhawk AUXOUT5 Pixhawk AUXOUT6 +BB Blue GP0 pin 3 PX4 FMU Relay1 PX4 FMU Relay2 -PX4IO Relay1 +PX4IO Relay1/BB Blue GP0 pin 6 PX4IO Relay2 PX4IO ACC1 -PX4IO ACC2 +PX4IO ACC2/BB Blue GP0 pin 5 @@ -5946,18 +5489,20 @@ Disabled APM2 A9 pin APM1 relay +BB Blue GP0 pin 4 Pixhawk AUXOUT1 Pixhawk AUXOUT2 Pixhawk AUXOUT3 Pixhawk AUXOUT4 Pixhawk AUXOUT5 Pixhawk AUXOUT6 +BB Blue GP0 pin 3 PX4 FMU Relay1 PX4 FMU Relay2 -PX4IO Relay1 +PX4IO Relay1/BB Blue GP0 pin 6 PX4IO Relay2 PX4IO ACC1 -PX4IO ACC2 +PX4IO ACC2/BB Blue GP0 pin 5 @@ -5965,18 +5510,20 @@ Disabled APM2 A9 pin APM1 relay +BB Blue GP0 pin 4 Pixhawk AUXOUT1 Pixhawk AUXOUT2 Pixhawk AUXOUT3 Pixhawk AUXOUT4 Pixhawk AUXOUT5 Pixhawk AUXOUT6 +BB Blue GP0 pin 3 PX4 FMU Relay1 PX4 FMU Relay2 -PX4IO Relay1 +PX4IO Relay1/BB Blue GP0 pin 6 PX4IO Relay2 PX4IO ACC1 -PX4IO ACC2 +PX4IO ACC2/BB Blue GP0 pin 5 @@ -5984,21 +5531,23 @@ Disabled APM2 A9 pin APM1 relay +BB Blue GP0 pin 4 Pixhawk AUXOUT1 Pixhawk AUXOUT2 Pixhawk AUXOUT3 Pixhawk AUXOUT4 Pixhawk AUXOUT5 Pixhawk AUXOUT6 +BB Blue GP0 pin 3 PX4 FMU Relay1 PX4 FMU Relay2 -PX4IO Relay1 +PX4IO Relay1/BB Blue GP0 pin 6 PX4IO Relay2 PX4IO ACC1 -PX4IO ACC2 +PX4IO ACC2/BB Blue GP0 pin 5 - + Off On @@ -6010,7 +5559,8 @@ 0.4 1.0 0.1 -seconds +s +seconds 0.1 4.0 @@ -6027,7 +5577,8 @@ 0 180 1 -degrees/second +deg/s +degrees per second 0 4500 @@ -6044,7 +5595,7 @@ None Analog MaxbotixI2C -PulsedLightI2C +LidarLiteV2-I2C PX4-PWM BBB-PRU LightWareI2C @@ -6054,7 +5605,13 @@ uLanding LeddarOne MaxbotixSerial -TrOneI2C +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini @@ -6077,11 +5634,13 @@ 0.001 -meters/Volt +m/V +meters per volt 0.001 -Volts +V +volt @@ -6092,11 +5651,13 @@ 1 -centimeters +cm +centimeters 1 -centimeters +cm +centimeters @@ -6117,7 +5678,8 @@ 1 -milliseconds +ms +milliseconds @@ -6127,12 +5689,14 @@ 0 32767 -meters +m +meters 5 127 1 -centimeters +cm +centimeters 0 127 @@ -6140,19 +5704,36 @@ m +meters m +meters m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + None Analog MaxbotixI2C -PulsedLightI2C +LidarLiteV2-I2C PX4-PWM BBB-PRU LightWareI2C @@ -6162,7 +5743,13 @@ uLanding LeddarOne MaxbotixSerial -TrOneI2C +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini @@ -6185,11 +5772,13 @@ 0.001 -meters/Volt +m/V +meters per volt 0.001 -Volts +V +volt @@ -6200,11 +5789,13 @@ 1 -centimeters +cm +centimeters 1 -centimeters +cm +centimeters @@ -6225,7 +5816,8 @@ 1 -milliseconds +ms +milliseconds @@ -6236,7 +5828,8 @@ 0 127 1 -centimeters +cm +centimeters 0 127 @@ -6244,19 +5837,36 @@ m +meters m +meters m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + None Analog -APM2-MaxbotixI2C -APM2-PulsedLightI2C +MaxbotixI2C +LidarLiteV2-I2C PX4-PWM BBB-PRU LightWareI2C @@ -6266,6 +5876,13 @@ uLanding LeddarOne MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini @@ -6288,11 +5905,13 @@ 0.001 -meters/Volt +m/V +meters per volt 0.001 -Volts +V +volt @@ -6303,11 +5922,13 @@ 1 -centimeters +cm +centimeters 1 -centimeters +cm +centimeters @@ -6328,7 +5949,8 @@ 1 -milliseconds +ms +milliseconds @@ -6339,7 +5961,8 @@ 0 127 1 -centimeters +cm +centimeters 0 127 @@ -6347,19 +5970,36 @@ m +meters m +meters m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + None Analog -APM2-MaxbotixI2C -APM2-PulsedLightI2C +MaxbotixI2C +LidarLiteV2-I2C PX4-PWM BBB-PRU LightWareI2C @@ -6369,6 +6009,13 @@ uLanding LeddarOne MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini @@ -6391,11 +6038,13 @@ 0.001 -meters/Volt +m/V +meters per volt 0.001 -Volts +V +volt @@ -6406,56 +6055,169 @@ 1 -centimeters +cm +centimeters + + +1 +cm +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 +ms +milliseconds + + + +No +Yes + + + +0 127 +1 +cm +centimeters + + +0 127 +1 + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + + + + + +0 255 + + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + + +Low Speed +High Speed + + + + + +0 255 + + +0 255 + + +0 10000 - -1 -centimeters + +0 255 - + +-1 255 + + -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 +Low Speed +High Speed - -1 -milliseconds + + + +0 255 - + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + -No -Yes +Low Speed +High Speed - -0 127 -1 -centimeters + + + +0 255 - -0 127 -1 + +0 255 - -m + +0 10000 - -m + +0 255 - -m + +-1 255 + + + +Low Speed +High Speed + @@ -6463,6 +6225,7 @@ None PX4-PWM +AUXPIN @@ -6477,15 +6240,38 @@ 0.1 + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + None PX4-PWM +AUXPIN 0.001 + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + @@ -6493,6 +6279,7 @@ Disabled AnalogPin RCChannelPwmValue +ReceiverProtocol @@ -6503,30 +6290,34 @@ Pixracer Pixhawk ADC4 Pixhawk ADC3 - Pixhawk ADC6 +Pixhawk ADC6 Pixhawk SBUS +Pixhawk2 ADC 0 5.0 0.01 -Volt +V +volt 0 5.0 0.01 -Volt +V +volt - - + 0 2000 -Microseconds +PWM +PWM in microseconds - + 0 2000 -Microseconds +PWM +PWM in microseconds @@ -6537,7 +6328,7 @@ ShowOverruns - + 50Hz 100Hz @@ -6561,6 +6352,7 @@ 57600 111100 115200 +460800 500000 921600 1500000 @@ -6571,6 +6363,7 @@ MAVlink1 MAVLink2 +True @@ -6582,12 +6375,16 @@ GPS Alexmos Gimbal Serial SToRM32 Gimbal Serial -Lidar +Rangefinder FrSky SPort Passthrough (OpenTX) Lidar360 -Aerotenna uLanding -Pozyx Beacon +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry +True @@ -6615,12 +6412,16 @@ GPS Alexmos Gimbal Serial SToRM32 Gimbal Serial -Lidar +Rangefinder FrSky SPort Passthrough (OpenTX) Lidar360 -Aerotenna uLanding -Pozyx Beacon +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry +True @@ -6648,12 +6449,16 @@ GPS Alexmos Gimbal Serial SToRM32 Gimbal Serial -Lidar +Rangefinder FrSky SPort Passthrough (OpenTX) Lidar360 -Aerotenna uLanding -Pozyx Beacon +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry +True @@ -6681,12 +6486,16 @@ GPS Alexmos Gimbal Serial SToRM32 Gimbal Serial -Lidar +Rangefinder FrSky SPort Passthrough (OpenTX) Lidar360 -Aerotenna uLanding -Pozyx Beacon +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry +True @@ -6714,12 +6523,16 @@ GPS Alexmos Gimbal Serial SToRM32 Gimbal Serial -Lidar +Rangefinder FrSky SPort Passthrough (OpenTX) Lidar360 -Aerotenna uLanding -Pozyx Beacon +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry +True @@ -6745,22 +6558,30 @@ Enable + +25 400 +Hz +hertz + - -800 2200 + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -6785,14 +6606,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -6808,6 +6629,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -6832,35 +6654,39 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - -800 2200 + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -6885,14 +6711,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -6908,6 +6734,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -6932,35 +6759,39 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - -800 2200 + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -6985,14 +6816,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7008,6 +6839,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7032,35 +6864,39 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - -800 2200 + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds @@ -7085,14 +6921,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7108,6 +6944,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7132,43 +6969,257 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + 800 2200 1 -pwm +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7185,14 +7236,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7208,6 +7259,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7232,43 +7284,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7285,14 +7341,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7308,6 +7364,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7332,43 +7389,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7385,14 +7446,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7408,6 +7469,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7432,43 +7494,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7485,14 +7551,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7508,6 +7574,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7532,43 +7599,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7585,14 +7656,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7608,6 +7679,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7632,43 +7704,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7685,14 +7761,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7708,6 +7784,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7732,43 +7809,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7785,14 +7866,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7808,6 +7889,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7832,43 +7914,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7885,14 +7971,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -7908,6 +7994,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -7932,43 +8019,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -7985,14 +8076,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -8008,6 +8099,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -8032,43 +8124,47 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +500 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + 800 2200 1 -pwm +PWM +PWM in microseconds - + Normal Reversed - + Disabled RCPassThru @@ -8085,14 +8181,14 @@ mount2_tilt mount2_roll mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 Elevator -ElevatorWithInput Rudder -Flaperon1 -Flaperon2 +FlaperonLeft +FlaperonRight GroundSteering Parachute EPM @@ -8108,6 +8204,7 @@ Motor6 Motor7 Motor8 +MotorTilt RCIN1 RCIN2 RCIN3 @@ -8132,272 +8229,410 @@ TrackerPitch ThrottleLeft ThrottleRight -TiltMotorLeft -TiltMotorRight +tiltMotorLeft +tiltMotorRight ElevonLeft ElevonRight -VtailLeft -VtailRight -Boost Throttle +VTailLeft +VTailRight +BoostThrottle Motor9 Motor10 Motor11 Motor12 +Winch - - -800 2200 + + +0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + + + +Disabled +Enabled + + + + +Disabled +TestMotor1 +TestMotor2 +TestMotor3 +TestMotor4 +TestMotor5 +TestMotor6 +TestMotor7 +TestMotor8 + + + +0 300 +s +seconds + + +0 500 +Hz +hertz + + + +Disabled +Enabled + + + + +None +OneShot +OneShot125 +Brushed +DShot150 +DShot300 +DShot600 +DShot1200 + + + + + +25 250 +Hz +hertz + + + + +0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + + + + + +Disable +Enable + + + +0 10 +m/s +meters per second + + +0 100 +m +meters + + +0 32768 +s +seconds + + +0 32768 +s +seconds + + +0 0.5 +m.m/s/s +square meter per square second + + +0 1000.0 +m +meters + + +0 1000.0 +m +meters + + +0 1000.0 +m +meters + + +0 16 + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 50 +1 +Hz +hertz + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 50 +1 +Hz +hertz + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 1 -pwm +Hz +hertz - -800 2200 + +0 10 1 -pwm +Hz +hertz - -800 2200 + +0 10 1 -pwm +Hz +hertz - - -Normal -Reversed - + +0 10 +1 +Hz +hertz - - -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 -HeliRSC -HeliTailRSC -Motor1 -Motor2 -Motor3 -Motor4 -Motor5 -Motor6 -Motor7 -Motor8 -RCIN1 -RCIN2 -RCIN3 -RCIN4 -RCIN5 -RCIN6 -RCIN7 -RCIN8 -RCIN9 -RCIN10 -RCIN11 -RCIN12 -RCIN13 -RCIN14 -RCIN15 -RCIN16 -Ignition -Choke -Starter -Throttle -TrackerYaw -TrackerPitch -ThrottleLeft -ThrottleRight -TiltMotorLeft -TiltMotorRight -ElevonLeft -ElevonRight -VtailLeft -VtailRight -Boost Throttle -Motor9 -Motor10 -Motor11 -Motor12 - + +0 50 +1 +Hz +hertz - - -800 2200 + + +0 10 1 -pwm +Hz +hertz - -800 2200 + +0 10 1 -pwm +Hz +hertz - -800 2200 + +0 10 1 -pwm - - - -Normal -Reversed - - - - -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 -HeliRSC -HeliTailRSC -Motor1 -Motor2 -Motor3 -Motor4 -Motor5 -Motor6 -Motor7 -Motor8 -RCIN1 -RCIN2 -RCIN3 -RCIN4 -RCIN5 -RCIN6 -RCIN7 -RCIN8 -RCIN9 -RCIN10 -RCIN11 -RCIN12 -RCIN13 -RCIN14 -RCIN15 -RCIN16 -Ignition -Choke -Starter -Throttle -TrackerYaw -TrackerPitch -ThrottleLeft -ThrottleRight -TiltMotorLeft -TiltMotorRight -ElevonLeft -ElevonRight -VtailLeft -VtailRight -Boost Throttle -Motor9 -Motor10 -Motor11 -Motor12 - - - - - - - +Hz +hertz - + +0 10 +1 +Hz +hertz - + +0 10 +1 +Hz +hertz - - - - -Disabled -Enabled - + +0 10 +1 +Hz +hertz - -0 100 -percentage + +0 10 +1 +Hz +hertz - -1000 2000 -ms + +0 10 +1 +Hz +hertz - -0 1000 -cm/s + +0 10 +1 +Hz +hertz - -0 100 -percentage + +0 50 +1 +Hz +hertz +True -seconds +True +s +seconds -seconds +True +s +seconds -seconds +True +s +seconds 0.4 1.0 0.1 -seconds +s +seconds 0.1 10.0 @@ -8414,11 +8649,14 @@ 0 4500 1 +cdeg +centidegrees 0 5 0.1 m/s +meters per second 0.0 10.0 @@ -8428,16 +8666,19 @@ 0.0 30.0 0.1 m/s +meters per second 0.0 50.0 0.1 -degree/(m/s) +deg/m/s +degrees per meter per second 0.0 4500.0 0.1 -Centidegrees +cdeg +centidegrees @@ -8529,11 +8770,13 @@ 0.0 20.0 0.1 m/s +meters per second -2.0 2.0 0.1 m/s/m +meters per second per meter 0.1 1.0 @@ -8567,10 +8810,54 @@ 1 -meters +m +meters + + +None +RateRollPI +RateRollP +RateRollI +RateRollD +RatePitchPI +RatePitchP +RatePitchI +RatePitchD +RateYawPI +RateYawP +RateYawI +RateYawD +AngleRollP +AnglePitchP +AngleYawP +PosXYP +PosZP +VelXYP +VelXYI +VelZP +AccelZP +AccelZI +AccelZD +FixedWingRollP +FixedWingRollI +FixedWingRollD +FixedWingRollFF +FixedWingPitchP +FixedWingPitchI +FixedWingPitchD +FixedWingPitchFF +Set_RateRollPitch +Set_RateRoll +Set_RatePitch +Set_RateYaw +Set_AngleRollPitch +Set_VelXY +Set_AccelZ + + Disable @@ -8627,64 +8914,6 @@ 0 1 - - -20 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 - - -25 250 -1 -cm/s/s - - - -Disable -Enable - - - 0 4 diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml new file mode 100644 index 0000000000000000000000000000000000000000..304e358b19dd7bef32c2bf8fb24fa1f81d56d652 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.4.xml @@ -0,0 +1,7224 @@ + + + + + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:THR,5:NTUN,7:IMU,8:CMD,9:CURRENT,10:RANGEFINDER,11:COMPASS,12:CAMERA,13:STEERING,14:RC,15:ARM/DISARM,19:IMU_RAW + +Disabled +APM2-Default +PX4/Pixhawk-Default + + + + + + +MANUAL +ACRO +STEERING +HOLD +LOITER +AUTO +RTL +GUIDED + + + +1 255 + + +1 255 + + +0 30 +1 +s +seconds + + +0:Steering,1:Throttle + +None +Steering +Throttle + + + + +Disabled +Enabled + + + + +Disabled +APM TriggerPin0 +APM TriggerPin1 +APM TriggerPin2 +APM TriggerPin3 +APM TriggerPin4 +APM TriggerPin5 +APM TriggerPin6 +APM TriggerPin7 +APM TriggerPin8 +Pixhawk TriggerPin50 +Pixhawk TriggerPin51 +Pixhawk TriggerPin52 +Pixhawk TriggerPin53 +Pixhawk TriggerPin54 +Pixhawk TriggerPin55 + + + +0 20 +0.1 +m/s/s +meters per square second + + +0 100 +0.1 +m/s +meters per second + + +0 360 +1 +deg +degrees + + + +Nothing +SaveWaypoint +LearnCruiseSpeed +ArmDisarm +Manual +Acro +Steering +Hold +Auto +RTL +SmartRTL +Guided +Loiter + + + +0 100 +1 +% +percent + + + +Default +Two Paddles Input +Direction reversed when backing up +Direction unchanged when backing up + + + + +Nothing +RTL +Hold +SmartRTL or RTL +SmartRTL or Hold + + + +s +seconds + + + +Disabled +Enabled + + + +910 1100 +1 + + + +Disabled +Enabled + + + + +Disabled +Hold +HoldAndDisarm + + + +0 1000 +1 +cm +centimeters + + +-450 450 +1 +deg +degrees + + +0 100 +0.1 +s +seconds + + +1 100 +1 + + + + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + + +Manual +Acro +Steering +Hold +Loiter +Auto +RTL +SmartRTL +Guided + + + +0 1000 +0.1 +m +meters + + +0 10 +0.1 +m +meters + + +0.1 10 +0.01 +gravities +standard acceleration due to gravity + + + +NotEnforced +Enforced + + + +0 10 +0.1 +m +meters + + +0 360 +1 +deg/s +degrees per second + + +0 100 +0.1 +m/s +meters per second + + +0 100 +0.1 +m/s +meters per second + + + +Undefined +Rover +Boat + + + +0 360 +1 +deg/s +degrees per second + + + + + + + + + + + + + + + + + + + + +m +meters + + +m +meters + + +mbar +millibar + + + + + + + + + + + + + + +s +seconds + + + + +0.0 1.0 +.01 + + + +Disabled +Enabled + + + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s +meters per second + + +-0.1745 +0.1745 +0.01 +rad +radians + + +-0.1745 +0.1745 +0.01 +rad +radians + + +-0.1745 +0.1745 +0.01 +rad +radians + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 +Custom + + + +0.001 0.5 +.01 + + +0 10 +1 + + + +Disabled +Enable EKF2 +Enable EKF3 + + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + + + + +Disabled +THR_MIN PWM when disarmed +0 PWM when disarmed + + + +0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,10:Logging Available,11:Hardware safety switch,12:GPS Configuration + +None +All +Barometer +Compass +GPS Lock +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Channels +Board voltage +Battery Level +LoggingAvailable +Hardware safety switch +GPS configuration + + + +0.25 3.0 +m/s/s +meters per square second + + +0.1 +V +volt + + +0.1 +V +volt + + + + +0.000 2.000 +0.01 + + +0.000 2.000 +0.01 + + +0.000 1.000 +0.01 + + +0.000 0.400 +0.001 + + +0.000 3.000 +0.001 + + +0.000 100.000 +0.1 +Hz +hertz + + +0.010 2.000 +0.01 + + +0.000 2.000 + + +0.000 1.000 +0.01 + + +0.000 0.400 +0.001 + + +0.000 0.500 +0.001 + + +0.000 100.000 +0.1 +Hz +hertz + + +0.0 10.0 +0.1 +m/s/s +meters per square second + + + +Disable +Enable + + + +0.00 0.50 +0.01 +m/s +meters per second + + +1.000 10.000 +0.1 + + +0 1000 +0.1 +deg/s/s +degrees per square second + + +0 1000 +0.1 +deg/s +degrees per second + + +0.0 10.0 +0.1 +m/s/s +meters per square second + + + + +0:StopAtFence,1:UseProximitySensor,2:StopAtBeaconFence + +None +StopAtFence +UseProximitySensor +StopAtFence and UseProximitySensor +StopAtBeaconFence +All + + + +0 4500 +cdeg +centidegrees + + +1 30 +m +meters + + +1 10 +m +meters + + + +Slide +Stop + + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell +UAVCAN-BatteryInfo + +True + + + +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + +True + + + +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + +True + + + + +A/V +ampere per volt + + +V +volt + + +50 +mAh +milliampere hour + + +1 +W +watt + + + + +0 120 +1 +s +seconds + + + +Raw Voltage +Sag Compensated Voltage + + + +0.1 +V +volt + + +50 +mAh +milliampere hour + + +0.1 +V +volt + + +50 +mAh +milliampere hour + + + +None +RTL +Hold +SmartRTL +SmartRTL or Hold +Terminate + + + + +None +RTL +Hold +SmartRTL +SmartRTL or Hold +Terminate + + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell +UAVCAN-BatteryInfo + +True + + + +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + +True + + + +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + +True + + + + +A/V +ampere per volt + + +V +volt + + +50 +mAh +milliampere hour + + +1 +W +watt + + + + +0 120 +1 +s +seconds + + + +Raw Voltage +Sag Compensated Voltage + + + +0.1 +V +volt + + +50 +mAh +milliampere hour + + +0.1 +V +volt + + +50 +mAh +milliampere hour + + + +None +RTL +Hold +SmartRTL +SmartRTL or Hold +Terminate + + + + +None +RTL +Hold +SmartRTL +SmartRTL or Hold +Terminate + + + + + + +None +Pozyx +Marvelmind + + + +-90 90 +0.000001 +deg +degrees + + +-180 180 +0.000001 +deg +degrees + + +0 10000 +1 +m +meters + + +-180 +180 +1 +deg +degrees + + + + + +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled + +True + + + +Disabled +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz + +True + + +-32768 32767 + + +0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 + +Disabled +Enabled + +True + + +-1 80 +degC +degrees Celsius + + + +AUTO +PX4V1 +Pixhawk +Cube/Pixhawk2 +Pixracer +PixhawkMini +Pixhawk2Slim +VRBrain 5.1 +VRBrain 5.2 +VR Micro Brain 5.1 +VR Micro Brain 5.2 +VRBrain Core 1.0 +VRBrain 5.4 +Intel Aero FC +AUAV2.1 + +True + + + +Disabled +Enabled + +True + + +0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed + + + + + +None +CYRF6936 + + + + +Auto +DSM2 +DSMX + + + +0 4 + + + +NotDisabled +Disabled + + + +0 16 + + +0 16 + + + +Disabled +Enabled + + + +1 8 + + + +Disabled +MinChannel +MidChannel +MaxChannel +MinChannelCW +MidChannelCW +MaxChannelCW + + + + +Mode1 +Mode2 + + + + +Disabled +TestChan1 +TestChan2 +TestChan3 +TestChan4 +TestChan5 +TestChan6 +TestChan7 +TestChan8 + + + +0 16 + + +0 16 + + +1 8 + + +0 40 + + +0 120 + + +0 31 + + + + +0:GPS,1:MAVLINK_SYSTEM_TIME,2:HW + + + + + +Disabled +Enabled + + + + +Disabled +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 +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 +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 +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 + + + +0 3600 + + + + + +Servo +Relay + + + +0 50 +ds +deciseconds + + +1000 2000 +PWM +PWM in microseconds + + +1000 2000 +PWM +PWM in microseconds + + +0 1000 +m +meters + + + +Low +High + + + +0 10000 +ms +milliseconds + + +0 180 +deg +degrees + + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + + + + +TriggerLow +TriggerHigh + + + + +Always +Only when in AUTO + + + + + + +Disabled +UAVCAN + +True + + + + +1 250 + + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + + +1 200 +Hz +hertz + + + + + +Disabled +UAVCAN + +True + + + + +1 250 + + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + + +1 200 +Hz +hertz + + + + + +Disabled +UAVCAN + +True + + + + +1 250 + + +0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15 + + +0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16 + + +1 200 +Hz +hertz + + + + + +Disabled +First driver +Second driver + +True + + +10000 1000000 + + + +Disabled +Major messages +All messages + + + + + + +Disabled +First driver +Second driver + +True + + +10000 1000000 + + + +Disabled +Major messages +All messages + + + + + + +Disabled +First driver +Second driver + +True + + +10000 1000000 + + + +Disabled +Major messages +All messages + + + + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-3.142 3.142 +0.01 +rad +radians + + + +Disabled +Internal-Learning +EKF-Learning + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 + + + + +Internal +External +ForcedExternal + + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + + +FirstCompass +SecondCompass +ThirdCompass + + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-400 400 +1 +mGauss +milligauss + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + +-1000 1000 +1 +mGauss/A +milligauss per ampere + + + + + + + + + +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 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 + + + + +Internal +External +ForcedExternal + + + + +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 +Roll270Yaw135 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll180 +Pitch315 +Roll90Pitch315 + + + + +Internal +External +ForcedExternal + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +4 32 + +Very Strict +Strict +Default +Relaxed + +0.1 + + +500 3000 +1 + + +0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883 + + +0 100 +1 +% +percent + + + + + +Disabled +Enabled + + + +0 2 +0.01 + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +Disabled +Enabled + +True + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS + + + +0.05 5.0 +0.05 +m/s +meters per second + + +0.05 5.0 +0.05 +m/s +meters per second + + +100 1000 +25 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +10 100 +5 +m +meters + + +0 250 +10 +ms +milliseconds +True + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + +True + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +0 250 +10 +ms +milliseconds +True + + +0.01 0.5 +0.01 +Gauss +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s +meters per second + + +100 1000 +25 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s +radians per second + + +0.05 1.0 +0.05 +rad/s +radians per second + + +100 1000 +25 + + +0 127 +10 +ms +milliseconds +True + + +0.0001 0.1 +0.0001 +rad/s +radians per second + + +0.01 1.0 +0.01 +m/s/s +meters per square second + + +0.00001 0.001 +rad/s/s +radians per square second + + +0.000001 0.001 +Hz +hertz + + +0.00001 0.001 +m/s/s/s +meters per cubic second + + +0.01 1.0 +0.1 +m/s/s +meters per square second + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True + + +50 200 +% +percent + + +0.5 50.0 +m +meters + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True + + +0.05 1.0 +0.05 +rad +radians + + +100 1000 +25 + + +10 50 +5 +cs +centiseconds + + +0.00001 0.01 +Gauss/s +gauss per second + + +0.00001 0.01 +Gauss/s +gauss per second + + +-1 70 +1 +% +percent + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +0 127 +10 +ms +milliseconds +True + + +2.0 6.0 +0.5 +m/s +meters per second + + +0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF +True + + +0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position +True + + + + + +Disabled +Enabled + +True + + + +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS + + + +0.05 5.0 +0.05 +m/s +meters per second + + +0.05 5.0 +0.05 +m/s +meters per second + + +100 1000 +25 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +10 100 +5 +m +meters + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + +True + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +0 250 +10 +ms +milliseconds +True + + +0.01 0.5 +0.01 +Gauss +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + +True + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s +meters per second + + +100 1000 +25 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s +radians per second + + +0.05 1.0 +0.05 +rad/s +radians per second + + +100 1000 +25 + + +0 250 +10 +ms +milliseconds +True + + +0.0001 0.1 +0.0001 +rad/s +radians per second + + +0.01 1.0 +0.01 +m/s/s +meters per square second + + +0.00001 0.001 +rad/s/s +radians per square second + + +0.00001 0.001 +m/s/s/s +meters per cubic second + + +0.01 1.0 +0.1 +m/s/s +meters per square second + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True + + +50 200 +% +percent + + +0.5 50.0 +m +meters + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU +True + + +0.05 1.0 +0.05 +rad +radians + + +100 1000 +25 + + +10 50 +5 +cs +centiseconds + + +0.00001 0.01 +Gauss/s +gauss per second + + +0.00001 0.01 +Gauss/s +gauss per second + + +-1 70 +1 +% +percent + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m +meters + + +100 1000 +25 + + +0 250 +10 +ms +milliseconds +True + + +2.0 6.0 +0.5 +m/s +meters per second + + +0.5 2.5 +0.1 +m/s/s +meters per square second + + +0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF +True + + +0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position +True + + +0.05 0.5 +0.05 +m/s +meters per second + + +0.5 5.0 +0.1 +m/s +meters per second + + +0.01 1.0 +0.1 +m/s +meters per second + + + + + +Disabled +Enabled + + + +0:Altitude,1:Circle,2:Polygon + +None +Altitude +Circle +Altitude and Circle +Polygon +Altitude and Polygon +Circle and Polygon +All + + + + +Report Only +RTL or Land + + + +10 1000 +1 +m +meters + + +30 10000 +m +meters + + +1 10 +m +meters + + +1 20 + + +-100 100 +1 +m +meters + + + + +True +True +1 +Pa +pascal + + +True +1 +degC +degrees Celsius + + +0.1 +m +meters + + + +FirstBaro +2ndBaro +3rdBaro + + + + +Disabled +Bus0 +Bus1 + + + +1.0:Freshwater,1.024:Saltwater + + +True +True +1 +Pa +pascal + + +True +True +1 +Pa +pascal + + +0 100 +1 +% +percent + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +UAVCAN +SBF +GSOF +ERB +MAV +NOVA + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +UAVCAN +SBF +GSOF +ERB +MAV +NOVA + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + + + + +Disabled +UseBest +Blend + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + + + +-100 90 +deg +degrees + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None (0x0000) +All (0xFFFF) +External only (0xFF00) + + + + +Ignore +Always log +Stop logging when disarmed (SBF only) +Only log every five samples (uBlox only) + +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 + + + + +Do not save config +Save config +Save only when needed + + + +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 + + + + +Disables automatic configuration +Enable automatic configuration + + + +50 200 + +10Hz +8Hz +5Hz + +ms +milliseconds + + +50 200 + +10Hz +8Hz +5Hz + +ms +milliseconds + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +0 250 +ms +milliseconds +True + + +0 250 +ms +milliseconds +True + + +0:Horiz Pos,1:Vert Pos,2:Speed + + +5.0 30.0 +s +seconds + + + + + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +rad/s +radians per second + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +-3.5 3.5 +m/s/s +meters per square second + + +0 127 +Hz +hertz + + +0 127 +Hz +hertz + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0.05 50 + + + +Never +Start-up only + + + + +Don't adjust the trims +Assume first orientation was level +Assume ACC_BODYFIX is perfectly aligned to the vehicle + + + + +IMU 1 +IMU 2 +IMU 3 + + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +True + + +True + + +True + + +True + + +True + + +True + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU + +FirstIMUOnly +FirstAndSecondIMU + + + + + +32 + + +0:IMU1,1:IMU2,2:IMU3 + +None +First IMU +All + + + +0:Sensor-Rate Logging (sample at full sensor rate seen by AP) + + +ms +milliseconds +10 + + +1 + + + + + +Disabled +Enabled + + + +10 200 +Hz +hertz + + +5 50 +Hz +hertz + + +5 30 +dB +decibel + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +kB +kilobytes + + + + +0 32766 +1 + + + +Resume Mission +Restart Mission + + + +0:Clear Mission on reboot + + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + +0 100 +1 + + +0.0 0.2 +.005 +s +seconds + + +0.0 0.2 +.005 +s +seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + +-180.00 179.99 +1 +deg +degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +cdeg +centidegrees + + +-18000 17999 +1 +cdeg +centidegrees + + +0.0 0.2 +.005 +s +seconds + + +0.0 0.2 +.005 +s +seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + + + + +Normal +OneShot +OneShot125 +BrushedWithRelay +BrushedBiPolar + +True + + +1 20 +1 +kHz +kilohertz +True + + + +PWM enabled while disarmed +PWM disabled while disarmed + + + +0 20 +1 +% +percent + + +30 100 +1 +% +percent + + +0 1000 +1 +%/s +percent per second + + +-1.0 1.0 + + +0 100 +% +percent + + +0 10 +m/s +meters per second + + + + +1 60 +1 +s +seconds + + +0.6 1.0 +0.05 + + +0 0.1 +0.01 + + +0 89 +deg +degrees + + + + + +Off +Low +Medium +High + + + + +Disable +Enable + + + + +Disable +Enable + + + + +Disable +ssd1306 +sh1106 + + + + +Disabled +Aircraft +Rover + + + + +Disabled + + + + + + +None +LightWareSF40C +MAVLink +TeraRangerTower +RangeFinder +RPLidarA2 + +True + + + +Default +Upside Down + + + +-180 180 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + +0 360 +deg +degrees + + +0 45 +deg +degrees + + + +None +LightWareSF40C +MAVLink +TeraRangerTower +RangeFinder +RPLidarA2 + +True + + + +Default +Upside Down + + + +-180 180 +deg +degrees + + + + +0.0 120.0 +s +seconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + +0 200 +PWM +PWM in microseconds + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Disabled +APM2 A9 pin +APM1 relay +BB Blue GP0 pin 4 +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +BB Blue GP0 pin 3 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1/BB Blue GP0 pin 6 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2/BB Blue GP0 pin 5 + + + + +Disabled +APM2 A9 pin +APM1 relay +BB Blue GP0 pin 4 +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +BB Blue GP0 pin 3 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1/BB Blue GP0 pin 6 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2/BB Blue GP0 pin 5 + + + + +Disabled +APM2 A9 pin +APM1 relay +BB Blue GP0 pin 4 +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +BB Blue GP0 pin 3 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1/BB Blue GP0 pin 6 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2/BB Blue GP0 pin 5 + + + + +Disabled +APM2 A9 pin +APM1 relay +BB Blue GP0 pin 4 +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +BB Blue GP0 pin 3 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1/BB Blue GP0 pin 6 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2/BB Blue GP0 pin 5 + + + + +Off +On +NoChange + + + + + + +None +Analog +MaxbotixI2C +LidarLiteV2-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini + + + + +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 +m/V +meters per volt + + +0.001 +V +volt + + + +Linear +Inverted +Hyperbolic + + + +1 +cm +centimeters + + +1 +cm +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 +ms +milliseconds + + + +No +Yes + + + +0 32767 +m +meters + + +5 127 +1 +cm +centimeters + + +0 127 +1 + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + + + + +None +Analog +MaxbotixI2C +LidarLiteV2-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini + + + + +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 +m/V +meters per volt + + +0.001 +V +volt + + + +Linear +Inverted +Hyperbolic + + + +1 +cm +centimeters + + +1 +cm +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 +ms +milliseconds + + + +No +Yes + + + +0 127 +1 +cm +centimeters + + +0 127 +1 + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + + + + +None +Analog +MaxbotixI2C +LidarLiteV2-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini + + + + +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 +m/V +meters per volt + + +0.001 +V +volt + + + +Linear +Inverted +Hyperbolic + + + +1 +cm +centimeters + + +1 +cm +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 +ms +milliseconds + + + +No +Yes + + + +0 127 +1 +cm +centimeters + + +0 127 +1 + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + + + + +None +Analog +MaxbotixI2C +LidarLiteV2-I2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TeraRangerI2C +LidarLiteV3-I2C +VL53L0X +NMEA +WASP-LRF +BenewakeTF02 +BenewakeTFmini + + + + +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 +m/V +meters per volt + + +0.001 +V +volt + + + +Linear +Inverted +Hyperbolic + + + +1 +cm +centimeters + + +1 +cm +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 +ms +milliseconds + + + +No +Yes + + + +0 127 +1 +cm +centimeters + + +0 127 +1 + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Forward-Right +Right +Back-Right +Back +Back-Left +Left +Forward-Left +Up +Down + + + + + +0 255 + + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + + +Low Speed +High Speed + + + + + +0 255 + + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + + +Low Speed +High Speed + + + + + +0 255 + + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + + +Low Speed +High Speed + + + + + +0 255 + + +0 255 + + +0 10000 + + +0 255 + + +-1 255 + + + +Low Speed +High Speed + + + + + + +Disabled +AnalogPin +RCChannelPwmValue +ReceiverProtocol + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixracer +Pixhawk ADC4 +Pixhawk ADC3 +Pixhawk ADC6 +Pixhawk SBUS +Pixhawk2 ADC + + + +0 5.0 +0.01 +V +volt + + +0 5.0 +0.01 +V +volt + + + + +0 2000 +PWM +PWM in microseconds + + +0 2000 +PWM +PWM in microseconds + + + + + +Disabled +ShowSlips +ShowOverruns + + + + +50Hz +100Hz +200Hz +250Hz +300Hz +400Hz + +True + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +460800 +500000 +921600 +1500000 + + + + +MAVlink1 +MAVLink2 + +True + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Rangefinder +FrSky SPort Passthrough (OpenTX) +Lidar360 +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry + +True + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Rangefinder +FrSky SPort Passthrough (OpenTX) +Lidar360 +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry + +True + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Rangefinder +FrSky SPort Passthrough (OpenTX) +Lidar360 +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry + +True + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Rangefinder +FrSky SPort Passthrough (OpenTX) +Lidar360 +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry + +True + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Rangefinder +FrSky SPort Passthrough (OpenTX) +Lidar360 +Beacon +Volz servo out +SBus servo out +ESC Telemetry +Devo Telemetry + +True + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + + +Disable +Enable + + + +25 400 +Hz +hertz + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +500 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + +800 2200 +1 +PWM +PWM in microseconds + + + +Normal +Reversed + + + + +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 +DifferentialSpoilerLeft1 +DifferentialSpoilerRight1 +DifferentialSpoilerLeft2 +DifferentialSpoilerRight2 +Elevator +Rudder +FlaperonLeft +FlaperonRight +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +MotorTilt +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch +ThrottleLeft +ThrottleRight +tiltMotorLeft +tiltMotorRight +ElevonLeft +ElevonRight +VTailLeft +VTailRight +BoostThrottle +Motor9 +Motor10 +Motor11 +Motor12 +Winch + + + + + +0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + + + +Disabled +Enabled + + + + +Disabled +TestMotor1 +TestMotor2 +TestMotor3 +TestMotor4 +TestMotor5 +TestMotor6 +TestMotor7 +TestMotor8 + + + +0 300 +s +seconds + + +0 500 +Hz +hertz + + + +Disabled +Enabled + + + + +None +OneShot +OneShot125 +Brushed +DShot150 +DShot300 +DShot600 +DShot1200 + + + + + +25 250 +Hz +hertz + + + + +0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16 + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + +0 10 +1 +Hz +hertz + + + + +0 10 +m +meters + + +0 500 +True + + + + +True + + +True +s +seconds + + +True +s +seconds + + +True +s +seconds + + + + + +None +MAV + + + +m +meters + + +m +meters + + +m +meters + + + +Forward +Right +Back +Left +Up +Down + + + + + + +None +Quadrature + + + +1 + + +0.001 + + +0.01 +m +meters + + +0.01 +m +meters + + +0.01 +m +meters + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + +None +Quadrature + + + +1 + + +0.001 + + +0.01 +m +meters + + +0.01 +m +meters + + +0.01 +m +meters + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + diff --git a/src/FirmwarePlugin/APM/APMResources.qrc b/src/FirmwarePlugin/APM/APMResources.qrc index df6ffa966370b0359dd61078c07874fe78a69a16..be6702780bcaa2d66b736529402676f91a9ff35e 100644 --- a/src/FirmwarePlugin/APM/APMResources.qrc +++ b/src/FirmwarePlugin/APM/APMResources.qrc @@ -15,13 +15,9 @@ ../../AutoPilotPlugins/APM/APMPowerComponent.qml ../../AutoPilotPlugins/APM/APMPowerComponentSummary.qml ../../AutoPilotPlugins/APM/APMRadioComponentSummary.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentCopter.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentPlane.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentRover.qml + ../../AutoPilotPlugins/APM/APMSafetyComponent.qml ../../AutoPilotPlugins/APM/APMSafetyComponentSub.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentSummaryPlane.qml - ../../AutoPilotPlugins/APM/APMSafetyComponentSummaryRover.qml + ../../AutoPilotPlugins/APM/APMSafetyComponentSummary.qml ../../AutoPilotPlugins/APM/APMSafetyComponentSummarySub.qml ../../AutoPilotPlugins/APM/APMSensorsComponent.qml ../../AutoPilotPlugins/APM/APMSensorsComponentSummary.qml @@ -51,6 +47,7 @@ APMParameterFactMetaData.Copter.3.6.xml APMParameterFactMetaData.Rover.3.0.xml APMParameterFactMetaData.Rover.3.2.xml + APMParameterFactMetaData.Rover.3.4.xml APMParameterFactMetaData.Sub.3.4.xml APMParameterFactMetaData.Sub.3.5.xml Copter3.5.OfflineEditing.params