From a7779df7913ad6440fe2779a85f44debf44f4316 Mon Sep 17 00:00:00 2001 From: DonLakeFlyer Date: Fri, 25 May 2018 15:24:43 -0700 Subject: [PATCH] Adjust to new parameters in Copter 3.6 Includes support for battery 2 setup --- .../APM/APMAirframeComponentSummary.qml | 22 +- .../APM/APMPowerComponent.qml | 133 +- .../APM/APMPowerComponentSummary.qml | 25 +- .../APM/APMSafetyComponentCopter.qml | 288 +- .../APM/APMSafetyComponentPlane.qml | 4 +- .../APM/APMSafetyComponentSummaryCopter.qml | 86 +- .../FactControls/FactPanelController.cc | 2 + src/FirmwarePlugin/APM/APMFirmwarePlugin.cc | 2 + .../APMParameterFactMetaData.Copter.3.6.xml | 9398 +++++++++++++++++ src/FirmwarePlugin/APM/APMResources.qrc | 1 + .../APM/ArduCopterFirmwarePlugin.cc | 8 + 11 files changed, 9757 insertions(+), 212 deletions(-) create mode 100644 src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml diff --git a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml index 5afec5f85..d5f6e3261 100644 --- a/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMAirframeComponentSummary.qml @@ -18,32 +18,32 @@ FactPanel { factPanel: panel } - property bool _useOldFrameParam: controller.parameterExists(-1, "FRAME") - property Fact _oldFrameParam: controller.getParameterFact(-1, "FRAME", false) - property Fact _newFrameParam: controller.getParameterFact(-1, "FRAME_CLASS", false) - property Fact _frameTypeParam: controller.getParameterFact(-1, "FRAME_TYPE", false) + property bool _frameAvailable: controller.parameterExists(-1, "FRAME") + + property Fact _frame: controller.getParameterFact(-1, "FRAME", false) + property Fact _frameClass: controller.getParameterFact(-1, "FRAME_CLASS", false) + property Fact _frameType: controller.getParameterFact(-1, "FRAME_TYPE", false) Column { anchors.fill: parent VehicleSummaryRow { labelText: qsTr("Frame Type") - valueText: controller.currentAirframeTypeName() + " " + _oldFrameParam.enumStringValue - visible: _useOldFrameParam + valueText: visible ? controller.currentAirframeTypeName() + " " + _frame.enumStringValue : "" + visible: _frameAvailable } VehicleSummaryRow { labelText: qsTr("Frame Class") - valueText: _newFrameParam.enumStringValue - visible: !_useOldFrameParam + valueText: visible ? _frameClass.enumStringValue : "" + visible: !_frameAvailable } VehicleSummaryRow { labelText: qsTr("Frame Type") - valueText: _frameTypeParam.enumStringValue - visible: !_useOldFrameParam - + valueText: visible ? _frameType.enumStringValue : "" + visible: !_frameAvailable } VehicleSummaryRow { diff --git a/src/AutoPilotPlugins/APM/APMPowerComponent.qml b/src/AutoPilotPlugins/APM/APMPowerComponent.qml index 3d89553f1..3bb5028e5 100644 --- a/src/AutoPilotPlugins/APM/APMPowerComponent.qml +++ b/src/AutoPilotPlugins/APM/APMPowerComponent.qml @@ -31,46 +31,119 @@ SetupPage { Component { id: powerPageComponent - Column { - spacing: _margins + Flow { + id: flowLayout + width: availableWidth + spacing: _margins + + property bool _batt2ParamsAvailable: controller.parameterExists(-1, "BATT2_FS_LOW_ACT") + property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) - QGCLabel { text: qsTr("Battery 1"); font.pointSize: ScreenTools.mediumFontPointSize } + QGCPalette { id: ggcPal; colorGroupEnabled: true } - Loader { - sourceComponent: powerSetupComponent + // Battery 1 settings + Column { + spacing: _margins / 2 + + QGCLabel { + text: qsTr("Battery 1") + font.family: ScreenTools.demiboldFontFamily + } - property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT_MIN") - property Fact battAmpPerVolt: controller.getParameterFact(-1, "BATT_AMP_PERVOLT") - property Fact battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY") - property Fact battCurrPin: controller.getParameterFact(-1, "BATT_CURR_PIN") - property Fact battMonitor: controller.getParameterFact(-1, "BATT_MONITOR") - property Fact battVoltMult: controller.getParameterFact(-1, "BATT_VOLT_MULT") - property Fact battVoltPin: controller.getParameterFact(-1, "BATT_VOLT_PIN") - property Fact vehicleVoltage: controller.vehicle.battery.voltage - property Fact vehicleCurrent: controller.vehicle.battery.current + Rectangle { + width: battery1Loader.x + battery1Loader.width + _margins + height: battery1Loader.y + battery1Loader.height + _margins + color: ggcPal.windowShade + + Loader { + id: battery1Loader + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + sourceComponent: powerSetupComponent + + property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT_MIN") + property Fact battAmpPerVolt: controller.getParameterFact(-1, "r.BATT_AMP_PERVLT") + property Fact battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY") + property Fact battCurrPin: controller.getParameterFact(-1, "BATT_CURR_PIN") + property Fact battMonitor: controller.getParameterFact(-1, "BATT_MONITOR") + property Fact battVoltMult: controller.getParameterFact(-1, "BATT_VOLT_MULT") + property Fact battVoltPin: controller.getParameterFact(-1, "BATT_VOLT_PIN") + property Fact vehicleVoltage: controller.vehicle.battery.voltage + property Fact vehicleCurrent: controller.vehicle.battery.current + } + } } - Item { - height: ScreenTools.defaultFontPixelHeight - width: 1 + // Batter2 Monitor settings only - used when only monitor param is available + Column { + spacing: _margins / 2 + visible: _batt2MonitorAvailable && !_batt2ParamsAvailable + + QGCLabel { + text: qsTr("Battery 2") + font.family: ScreenTools.demiboldFontFamily + } + + Rectangle { + width: batt2MonitorRow.x + batt2MonitorRow.width + _margins + height: batt2MonitorRow.y + batt2MonitorRow.height + _margins + color: ggcPal.windowShade + + RowLayout { + id: batt2MonitorRow + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + spacing: ScreenTools.defaultFontPixelWidth + visible: _batt2MonitorAvailable && !_batt2ParamsAvailable + + QGCLabel { text: qsTr("Battery2 monitor:") } + FactComboBox { + id: monitorCombo + fact: _batt2Monitor + indexModel: false + } + } + } } - QGCLabel { text: qsTr("Battery 2"); font.pointSize: ScreenTools.mediumFontPointSize } + // Battery 2 settings - Used when full params are available + Column { + spacing: _margins / 2 + visible: _batt2ParamsAvailable - Loader { - sourceComponent: powerSetupComponent + QGCLabel { + text: qsTr("Battery 2") + font.family: ScreenTools.demiboldFontFamily + } - property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT2_MIN") - property Fact battAmpPerVolt: controller.getParameterFact(-1, "BATT2_AMP_PERVOL") - property Fact battCapacity: controller.getParameterFact(-1, "BATT2_CAPACITY") - property Fact battCurrPin: controller.getParameterFact(-1, "BATT2_CURR_PIN") - property Fact battMonitor: controller.getParameterFact(-1, "BATT2_MONITOR") - property Fact battVoltMult: controller.getParameterFact(-1, "BATT2_VOLT_MULT") - property Fact battVoltPin: controller.getParameterFact(-1, "BATT2_VOLT_PIN") - property Fact vehicleVoltage: controller.vehicle.battery2.voltage - property Fact vehicleCurrent: controller.vehicle.battery2.current + Rectangle { + width: battery2Loader.x + battery2Loader.width + _margins + height: battery2Loader.y + battery2Loader.height + _margins + color: ggcPal.windowShade + + Loader { + id: battery2Loader + anchors.margins: _margins + anchors.top: parent.top + anchors.left: parent.left + sourceComponent: _batt2ParamsAvailable ? powerSetupComponent : undefined + + property Fact armVoltMin: controller.getParameterFact(-1, "r.ARMING_VOLT2_MIN", false /* reportMissing */) + property Fact battAmpPerVolt: controller.getParameterFact(-1, "r.BATT2_AMP_PERVLT", false /* reportMissing */) + property Fact battCapacity: controller.getParameterFact(-1, "BATT2_CAPACITY", false /* reportMissing */) + property Fact battCurrPin: controller.getParameterFact(-1, "BATT2_CURR_PIN", false /* reportMissing */) + property Fact battMonitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) + property Fact battVoltMult: controller.getParameterFact(-1, "BATT2_VOLT_MULT", false /* reportMissing */) + property Fact battVoltPin: controller.getParameterFact(-1, "BATT2_VOLT_PIN", false /* reportMissing */) + property Fact vehicleVoltage: controller.vehicle.battery2.voltage + property Fact vehicleCurrent: controller.vehicle.battery2.current + } + } } - } + } // Flow } // Component - powerPageComponent Component { diff --git a/src/AutoPilotPlugins/APM/APMPowerComponentSummary.qml b/src/AutoPilotPlugins/APM/APMPowerComponentSummary.qml index 4767e8851..ab2356176 100644 --- a/src/AutoPilotPlugins/APM/APMPowerComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMPowerComponentSummary.qml @@ -24,20 +24,37 @@ FactPanel { QGCPalette { id: qgcPal; colorGroupEnabled: enabled } FactPanelController { id: controller; factPanel: panel } - property Fact battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY") - property Fact battMonitor: controller.getParameterFact(-1, "BATT_MONITOR") + property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") + property bool _batt2CapacityAvailable: controller.parameterExists(-1, "BATT2_CAPACITY") + + property Fact _battCapacity: controller.getParameterFact(-1, "BATT_CAPACITY") + property Fact _batt2Capacity: controller.getParameterFact(-1, "BATT2_CAPACITY", false /* reportMissing */) + property Fact _battMonitor: controller.getParameterFact(-1, "BATT_MONITOR") + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) Column { anchors.fill: parent VehicleSummaryRow { labelText: qsTr("Battery monitor") - valueText: battMonitor.enumStringValue + valueText: _battMonitor.enumStringValue } VehicleSummaryRow { labelText: qsTr("Battery capacity") - valueText: battCapacity.valueString + " " + battCapacity.units + valueText: _battCapacity.valueString + " " + _battCapacity.units + } + + VehicleSummaryRow { + labelText: qsTr("Battery2 monitor") + valueText: _batt2MonitorAvailable ? _batt2Monitor.enumStringValue : "" + visible: _batt2MonitorAvailable + } + + VehicleSummaryRow { + labelText: qsTr("Battery2 capacity") + valueText: _batt2CapacityAvailable ? _batt2Capacity.valueString + " " + _battCapacity.units : "" + visible: _batt2CapacityAvailable } } } diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentCopter.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentCopter.qml index 24f5c0752..24f560c05 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponentCopter.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentCopter.qml @@ -11,6 +11,7 @@ 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 @@ -34,12 +35,25 @@ SetupPage { QGCPalette { id: ggcPal; colorGroupEnabled: true } - property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE") - property Fact _failsafeBattEnable: controller.getParameterFact(-1, "FS_BATT_ENABLE") - property Fact _failsafeBattMah: controller.getParameterFact(-1, "FS_BATT_MAH") - property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "FS_BATT_VOLTAGE") - property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE") - property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE") + property Fact _failsafeGCSEnable: controller.getParameterFact(-1, "FS_GCS_ENABLE") + property Fact _failsafeBattLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT") + property Fact _failsafeBattMah: controller.getParameterFact(-1, "r.BATT_LOW_MAH") + property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "r.BATT_LOW_VOLT") + property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE") + property Fact _failsafeThrValue: controller.getParameterFact(-1, "FS_THR_VALUE") + + property bool _failsafeBattCritActAvailable: controller.parameterExists(-1, "BATT_FS_CRT_ACT") + property bool _failsafeBatt2LowActAvailable: controller.parameterExists(-1, "BATT2_FS_LOW_ACT") + property bool _failsafeBatt2CritActAvailable: controller.parameterExists(-1, "BATT2_FS_CRT_ACT") + property bool _batt2MonitorAvailable: controller.parameterExists(-1, "BATT2_MONITOR") + property bool _batt2MonitorEnabled: _batt2MonitorAvailable ? _batt2Monitor.rawValue !== 0 : false + + property Fact _failsafeBattCritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */) + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) + property Fact _failsafeBatt2LowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */) + property Fact _failsafeBatt2CritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */) + property Fact _failsafeBatt2Mah: controller.getParameterFact(-1, "BATT2_LOW_MAH", false /* reportMissing */) + property Fact _failsafeBatt2Voltage: controller.getParameterFact(-1, "BATT2_LOW_VOLT", false /* reportMissing */) property Fact _fenceAction: controller.getParameterFact(-1, "FENCE_ACTION") property Fact _fenceAltMax: controller.getParameterFact(-1, "FENCE_ALT_MAX") @@ -66,135 +80,193 @@ SetupPage { spacing: _margins / 2 QGCLabel { - id: failsafeLabel - text: qsTr("Failsafe Triggers") + text: qsTr("Battery Failsafe Triggers") font.family: ScreenTools.demiboldFontFamily } Rectangle { - id: failsafeSettings - width: throttleEnableCombo.x + throttleEnableCombo.width + _margins - height: mahField.y + mahField.height + _margins + width: batteryFailsafeColumn.x + batteryFailsafeColumn.width + _margins + height: batteryFailsafeColumn.y + batteryFailsafeColumn.height + _margins color: ggcPal.windowShade - QGCLabel { - id: gcsEnableLabel + Column { + id: batteryFailsafeColumn anchors.margins: _margins + anchors.top: parent.top anchors.left: parent.left - anchors.baseline: gcsEnableCombo.baseline - text: qsTr("Ground Station failsafe:") - } + spacing: _margins + + GridLayout { + id: gridLayout + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + QGCLabel { text: qsTr("Battery low:") } + FactComboBox { + fact: _failsafeBattLowAct + indexModel: false + Layout.fillWidth: true + } - FactComboBox { - id: gcsEnableCombo - anchors.topMargin: _margins - anchors.leftMargin: _margins - anchors.left: gcsEnableLabel.right - anchors.top: parent.top - width: voltageField.width - fact: _failsafeGCSEnable - indexModel: false - } + QGCLabel { + text: qsTr("Battery critical:") + visible: _failsafeBattCritActAvailable + } + FactComboBox { + fact: _failsafeBattCritAct + visible: _failsafeBattCritActAvailable + indexModel: false + Layout.fillWidth: true + } - QGCLabel { - id: throttleEnableLabel - anchors.margins: _margins - anchors.left: parent.left - anchors.baseline: throttleEnableCombo.baseline - text: qsTr("Throttle failsafe:") - } + QGCCheckBox { + text: qsTr("Voltage threshold:") + checked: _failsafeBattVoltage.value != 0 + onClicked: _failsafeBattVoltage.value = checked ? 10.5 : 0 + } + FactTextField { + fact: _failsafeBattVoltage + showUnits: true + Layout.fillWidth: true + } - QGCComboBox { - id: throttleEnableCombo - anchors.topMargin: _margins - anchors.left: gcsEnableCombo.left - anchors.top: gcsEnableCombo.bottom - width: voltageField.width - model: [qsTr("Disabled"), qsTr("Always RTL"), - qsTr("Continue with Mission in Auto Mode"), qsTr("Always Land")] - currentIndex: _failsafeThrEnable.value - - onActivated: _failsafeThrEnable.value = index - } + QGCCheckBox { + text: qsTr("MAH threshold:") + checked: _failsafeBattMah.value != 0 + onClicked: _failsafeBattMah.value = checked ? 600 : 0 + } + FactTextField { + fact: _failsafeBattMah + showUnits: true + Layout.fillWidth: true + } + } // GridLayout + } // Column + } // Rectangle + } // Column - Battery Failsafe Settings - QGCLabel { - id: throttlePWMLabel - anchors.margins: _margins - anchors.left: parent.left - anchors.baseline: throttlePWMField.baseline - text: qsTr("PWM threshold:") - } + Column { + spacing: _margins / 2 + visible: _batt2MonitorEnabled && _failsafeBatt2LowActAvailable - FactTextField { - id: throttlePWMField - anchors.topMargin: _margins / 2 - anchors.left: gcsEnableCombo.left - anchors.top: throttleEnableCombo.bottom - fact: _failsafeThrValue - showUnits: true - } + QGCLabel { + text: qsTr("Battery2 Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } - QGCLabel { - id: batteryEnableLabel + 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 - anchors.baseline: batteryEnableCombo.baseline - text: qsTr("Battery failsafe:") - } + spacing: _margins + + GridLayout { + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + visible: _batt2MonitorEnabled && _failsafeBatt2LowActAvailable + + QGCLabel { text: qsTr("Battery low:") } + FactComboBox { + fact: _failsafeBatt2LowAct + indexModel: false + Layout.fillWidth: true + } - QGCComboBox { - id: batteryEnableCombo - anchors.topMargin: _margins - anchors.left: gcsEnableCombo.left - anchors.top: throttlePWMField.bottom - width: voltageField.width - model: [qsTr("Disabled"), qsTr("Land"), qsTr("Return to Launch")] - currentIndex: _failsafeBattEnable.value + QGCLabel { + text: qsTr("Battery critical:") + } + FactComboBox { + fact: _failsafeBatt2CritAct + indexModel: false + Layout.fillWidth: true + } - onActivated: _failsafeBattEnable.value = index - } + 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 { - id: voltageLabel - anchors.margins: _margins - anchors.left: parent.left - anchors.baseline: voltageField.baseline - text: qsTr("Voltage threshold:") - checked: _failsafeBattVoltage.value != 0 + 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 - onClicked: _failsafeBattVoltage.value = checked ? 10.5 : 0 - } + Column { + spacing: _margins / 2 - FactTextField { - id: voltageField - anchors.topMargin: _margins / 2 - anchors.left: gcsEnableCombo.left - anchors.top: batteryEnableCombo.bottom - fact: _failsafeBattVoltage - showUnits: true - } + QGCLabel { + text: qsTr("General Failsafe Triggers") + font.family: ScreenTools.demiboldFontFamily + } - QGCCheckBox { - id: mahLabel + 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 - anchors.baseline: mahField.baseline - text: qsTr("MAH threshold:") - checked: _failsafeBattMah.value != 0 + spacing: _margins + + GridLayout { + columnSpacing: _margins + rowSpacing: _margins + columns: 2 + + QGCLabel { text: qsTr("Ground Station failsafe:") } + FactComboBox { + fact: _failsafeGCSEnable + indexModel: false + Layout.fillWidth: true + } - onClicked: _failsafeBattMah.value = checked ? 600 : 0 - } + 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 - FactTextField { - id: mahField - anchors.topMargin: _margins / 2 - anchors.left: gcsEnableCombo.left - anchors.top: voltageField.bottom - fact: _failsafeBattMah - showUnits: true - } + onActivated: _failsafeThrEnable.value = index + } + + QGCLabel { text: qsTr("PWM threshold:") } + FactTextField { + fact: _failsafeThrValue + showUnits: true + Layout.fillWidth: true + } + } // GridLayout + } // Column } // Rectangle - Failsafe Settings - } // Column - Failsafe Settings + } // Column - General Failsafe Settings Column { spacing: _margins / 2 diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentPlane.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentPlane.qml index 700603914..36f902797 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponentPlane.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentPlane.qml @@ -34,8 +34,8 @@ SetupPage { QGCPalette { id: palette; colorGroupEnabled: true } - property Fact _failsafeBattMah: controller.getParameterFact(-1, "FS_BATT_MAH") - property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "FS_BATT_VOLTAGE") + property Fact _failsafeBattMah: controller.getParameterFact(-1, "r.BATT_LOW_MAH") + property Fact _failsafeBattVoltage: controller.getParameterFact(-1, "r.BATT_LOW_VOLT") 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") diff --git a/src/AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml b/src/AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml index 785147b39..a08b9c082 100644 --- a/src/AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml +++ b/src/AutoPilotPlugins/APM/APMSafetyComponentSummaryCopter.qml @@ -14,7 +14,7 @@ FactPanel { QGCPalette { id: qgcPal; colorGroupEnabled: enabled } FactPanelController { id: controller; factPanel: panel } - property Fact _failsafeBattEnable: controller.getParameterFact(-1, "FS_BATT_ENABLE") + property Fact _failsafeBattLowAct: controller.getParameterFact(-1, "r.BATT_FS_LOW_ACT") property Fact _failsafeThrEnable: controller.getParameterFact(-1, "FS_THR_ENABLE") property Fact _fenceAction: controller.getParameterFact(-1, "FENCE_ACTION") @@ -28,60 +28,14 @@ FactPanel { property Fact _armingCheck: controller.getParameterFact(-1, "ARMING_CHECK") - property string _failsafeBattEnableText - property string _failsafeThrEnableText + property bool _failsafeBattCritActAvailable: controller.parameterExists(-1, "BATT_FS_CRT_ACT") + property bool _failsafeBatt2LowActAvailable: controller.parameterExists(-1, "BATT2_FS_LOW_ACT") + property bool _failsafeBatt2CritActAvailable: controller.parameterExists(-1, "BATT2_FS_CRT_ACT") - Component.onCompleted: { - setFailsafeBattEnableText() - setFailsafeThrEnableText() - } - - Connections { - target: _failsafeBattEnable - - onValueChanged: setFailsafeBattEnableText() - } - - Connections { - target: _failsafeThrEnable - - onValueChanged: setFailsafeThrEnableText() - } - - function setFailsafeThrEnableText() { - switch (_failsafeThrEnable.value) { - case 0: - _failsafeThrEnableText = qsTr("Disabled") - break - case 1: - _failsafeThrEnableText = qsTr("Always RTL") - break - case 2: - _failsafeThrEnableText = qsTr("Continue with Mission in Auto Mode") - break - case 3: - _failsafeThrEnableText = qsTr("Always Land") - break - default: - _failsafeThrEnableText = qsTr("Unknown") - } - } - - function setFailsafeBattEnableText() { - switch (_failsafeBattEnable.value) { - case 0: - _failsafeBattEnableText = qsTr("Disabled") - break - case 1: - _failsafeBattEnableText = qsTr("Land") - break - case 2: - _failsafeBattEnableText = qsTr("Return to Launch") - break - default: - _failsafeThrEnableText = qsTr("Unknown") - } - } + property Fact _failsafeBattCritAct: controller.getParameterFact(-1, "BATT_FS_CRT_ACT", false /* reportMissing */) + property Fact _batt2Monitor: controller.getParameterFact(-1, "BATT2_MONITOR", false /* reportMissing */) + property Fact _failsafeBatt2LowAct: controller.getParameterFact(-1, "BATT2_FS_LOW_ACT", false /* reportMissing */) + property Fact _failsafeBatt2CritAct: controller.getParameterFact(-1, "BATT2_FS_CRT_ACT", false /* reportMissing */) Column { anchors.fill: parent @@ -93,12 +47,30 @@ FactPanel { VehicleSummaryRow { labelText: qsTr("Throttle failsafe:") - valueText: _failsafeThrEnableText + valueText: _failsafeBattLowAct.enumStringValue + } + + VehicleSummaryRow { + labelText: qsTr("Batt low failsafe:") + valueText: _failsafeBattLowAct.enumStringValue + } + + VehicleSummaryRow { + labelText: qsTr("Batt critical failsafe:") + valueText: _failsafeBattCritActAvailable ? _failsafeBattCritAct.enumStringValue : "" + visible: _failsafeBattCritActAvailable + } + + VehicleSummaryRow { + labelText: qsTr("Batt2 low failsafe:") + valueText: _failsafeBatt2LowActAvailable ? _failsafeBatt2LowAct.enumStringValue : "" + visible: _failsafeBatt2LowActAvailable } VehicleSummaryRow { - labelText: qsTr("Battery failsafe:") - valueText: _failsafeBattEnableText + labelText: qsTr("Batt2 critical failsafe:") + valueText: _failsafeBatt2CritActAvailable ? _failsafeBatt2CritAct.enumStringValue : "" + visible: _failsafeBatt2CritActAvailable } VehicleSummaryRow { diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index dc19cb91f..ea3e6aded 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -88,6 +88,8 @@ void FactPanelController::_reportMissingParameter(int componentId, const QString QString missingParam = QString("%1:%2").arg(componentId).arg(name); + qCWarning(FactPanelControllerLog) << "Missing parameter:" << missingParam; + // If missing parameters a reported from the constructor of a derived class we // will not have access to _factPanel yet. Just record list of missing facts // in that case instead of notify. Once _factPanel is available they will be diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 9b725e3e6..7830075e5 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -791,6 +791,8 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"); 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"); diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml new file mode 100644 index 000000000..1d6ffda00 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml @@ -0,0 +1,9398 @@ + + + + + + +True + + +True + +ArduPlane +AntennaTracker +Copter +Rover +ArduSub + + + +1 255 + + + +Mission Planner and DroidPlanner + AP Planner 2 + + + +0 10 +.5 +Hz +hertz + + +0.0 1000.0 +10 +cm +centimeters + + +0 500 +10 + + +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 + + + +0 30 +1 +s +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 8000 +1 +cm +centimeters + + +0.5 10.0 + +Disabled +Shallow +Steep + +.1 + + +0 2000 +50 +cm/s +centimeters per second + + +-1 1000 +1 +cm +centimeters + + +0 3000 +10 +cm +centimeters + + +0 60000 +1000 +ms +milliseconds + + +0.01 2.0 +0.01 + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always SmartRTL or RTL +Enabled always SmartRTL or Land + + + +100 900 + + + +Disabled +Enabled + + + + +Disabled +Mode1 +Mode2 +Mode1+2 +Mode3 +Mode1+3 +Mode2+3 +Mode1+2+3 +Mode4 +Mode1+4 +Mode2+4 +Mode1+2+4 +Mode3+4 +Mode1+3+4 +Mode2+3+4 +Mode1+2+3+4 +Mode5 +Mode1+5 +Mode2+5 +Mode1+2+5 +Mode3+5 +Mode1+3+5 +Mode2+3+5 +Mode1+2+3+5 +Mode4+5 +Mode1+4+5 +Mode2+4+5 +Mode1+2+4+5 +Mode3+4+5 +Mode1+3+4+5 +Mode2+3+4+5 +Mode1+2+3+4+5 +Mode6 +Mode1+6 +Mode2+6 +Mode1+2+6 +Mode3+6 +Mode1+3+6 +Mode2+3+6 +Mode1+2+3+6 +Mode4+6 +Mode1+4+6 +Mode2+4+6 +Mode1+2+4+6 +Mode3+4+6 +Mode1+3+4+6 +Mode2+3+4+6 +Mode1+2+3+4+6 +Mode5+6 +Mode1+5+6 +Mode2+5+6 +Mode1+2+5+6 +Mode3+5+6 +Mode1+3+5+6 +Mode2+3+5+6 +Mode1+2+3+5+6 +Mode4+5+6 +Mode1+4+5+6 +Mode2+4+5+6 +Mode1+2+4+5+6 +Mode3+4+5+6 +Mode1+3+4+5+6 +Mode2+3+4+5+6 +Mode1+2+3+4+5+6 + + + + +Never change yaw +Face next waypoint +Face next waypoint except RTL +Face along GPS course + + + +30 200 +10 +cm/s +centimeters per second + + +0 500 +10 +cm/s +centimeters per second + + +50 500 +10 +cm/s +centimeters per second + + +50 500 +10 +cm/s/s +centimeters per square second + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always Land +Enabled always SmartRTL or RTL +Enabled always SmartRTL or Land + + + +925 1100 +1 +PWM +PWM in microseconds + + +0 300 +1 +PWM +PWM in microseconds + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +Smart_RTL +FlowHold +Follow + + + + +Disabled +Channel5 +Channel6 +Channel7 +Channel8 + + + + + +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 + + + + +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 + + + + +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 +Rate Yaw Filter +Motor Yaw Headroom +AltHold kP +Throttle Rate kP +Throttle Accel kP +Throttle Accel kI +Throttle Accel kD +Loiter Pos kP +Velocity XY kP +Velocity XY kI +WP Speed +Acro RollPitch kP +Acro Yaw kP +RC Feel +Heli Ext Gyro +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 +Winch + + + +0 32767 + + +0 32767 + + + +Plus +X +V +H +V-Tail +A-Tail +Y6B + +True + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + + +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 +ADSB-Avoidance +PrecLoiter +Object Avoidance +ArmDisarm +SmartRTL +InvertedFlight +Winch Enable +WinchControl + + + +0 127 +s +seconds + + +1000 8000 +cdeg +centidegrees + + +4 12 +deg/s +degrees per second + + +2000 4500 +cdeg +centidegrees + + + +No repositioning +Repositioning + + + + +Land +AltHold +Land even in Stabilize + + + +0.6:Strict, 0.8:Default, 1.0:Relaxed + + + +Disabled +Enabled + + + +50 490 +1 +Hz +hertz + + +1 10 + + +1 10 + + +0 3 +0.1 + + +0 3 +0.1 + + + +Disabled +Leveling +Leveling and Limited + + + +-0.5 1.0 + +Disabled +Very Low +Low +Medium +High +Very High + + + +0:Roll,1:Pitch,2:Yaw + +All +Roll Only +Pitch Only +Yaw Only +Roll and Pitch +Roll and Yaw +Pitch and Yaw + + + +0.05 0.10 + + +0.001 0.006 + + + +Stopped +Running + + + + +Do Not Use in RTL and Land +Use in RTL and Land + + + +0 5 + + + +Auto +Guided +LOITER +RTL +Land +Brake +Throw + + + + +Upward Throw +Drop + + + + +Disabled +Enabled + + + +0:ADSBMavlinkProcessing + + +-0.5 1.0 + +Disabled +Very Low +Low +Medium +High +Very High + + + +0 1 + + + +NotEnforced +Enforced + + + + +Undefined +Quad +Hexa +Octa +OctaQuad +Y6 +Heli +Tri +SingleCopter +CoaxCopter +Heli_Dual +DodecaHexa +HeliQuad + +True + + +50 500 +10 +cm/s +centimeters per second + + +100 10000 +10 +cm +centimeters + + + + + +Disabled +Enabled + + + +1 100 + + +1 100000 + + +-1 16777215 + + + +NoInfo +Light +Small +Large +HighVortexlarge +Heavy +HighlyManuv +Rotocraft +RESERVED +Glider +LightAir +Parachute +UltraLight +RESERVED +UAV +Space +RESERVED +EmergencySurface +ServiceSurface +PointObstacle + + + + +NO_DATA +L15W23 +L25W28P5 +L25W34 +L35W33 +L35W38 +L45W39P5 +L45W45 +L55W45 +L55W52 +L65W59P5 +L65W67 +L75W72P5 +L75W80 +L85W80 +L85W90 + + + + +NoData +Left2m +Left4m +Left6m +Center +Right2m +Right4m +Right6m + + + + +NO_DATA +AppliedBySensor + + + + +Disabled +Rx-Only +Tx-Only +Rx and Tx Enabled + + + +octal +octal + + +0:UAT_in,1:1090ES_in,2:UAT_out,3:1090ES_out + +Unknown +Rx UAT only +Rx UAT and 1090ES +Rx&Tx UAT and 1090ES + + + + + + + + + + + + + + + + + + + + + +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 + + + + +500 18000 +100 +cdeg/s +centidegrees per second + + +0 72000 + +Disabled +VerySlow +Slow +Medium +Fast + +1000 +cdeg/s/s +centidegrees per square second + + + +Disabled +Enabled + + + +0 180000 + +Disabled +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 +Enabled + + + +3.000 12.000 + + +3.000 12.000 + + +3.000 6.000 + + +0.5 10.0 + + +0 1080 + +Disabled +Slow +Medium +Fast + +1 +deg/s +degrees per second + + +0 1080 + +Disabled +Slow +Medium +Fast + +1 +deg/s +degrees per second + + +0 1080 + +Disabled +Slow +Medium +Fast + +1 +deg/s +degrees per second + + +0 1 +0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp +0.01 +s +seconds + + +0.05 0.5 +0.005 + + +0.01 2.0 +0.01 + + +0 1 +0.01 +% +percent + + +0.0 0.02 +0.001 + + +0 0.5 +0.001 + + +1 100 +1 +Hz +hertz + + +0.05 0.50 +0.005 + + +0.01 2.0 +0.01 + + +0 1 +0.01 +% +percent + + +0.0 0.02 +0.001 + + +0 0.5 +0.001 + + +1 100 +1 +Hz +hertz + + +0.10 2.50 +0.005 + + +0.010 1.0 +0.01 + + +0 1 +0.01 +% +percent + + +0.000 0.02 +0.001 + + +0 0.5 +0.001 + + +1 10 +1 +Hz +hertz + + +0.1 0.25 + + +0.5 0.9 + + +0.1 0.9 + + +0 1000 +cdeg +centidegrees + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +0 0.5 +0.001 + + +1 20 +1 +Hz +hertz + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +0 0.5 +0.001 + + +1 20 +1 +Hz +hertz + + +0.180 0.60 +0.005 + + +0.01 0.06 +0.01 + + +0 1 +0.01 + + +0.000 0.02 +0.001 + + +0 0.5 +0.001 + + +1 20 +1 +Hz +hertz + + + +Disabled +Enabled + + + + + + +Disabled +Enabled + + + + +Remain in AVOID_ADSB +Resume previous flight mode +RTL +Resume if AUTO else Loiter + + + + + +s +seconds + + +s +seconds + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + +m +meters + + + + +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 + + + + +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + + + + +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + + + + + +A/V +ampere per volt + + +V +volt + + +50 +mA.h +milliampere hour + + +1 +W +watt + + + + +0 120 +1 +s +seconds + + + +Raw Voltage +Sag Compensated Voltage + + + +0.1 +V +volt + + +50 +mA.h +milliampere hour + + +0.1 +V +volt + + +50 +mA.h +milliampere hour + + + +Nothing +Land +RTL +SmartRTL +SmartRTL or Land +Terminate + + + + +Nothing +Land +RTL +SmartRTL +SmartRTL or Land +Terminate + + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell +UAVCAN-BatteryInfo + + + + +Disabled +A0 +A1 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + + + + +Disabled +A1 +A2 +Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 +Pixhawk2_PM2 +PX4-v1 + + + + + +A/V +ampere per volt + + +V +volt + + +50 +mA.h +milliampere hour + + +1 +W +watt + + + + +0 120 +1 +s +seconds + + + +Raw Voltage +Sag Compensated Voltage + + + +0.1 +V +volt + + +50 +mA.h +milliampere hour + + +0.1 +V +volt + + +50 +mA.h +milliampere hour + + + +Nothing +Land +RTL +SmartRTL +SmartRTL or Land +Terminate + + + + +Nothing +Land +RTL +SmartRTL +SmartRTL or Land +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 + + + + + +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 + + + + + + +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 + + + + +0 10000 +100 +cm +centimeters + + +-90 90 +1 +deg/s +degrees per second + + + + +-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 + + + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0 4500 +10 +cdeg +centidegrees + + +0.1 2.5 + + +1 100 +Hz +hertz + + +0 255 + + +1 30 +deg/s +degrees per second + + + + + +Disabled +Enabled + + + +-200 +200 +1 + + +-200 +200 +1 + + +-18000 +18000 +1 + + +m +meters + + +m +meters + + +m +meters + + +0 127 + + + + + +Disabled +Enabled + + + +0 255 + + +1 1000 +m +meters + + + +North-East-Down +Relative to lead vehicle heading + + + +-100 100 +1 +m +meters + + +-100 100 +1 +m +meters + + +-100 100 +1 +m +meters + + + +None +Face Lead Vehicle +Same as Lead vehicle +Direction of Flight + + + +0.01 1.00 +0.01 + + + + +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 + + + + + +Disabled +Enabled + + + + +None +Servo +EPM + + + +1000 2000 +PWM +PWM in microseconds + + +1000 2000 +PWM +PWM in microseconds + + +1000 2000 +PWM +PWM in microseconds + + +0 255 +s +seconds + + +0 255 + + + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + + +Servo only +Servo with ExtGyro +DirectDrive VarPitch +DirectDrive FixedPitch + + + + +H3 CCPM Adjustable +H1 Straight Swash +H3_140 CCPM + + + +0 1000 +1 +PWM +PWM in microseconds + + +-30 30 +1 +deg +degrees + + +-10 10 +0.1 + + + +NoFlybar +Flybar + + + +0 1000 +1 +PWM +PWM in microseconds + + +0 1000 +1 +PWM +PWM in microseconds + + +0: Normal, 1: Reversed + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-180 180 +1 +deg +degrees + + +-90 90 +1 +deg +degrees + + +-90 90 +1 +deg +degrees + + + +Longitudinal +Transverse + + + +0 1 + + +-10 10 +0.1 + + +-10 10 +0.1 + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + +0: Normal, 1: Reversed + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + + +Disabled +Passthrough +Max collective +Mid collective +Min collective + + + +0 1000 +10 +PWM +PWM in microseconds + + + +Ch8 Input +SetPoint +Throttle Curve + + + +0 500 +1 +PWM +PWM in microseconds + + +0 60 +s +seconds + + +0 60 +s +seconds + + +0 1000 +10 + + +0 500 +10 + + +0 18000 +100 +cdeg +centidegrees + + +0 10 +1 + + +0 500 +10 + + +0 1000 +10 + + +0 1000 +10 + + +0 1000 +10 + + +0 1000 +10 + + +0 1000 +10 + + + + +0 500 +1 +d% +decipercent + + +0 500 +1 +d% +decipercent + + +500 1000 +1 +d% +decipercent + + +500 1000 +1 +d% +decipercent + + + +Disabled +Very Low +Low +Medium +High +Very High + + + + + + + +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 + + + + +1000 2000 +1 +PWM +PWM in microseconds + + +1000 2000 +1 +PWM +PWM in microseconds + + + +WaitForPilotInput +Retract +Deploy + + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +kB +kilobytes + + + + +0 45 +1 +deg +degrees + + +20 2000 +50 +cm/s +centimeters per second + + +100 981 +1 +cm/s/s +centimeters per square second + + +25 250 +1 +cm/s/s +centimeters per square second + + +500 5000 +1 +cm/s/s/s +centimeters per cubic second + + +0 2 +0.1 +s +seconds + + + + +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 + + + + + +0 500 +PWM +PWM in microseconds + + +0.25 0.8 + + +0.9:Low, 0.95:Default, 1.0:High + + +6 35 +V +volt + + +6 35 +V +volt + + +0 200 +A +ampere + + + +Normal +OneShot +OneShot125 +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 +s +seconds + + +0.2 0.8 + + + +Disabled +Learn +LearnAndSave + + + + +PWM enabled while disarmed +PWM disabled while disarmed + + + +5 80 +1 +deg +degrees + + +0 2 +0.1 +s +seconds + + +0 5 +0.1 + + + +First battery +Second battery + + + + + + +Off +Low +Medium +High + + + + +Disable +Enable + + + + +Disable +Enable + + + + +Disable +ssd1306 +sh1106 + + + + +Disabled +Aircraft +Rover + + + + +Disabled + + + + + + +Disabled +Enabled Always Land +Enabled Strict + + + + +None +CompanionComputer +IRLock +SITL_Gazebo +SITL + + + +0 360 +1 +cdeg +centidegrees + + +-20 20 +1 +cm +centimeters + + +-20 20 +1 +cm +centimeters + + + +RawSensor +KalmanFilter + + + +0.5 5 + + +m +meters + + +m +meters + + +m +meters + + + +DefaultBus +InternalI2C +ExternalI2C + + + + + + +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.5 5 +0.1 +Hz +hertz + + +1.000 3.000 + + +1.000 8.000 + + +0.500 1.500 +0.05 + + +0.000 3.000 + + +0 1000 +d% +decipercent + + +0.000 0.400 + + +1.000 100.000 +Hz +hertz + + +0.500 2.000 + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0.00 1.00 +0.001 + + +0 4500 +10 +cm/s/s +centimeters per square second + + +0 100 +Hz +hertz + + +0 100 +Hz +hertz + + +0 45 +1 +deg +degrees + + + + + + +0.1 +km +kilometers + + + +DoNotIncludeHome +IncludeHome + + + + + +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 + + + + +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 + + + + +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 + + + + +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 + + + + +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 +PX4-PWM +AUXPIN + + + +0.001 + + +1 + + +1 + + +0.1 + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + +None +PX4-PWM +AUXPIN + + + +0.001 + + + +Disabled +PixhawkAUX1 +PixhawkAUX2 +PixhawkAUX3 +PixhawkAUX4 +PixhawkAUX5 +PixhawkAUX6 + + + + + + +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 + + + + + +Disabled +Enabled + + + +0 100 +% +percent + + +1000 2000 +ms +milliseconds + + +0 1000 +cm/s +centimeters per second + + +0 100 +% +percent + + + + +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 +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 +m +meters + + +0 500 +True + + + + +True + + +True +s +seconds + + +True +s +seconds + + +True +s +seconds + + + + + +Disabled +Enabled +EnableAndLearn + + + +True +True +degC +degrees Celsius + + +True +True +degC +degrees Celsius + + +True +True +degC +degrees Celsius + + +True +True + + + + + +Disable +Enable + + + +1 +m +meters + + + + + +Disabled +EnableVersion1 +EnableVersion2 + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +FlowHold + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS +FlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest +ModeFlowHold + + + +0 100 + + + +None +TakePhoto +ToggleVideo +ModeAcro +ModeAltHold +ModeAuto +ModeLoiter +ModeRTL +ModeCircle +ModeLand +ModeDrift +ModeSport +ModeAutoTune +ModePosHold +ModeBrake +ModeThrow +Flip +ModeStabilize +Disarm +ToggleMode +Arm-Land-RTL +ToggleSimpleMode +ToggleSuperSimpleMode +MotorLoadTest + + + +0:DisarmOnLowThrottle,1:ArmOnHighThrottle,2:UpgradeToLoiter,3:RTLStickCancel + + +0 5 +0.01 + + +0 5 +0.01 + + +0 1 +0.01 + + +0 1 +0.01 + + +0 1 +0.01 + + +0 100 + + + +ConstantThrust +LogReplay1 +LogReplay2 + + + + + + +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 + + + + + + +Disabled +Enabled + + + + +Servo with encoder + + + +0 10 +m/s +meters per second + + +0.01 10.0 + + +0.100 2.000 + + +0.000 2.000 + + +0.000 1.000 + + +0.000 0.400 + + +1.000 100.000 +Hz +hertz + + + + +20 2000 +50 +cm/s +centimeters per second + + +10 1000 +1 +cm +centimeters + + +10 1000 +50 +cm/s +centimeters per second + + +10 500 +10 +cm/s +centimeters per second + + +50 500 +10 +cm/s/s +centimeters per square second + + +50 500 +10 +cm/s/s +centimeters per square second + + + +Disable +Enable + + + + diff --git a/src/FirmwarePlugin/APM/APMResources.qrc b/src/FirmwarePlugin/APM/APMResources.qrc index c99292bd4..58536bab5 100644 --- a/src/FirmwarePlugin/APM/APMResources.qrc +++ b/src/FirmwarePlugin/APM/APMResources.qrc @@ -47,6 +47,7 @@ APMParameterFactMetaData.Copter.3.3.xml APMParameterFactMetaData.Copter.3.4.xml APMParameterFactMetaData.Copter.3.5.xml + APMParameterFactMetaData.Copter.3.6.xml APMParameterFactMetaData.Rover.3.0.xml APMParameterFactMetaData.Rover.3.2.xml APMParameterFactMetaData.Sub.3.4.xml diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 3df92033b..68a86e559 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -148,6 +148,14 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) remapV3_5["ARMING_VOLT_MIN"] = QStringLiteral("ARMING_MIN_VOLT"); remapV3_5["ARMING_VOLT2_MIN"] = QStringLiteral("ARMING_MIN_VOLT2"); + FirmwarePlugin::remapParamNameMap_t& remapV3_6 = _remapParamName[3][6]; + + remapV3_6["BATT_AMP_PERVLT"] = QStringLiteral("BATT_AMP_PERVOL"); + remapV3_6["BATT2_AMP_PERVLT"] = QStringLiteral("BATT2_AMP_PERVOL"); + remapV3_6["BATT_LOW_MAH"] = QStringLiteral("FS_BATT_MAH"); + remapV3_6["BATT_LOW_VOLT"] = QStringLiteral("FS_BATT_VOLTAGE"); + remapV3_6["BATT_FS_LOW_ACT"] = QStringLiteral("FS_BATT_ENABLE"); + _remapParamNameIntialized = true; } } -- 2.22.0