diff --git a/src/AutoPilotPlugins/APM/APMCameraComponent.qml b/src/AutoPilotPlugins/APM/APMCameraComponent.qml index 6ff44a5ceb300fdc94ac9b7ef8eca860cb4cbd13..0eafaade9402fde0f18b24d767affde9cdb32c1e 100644 --- a/src/AutoPilotPlugins/APM/APMCameraComponent.qml +++ b/src/AutoPilotPlugins/APM/APMCameraComponent.qml @@ -55,21 +55,23 @@ SetupPage { property Fact _mountAngMinPan: controller.getParameterFact(-1, "MNT_ANGMIN_PAN") property Fact _mountAngMaxPan: controller.getParameterFact(-1, "MNT_ANGMAX_PAN") - property Fact _rc5Function: controller.getParameterFact(-1, "RC5_FUNCTION") - property Fact _rc6Function: controller.getParameterFact(-1, "RC6_FUNCTION") - property Fact _rc7Function: controller.getParameterFact(-1, "RC7_FUNCTION") - property Fact _rc8Function: controller.getParameterFact(-1, "RC8_FUNCTION") - property Fact _rc9Function: controller.getParameterFact(-1, "RC9_FUNCTION") - property Fact _rc10Function: controller.getParameterFact(-1, "RC10_FUNCTION") - property Fact _rc11Function: controller.getParameterFact(-1, "RC11_FUNCTION") - property Fact _rc12Function: controller.getParameterFact(-1, "RC12_FUNCTION") - property Fact _rc13Function: controller.getParameterFact(-1, "RC13_FUNCTION") - property Fact _rc14Function: controller.getParameterFact(-1, "RC14_FUNCTION") + property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION") + property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION") + property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION") + property Fact _rc8Function: controller.getParameterFact(-1, "r.SERVO8_FUNCTION") + property Fact _rc9Function: controller.getParameterFact(-1, "r.SERVO9_FUNCTION") + property Fact _rc10Function: controller.getParameterFact(-1, "r.SERVO10_FUNCTION") + property Fact _rc11Function: controller.getParameterFact(-1, "r.SERVO11_FUNCTION") + property Fact _rc12Function: controller.getParameterFact(-1, "r.SERVO12_FUNCTION") + property Fact _rc13Function: controller.getParameterFact(-1, "r.SERVO13_FUNCTION") + property Fact _rc14Function: controller.getParameterFact(-1, "r.SERVO14_FUNCTION") property bool _tiltEnabled: false property bool _panEnabled: false property bool _rollEnabled: false + property bool _servoReverseIsBool: controller.parameterExists(-1, "RC5_REVERSED") + // Gimbal Settings not available on older firmware property bool _showGimbaLSettings: controller.parameterExists(-1, "MNT_DEFLT_MODE") @@ -95,10 +97,17 @@ SetupPage { loader.gimbalOutIndex = channel - 4 loader.servoPWMMinFact = controller.getParameterFact(-1, rcPrefix + "MIN") loader.servoPWMMaxFact = controller.getParameterFact(-1, rcPrefix + "MAX") - loader.servoReverseFact = controller.getParameterFact(-1, rcPrefix + "REV") + if (controller.parameterExists(-1, "RC5_REVERSED")) { + // Newer firmware parameter + loader.servoReverseFact = controller.getParameterFact(-1, rcPrefix + "REVERSED") + } else { + // Older firmware parameter + loader.servoReverseFact = controller.getParameterFact(-1, rcPrefix + "REV") + } + } - /// Gimbal output channels are stored in RC#_FUNCTION parameters. We need to loop through those + /// Gimbal output channels are stored in SERVO#_FUNCTION parameters. We need to loop through those /// to find them and setup the ui accordindly. function calcGimbalOutValues() { gimbalDirectionTiltLoader.gimbalOutIndex = 0 @@ -108,7 +117,7 @@ SetupPage { _panEnabled = false _rollEnabled = false for (var channel=_firstGimbalOutChannel; channel<=_lastGimbalOutChannel; channel++) { - var functionFact = controller.getParameterFact(-1, "RC" + channel + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + channel + "_FUNCTION") if (functionFact.value == _rcFunctionMountTilt) { _tiltEnabled = true setGimbalSettingsServoInfo(gimbalDirectionTiltLoader, channel) @@ -125,7 +134,7 @@ SetupPage { function setRCFunction(channel, rcFunction) { // First clear any previous settings for this function for (var index=_firstGimbalOutChannel; index<=_lastGimbalOutChannel; index++) { - var functionFact = controller.getParameterFact(-1, "RC" + index + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + index + "_FUNCTION") if (functionFact.value != _rcFunctionDisabled && functionFact.value == rcFunction) { functionFact.value = _rcFunctionDisabled } @@ -133,12 +142,12 @@ SetupPage { // Now set the function into the new channel if (channel != 0) { - var functionFact = controller.getParameterFact(-1, "RC" + channel + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + channel + "_FUNCTION") functionFact.value = rcFunction } } - // Whenever any RC#_FUNCTION parameters chagnes we need to go looking for gimbal output channels again + // Whenever any SERVO#_FUNCTION parameters changes we need to go looking for gimbal output channels again Connections { target: _rc5Function; onValueChanged: calcGimbalOutValues() } Connections { target: _rc6Function; onValueChanged: calcGimbalOutValues() } Connections { target: _rc7Function; onValueChanged: calcGimbalOutValues() } @@ -195,6 +204,7 @@ SetupPage { // property Fact servoPWMMinFact // property Fact servoPWMMaxFact // property Fact servoReverseFact + // property bool servoReverseIsBool // property int rcFunction Item { @@ -234,10 +244,12 @@ SetupPage { anchors.top: mountStabCheckBox.bottom anchors.right: parent.right text: qsTr("Servo reverse") - checkedValue: 1 - uncheckedValue: 0 + checkedValue: _servoReverseIsBool ? 1 : -1 + uncheckedValue: _servoReverseIsBool ? 0 : 1 fact: servoReverseFact enabled: directionEnabled + + property bool _servoReverseIsBool: servoReverseIsBool } QGCLabel { @@ -462,6 +474,7 @@ SetupPage { property Fact servoPWMMinFact: Fact { } property Fact servoPWMMaxFact: Fact { } property Fact servoReverseFact: Fact { } + property bool servoReverseIsBool: _servoReverseIsBool property int rcFunction: _rcFunctionMountTilt } @@ -479,6 +492,7 @@ SetupPage { property Fact servoPWMMinFact: Fact { } property Fact servoPWMMaxFact: Fact { } property Fact servoReverseFact: Fact { } + property bool servoReverseIsBool: _servoReverseIsBool property int rcFunction: _rcFunctionMountRoll } @@ -496,6 +510,7 @@ SetupPage { property Fact servoPWMMinFact: Fact { } property Fact servoPWMMaxFact: Fact { } property Fact servoReverseFact: Fact { } + property bool servoReverseIsBool: _servoReverseIsBool property int rcFunction: _rcFunctionMountPan } diff --git a/src/AutoPilotPlugins/APM/APMLightsComponent.qml b/src/AutoPilotPlugins/APM/APMLightsComponent.qml index 42c76d1a24b18e20b533fa56d6e49c234b83765c..aefb1d923e8767358f4ce7c70558516877584c02 100644 --- a/src/AutoPilotPlugins/APM/APMLightsComponent.qml +++ b/src/AutoPilotPlugins/APM/APMLightsComponent.qml @@ -32,16 +32,16 @@ SetupPage { QGCPalette { id: palette; colorGroupEnabled: true } - property Fact _rc5Function: controller.getParameterFact(-1, "RC5_FUNCTION") - property Fact _rc6Function: controller.getParameterFact(-1, "RC6_FUNCTION") - property Fact _rc7Function: controller.getParameterFact(-1, "RC7_FUNCTION") - property Fact _rc8Function: controller.getParameterFact(-1, "RC8_FUNCTION") - property Fact _rc9Function: controller.getParameterFact(-1, "RC9_FUNCTION") - property Fact _rc10Function: controller.getParameterFact(-1, "RC10_FUNCTION") - property Fact _rc11Function: controller.getParameterFact(-1, "RC11_FUNCTION") - property Fact _rc12Function: controller.getParameterFact(-1, "RC12_FUNCTION") - property Fact _rc13Function: controller.getParameterFact(-1, "RC13_FUNCTION") - property Fact _rc14Function: controller.getParameterFact(-1, "RC14_FUNCTION") + property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION") + property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION") + property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION") + property Fact _rc8Function: controller.getParameterFact(-1, "r.SERVO8_FUNCTION") + property Fact _rc9Function: controller.getParameterFact(-1, "r.SERVO9_FUNCTION") + property Fact _rc10Function: controller.getParameterFact(-1, "r.SERVO10_FUNCTION") + property Fact _rc11Function: controller.getParameterFact(-1, "r.SERVO11_FUNCTION") + property Fact _rc12Function: controller.getParameterFact(-1, "r.SERVO12_FUNCTION") + property Fact _rc13Function: controller.getParameterFact(-1, "r.SERVO13_FUNCTION") + property Fact _rc14Function: controller.getParameterFact(-1, "r.SERVO14_FUNCTION") readonly property real _margins: ScreenTools.defaultFontPixelHeight readonly property int _rcFunctionDisabled: 0 @@ -54,13 +54,13 @@ SetupPage { calcLightOutValues() } - /// Light output channels are stored in RC#_FUNCTION parameters. We need to loop through those + /// Light output channels are stored in SERVO#_FUNCTION parameters. We need to loop through those /// to find them and setup the ui accordindly. function calcLightOutValues() { lightsLoader.lights1OutIndex = 0 lightsLoader.lights2OutIndex = 0 for (var channel=_firstLightsOutChannel; channel<=_lastLightsOutChannel; channel++) { - var functionFact = controller.getParameterFact(-1, "RC" + channel + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + channel + "_FUNCTION") if (functionFact.value == _rcFunctionRCIN9) { lightsLoader.lights1OutIndex = channel - 4 } else if (functionFact.value == _rcFunctionRCIN10) { @@ -72,7 +72,7 @@ SetupPage { function setRCFunction(channel, rcFunction) { // First clear any previous settings for this function for (var index=_firstLightsOutChannel; index<=_lastLightsOutChannel; index++) { - var functionFact = controller.getParameterFact(-1, "RC" + index + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + index + "_FUNCTION") if (functionFact.value != _rcFunctionDisabled && functionFact.value == rcFunction) { functionFact.value = _rcFunctionDisabled } @@ -80,12 +80,12 @@ SetupPage { // Now set the function into the new channel if (channel != 0) { - var functionFact = controller.getParameterFact(-1, "RC" + channel + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + channel + "_FUNCTION") functionFact.value = rcFunction } } - // Whenever any RC#_FUNCTION parameters chagnes we need to go looking for light output channels again + // Whenever any SERVO#_FUNCTION parameters chagnes we need to go looking for light output channels again Connections { target: _rc5Function; onValueChanged: calcLightOutValues() } Connections { target: _rc6Function; onValueChanged: calcLightOutValues() } Connections { target: _rc7Function; onValueChanged: calcLightOutValues() } diff --git a/src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml b/src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml index 3eb129d28a14139ace27fd6c94346a00fa525e46..7712df99c7169cfafd95b0a2fed9107b075cda50 100644 --- a/src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml +++ b/src/AutoPilotPlugins/APM/APMLightsComponentSummary.qml @@ -14,16 +14,16 @@ FactPanel { QGCPalette { id: qgcPal; colorGroupEnabled: enabled } FactPanelController { id: controller; factPanel: panel } - property Fact _rc5Function: controller.getParameterFact(-1, "RC5_FUNCTION") - property Fact _rc6Function: controller.getParameterFact(-1, "RC6_FUNCTION") - property Fact _rc7Function: controller.getParameterFact(-1, "RC7_FUNCTION") - property Fact _rc8Function: controller.getParameterFact(-1, "RC8_FUNCTION") - property Fact _rc9Function: controller.getParameterFact(-1, "RC9_FUNCTION") - property Fact _rc10Function: controller.getParameterFact(-1, "RC10_FUNCTION") - property Fact _rc11Function: controller.getParameterFact(-1, "RC11_FUNCTION") - property Fact _rc12Function: controller.getParameterFact(-1, "RC12_FUNCTION") - property Fact _rc13Function: controller.getParameterFact(-1, "RC13_FUNCTION") - property Fact _rc14Function: controller.getParameterFact(-1, "RC14_FUNCTION") + property Fact _rc5Function: controller.getParameterFact(-1, "r.SERVO5_FUNCTION") + property Fact _rc6Function: controller.getParameterFact(-1, "r.SERVO6_FUNCTION") + property Fact _rc7Function: controller.getParameterFact(-1, "r.SERVO7_FUNCTION") + property Fact _rc8Function: controller.getParameterFact(-1, "r.SERVO8_FUNCTION") + property Fact _rc9Function: controller.getParameterFact(-1, "r.SERVO9_FUNCTION") + property Fact _rc10Function: controller.getParameterFact(-1, "r.SERVO10_FUNCTION") + property Fact _rc11Function: controller.getParameterFact(-1, "r.SERVO11_FUNCTION") + property Fact _rc12Function: controller.getParameterFact(-1, "r.SERVO12_FUNCTION") + property Fact _rc13Function: controller.getParameterFact(-1, "r.SERVO13_FUNCTION") + property Fact _rc14Function: controller.getParameterFact(-1, "r.SERVO14_FUNCTION") readonly property int _rcFunctionRCIN9: 59 readonly property int _rcFunctionRCIN10: 60 @@ -34,13 +34,13 @@ FactPanel { calcLightOutValues() } - /// Light output channels are stored in RC#_FUNCTION parameters. We need to loop through those + /// Light output channels are stored in SERVO#_FUNCTION parameters. We need to loop through those /// to find them and setup the ui accordindly. function calcLightOutValues() { lightsLoader.lights1OutIndex = 0 lightsLoader.lights2OutIndex = 0 for (var channel=_firstLightsOutChannel; channel<=_lastLightsOutChannel; channel++) { - var functionFact = controller.getParameterFact(-1, "RC" + channel + "_FUNCTION") + var functionFact = controller.getParameterFact(-1, "r.SERVO" + channel + "_FUNCTION") if (functionFact.value == _rcFunctionRCIN9) { lightsLoader.lights1OutIndex = channel - 4 } else if (functionFact.value == _rcFunctionRCIN10) { @@ -49,7 +49,7 @@ FactPanel { } } - // Whenever any RC#_FUNCTION parameters chagnes we need to go looking for light output channels again + // Whenever any SERVO#_FUNCTION parameters chagnes we need to go looking for light output channels again Connections { target: _rc5Function; onValueChanged: calcLightOutValues() } Connections { target: _rc6Function; onValueChanged: calcLightOutValues() } Connections { target: _rc7Function; onValueChanged: calcLightOutValues() } diff --git a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml index 2bb09e601575cd4a0efb35ac1c86024b50a03def..4547fbd3cf18c4be1efb3527e6c98cdf448d1139 100644 --- a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml +++ b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml @@ -84,7 +84,7 @@ SetupPage { calcAutoTuneChannel() } - /// The AutoTune switch is stored in one of the RC#_FUNCTION parameters. We need to loop through those + /// The AutoTune switch is stored in one of the CH#_OPT parameters. We need to loop through those /// to find them and setup the ui accordindly. function calcAutoTuneChannel() { _autoTuneSwitchChannelIndex = 0 diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.cc b/src/AutoPilotPlugins/Common/RadioComponentController.cc index 2af400c22065ac4e9c7f449742be047ce9e816da..f64f29517c5a87ad5b7933c916e2434f672eb7d5 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.cc +++ b/src/AutoPilotPlugins/Common/RadioComponentController.cc @@ -18,6 +18,7 @@ #include QGC_LOGGING_CATEGORY(RadioComponentControllerLog, "RadioComponentControllerLog") +QGC_LOGGING_CATEGORY(RadioComponentControllerVerboseLog, "RadioComponentControllerVerboseLog") #ifdef UNITTEST_BUILD // Nasty hack to expose controller to unit test code @@ -26,66 +27,78 @@ RadioComponentController* RadioComponentController::_unitTestController = NULL; const int RadioComponentController::_updateInterval = 150; ///< Interval for timer which updates radio channel widgets const int RadioComponentController::_rcCalPWMCenterPoint = ((RadioComponentController::_rcCalPWMValidMaxValue - RadioComponentController::_rcCalPWMValidMinValue) / 2.0f) + RadioComponentController::_rcCalPWMValidMinValue; -// FIXME: Double check these mins againt 150% throws -const int RadioComponentController::_rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value -const int RadioComponentController::_rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value -const int RadioComponentController::_rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set -const int RadioComponentController::_rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set -const int RadioComponentController::_rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered -const int RadioComponentController::_rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement -const int RadioComponentController::_rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement -const int RadioComponentController::_rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min +const int RadioComponentController::_rcCalPWMValidMinValue = 1300; ///< Largest valid minimum PWM Min range value +const int RadioComponentController::_rcCalPWMValidMaxValue = 1700; ///< Smallest valid maximum PWM Max range value +const int RadioComponentController::_rcCalPWMDefaultMinValue = 1000; ///< Default value for Min if not set +const int RadioComponentController::_rcCalPWMDefaultMaxValue = 2000; ///< Default value for Max if not set +const int RadioComponentController::_rcCalRoughCenterDelta = 50; ///< Delta around center point which is considered to be roughly centered +const int RadioComponentController::_rcCalMoveDelta = 300; ///< Amount of delta past center which is considered stick movement +const int RadioComponentController::_rcCalSettleDelta = 20; ///< Amount of delta which is considered no stick movement +const int RadioComponentController::_rcCalMinDelta = 100; ///< Amount of delta allowed around min value to consider channel at min const int RadioComponentController::_stickDetectSettleMSecs = 500; -const char* RadioComponentController::_imageFilePrefix = "calibration/"; +const char* RadioComponentController::_imageFilePrefix = "calibration/"; const char* RadioComponentController::_imageFileMode1Dir = "mode1/"; const char* RadioComponentController::_imageFileMode2Dir = "mode2/"; -const char* RadioComponentController::_imageCenter = "radioCenter.png"; -const char* RadioComponentController::_imageHome = "radioHome.png"; -const char* RadioComponentController::_imageThrottleUp = "radioThrottleUp.png"; +const char* RadioComponentController::_imageCenter = "radioCenter.png"; +const char* RadioComponentController::_imageHome = "radioHome.png"; +const char* RadioComponentController::_imageThrottleUp = "radioThrottleUp.png"; const char* RadioComponentController::_imageThrottleDown = "radioThrottleDown.png"; -const char* RadioComponentController::_imageYawLeft = "radioYawLeft.png"; -const char* RadioComponentController::_imageYawRight = "radioYawRight.png"; -const char* RadioComponentController::_imageRollLeft = "radioRollLeft.png"; -const char* RadioComponentController::_imageRollRight = "radioRollRight.png"; -const char* RadioComponentController::_imagePitchUp = "radioPitchUp.png"; -const char* RadioComponentController::_imagePitchDown = "radioPitchDown.png"; +const char* RadioComponentController::_imageYawLeft = "radioYawLeft.png"; +const char* RadioComponentController::_imageYawRight = "radioYawRight.png"; +const char* RadioComponentController::_imageRollLeft = "radioRollLeft.png"; +const char* RadioComponentController::_imageRollRight = "radioRollRight.png"; +const char* RadioComponentController::_imagePitchUp = "radioPitchUp.png"; +const char* RadioComponentController::_imagePitchDown = "radioPitchDown.png"; const char* RadioComponentController::_imageSwitchMinMax = "radioSwitchMinMax.png"; -const char* RadioComponentController::_settingsGroup = "RadioCalibration"; +const char* RadioComponentController::_settingsGroup = "RadioCalibration"; const char* RadioComponentController::_settingsKeyTransmitterMode = "TransmitterMode"; +const char* RadioComponentController::_px4RevParamFormat = "RC%1_REV"; +const char* RadioComponentController::_apmNewRevParamFormat = "RC%1_REVERSED"; + const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoPX4[RadioComponentController::rcCalFunctionMax] = { - { "RC_MAP_ROLL" }, - { "RC_MAP_PITCH" }, - { "RC_MAP_YAW" }, - { "RC_MAP_THROTTLE" } +{ "RC_MAP_ROLL" }, +{ "RC_MAP_PITCH" }, +{ "RC_MAP_YAW" }, +{ "RC_MAP_THROTTLE" } }; const struct RadioComponentController::FunctionInfo RadioComponentController::_rgFunctionInfoAPM[RadioComponentController::rcCalFunctionMax] = { - { "RCMAP_ROLL" }, - { "RCMAP_PITCH" }, - { "RCMAP_YAW" }, - { "RCMAP_THROTTLE" } +{ "RCMAP_ROLL" }, +{ "RCMAP_PITCH" }, +{ "RCMAP_YAW" }, +{ "RCMAP_THROTTLE" } }; -RadioComponentController::RadioComponentController(void) : - _currentStep(-1), - _transmitterMode(2), - _chanCount(0), - _rcCalState(rcCalStateChannelWait), - _unitTestMode(false), - _statusText(NULL), - _cancelButton(NULL), - _nextButton(NULL), - _skipButton(NULL) +RadioComponentController::RadioComponentController(void) + : _currentStep(-1) + , _transmitterMode(2) + , _chanCount(0) + , _rcCalState(rcCalStateChannelWait) + , _unitTestMode(false) + , _statusText(NULL) + , _cancelButton(NULL) + , _nextButton(NULL) + , _skipButton(NULL) { #ifdef UNITTEST_BUILD // Nasty hack to expose controller to unit test code _unitTestController = this; #endif + if (parameterExists(FactSystem::defaultComponentId, QStringLiteral("RC1_REVERSED"))) { + // Newer ardupilot firmwares have a different reverse param naming scheme and value scheme + _revParamFormat = _apmNewRevParamFormat; + _revParamIsBool = true; // param value is boolean 0/1 for reversed or not + } else { + // Older ardupilot firmwares share the same naming convention as PX4 + _revParamFormat = _px4RevParamFormat; + _revParamIsBool = false; // paeram value if -1 indicates reversed + } + connect(_vehicle, &Vehicle::rcChannelsChanged, this, &RadioComponentController::_rcChannelsChanged); _loadSettings(); @@ -226,7 +239,7 @@ void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValue int channelValue = pwmValues[channel]; if (channelValue != -1) { - qCDebug(RadioComponentControllerLog) << "Raw value" << channel << channelValue; + qCDebug(RadioComponentControllerVerboseLog) << "Raw value" << channel << channelValue; _rcRawValue[channel] = channelValue; emit channelRCValueChanged(channel, channelValue); @@ -259,9 +272,12 @@ void RadioComponentController::_rcChannelsChanged(int channelCount, int pwmValue } } else { const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - Q_ASSERT(state); - if (state->rcInputFn) { - (this->*state->rcInputFn)(state->function, channel, channelValue); + if (state) { + if (state->rcInputFn) { + (this->*state->rcInputFn)(state->function, channel, channelValue); + } + } else { + qWarning() << "Internal error: NULL _getStateMachineEntry return"; } } } @@ -283,20 +299,27 @@ void RadioComponentController::nextButtonClicked(void) _startCalibration(); } else { const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - Q_ASSERT(state); - Q_ASSERT(state->nextFn); - (this->*state->nextFn)(); + if (state && state->nextFn) { + (this->*state->nextFn)(); + } else { + qWarning() << "Internal error: NULL _getStateMachineEntry return"; + } } } void RadioComponentController::skipButtonClicked(void) { - Q_ASSERT(_currentStep != -1); + if (_currentStep == -1) { + qWarning() << "Internal error: _currentStep == -1"; + return; + } const stateMachineEntry* state = _getStateMachineEntry(_currentStep); - Q_ASSERT(state); - Q_ASSERT(state->skipFn); - (this->*state->skipFn)(); + if (state && state->skipFn) { + (this->*state->skipFn)(); + } else { + qWarning() << "Internal error: NULL _getStateMachineEntry return"; + } } void RadioComponentController::cancelButtonClicked(void) @@ -581,9 +604,6 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) QString minTpl("RC%1_MIN"); QString maxTpl("RC%1_MAX"); QString trimTpl("RC%1_TRIM"); - QString revTpl("RC%1_REV"); - - bool convertOk; for (int i = 0; i < _chanMax(); ++i) { struct ChannelInfo* info = &_rgChannelInfo[i]; @@ -601,29 +621,20 @@ void RadioComponentController::_setInternalCalibrationValuesFromParameters(void) Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, trimTpl.arg(i+1)); if (paramFact) { - info->rcTrim = paramFact->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + info->rcTrim = paramFact->rawValue().toInt(); } paramFact = getParameterFact(FactSystem::defaultComponentId, minTpl.arg(i+1)); if (paramFact) { - info->rcMin = paramFact->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + info->rcMin = paramFact->rawValue().toInt(); } paramFact = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1)); if (paramFact) { - info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + info->rcMax = getParameterFact(FactSystem::defaultComponentId, maxTpl.arg(i+1))->rawValue().toInt(); } - paramFact = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(i+1)); - if (paramFact) { - float floatReversed = paramFact->rawValue().toFloat(&convertOk); - Q_ASSERT(convertOk); - Q_ASSERT(floatReversed == 1.0f || floatReversed == -1.0f); - info->reversed = floatReversed == -1.0f; - } + info->reversed = _channelReversedParamValue(i); } for (int i=0; irawValue().toInt(&convertOk); - Q_ASSERT(convertOk); + paramChannel = paramFact->rawValue().toInt(); if (paramChannel != 0) { _rgFunctionChannelMapping[i] = paramChannel - 1; @@ -668,21 +678,21 @@ void RadioComponentController::_validateCalibration(void) info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); } else { switch (_rgChannelInfo[chan].function) { - case rcCalFunctionThrottle: - case rcCalFunctionYaw: - case rcCalFunctionRoll: - case rcCalFunctionPitch: - // Make sure trim is within min/max - if (info->rcTrim < info->rcMin) { - info->rcTrim = info->rcMin; - } else if (info->rcTrim > info->rcMax) { - info->rcTrim = info->rcMax; - } - break; - default: - // Non-attitude control channels have calculated trim - info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); - break; + case rcCalFunctionThrottle: + case rcCalFunctionYaw: + case rcCalFunctionRoll: + case rcCalFunctionPitch: + // Make sure trim is within min/max + if (info->rcTrim < info->rcMin) { + info->rcTrim = info->rcMin; + } else if (info->rcTrim > info->rcMax) { + info->rcTrim = info->rcMax; + } + break; + default: + // Non-attitude control channels have calculated trim + info->rcTrim = info->rcMin + ((info->rcMax - info->rcMin) / 2); + break; } } @@ -717,7 +727,6 @@ void RadioComponentController::_writeCalibration(void) QString minTpl("RC%1_MIN"); QString maxTpl("RC%1_MAX"); QString trimTpl("RC%1_TRIM"); - QString revTpl("RC%1_REV"); // Note that the rc parameters are all float, so you must cast to float in order to get the right QVariant for (int chan = 0; chan<_chanMax(); chan++) { @@ -746,16 +755,13 @@ void RadioComponentController::_writeCalibration(void) // may affect channel reversing so we can't automatically determine it. This is ok for PX4 given how it uses mixers, but not for ArduPilot. if (_vehicle->px4Firmware() || _vehicle->multiRotor()) { // APM multi-rotor has a backwards interpretation of "reversed" on the Pitch control. So be careful. - float reversedParamValue; + bool reversed; if (_px4Vehicle() || info->function != rcCalFunctionPitch) { - reversedParamValue = info->reversed ? -1.0f : 1.0f; + reversed = info->reversed; } else { - reversedParamValue = info->reversed ? 1.0f : -1.0f; - } - paramFact = getParameterFact(FactSystem::defaultComponentId, revTpl.arg(oneBasedChannel)); - if (paramFact) { - paramFact->setRawValue(reversedParamValue); + reversed = !info->reversed; } + _setChannelReversedParamValue(chan, reversed); } } @@ -797,7 +803,10 @@ void RadioComponentController::_writeCalibration(void) /// @brief Starts the calibration process void RadioComponentController::_startCalibration(void) { - Q_ASSERT(_chanCount >= _chanMinimum); + if (_chanCount < _chanMinimum) { + qWarning() << "Call to RadioComponentController::_startCalibration with _chanCount < _chanMinimum"; + return; + } _resetInternalCalibrationValues(); @@ -853,7 +862,7 @@ void RadioComponentController::_rcCalSave(void) _statusText->setProperty("text", "The current calibration settings are now displayed for each channel on screen.\n\n" - "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."); + "Click the Next button to upload calibration to board. Click Cancel if you don't want to save these values."); _nextButton->setEnabled(true); _skipButton->setEnabled(false); @@ -895,7 +904,8 @@ void RadioComponentController::_setHelpImage(const char* imageFile) } else if (_transmitterMode == 2) { file += _imageFileMode2Dir; } else { - Q_ASSERT(false); + qWarning() << "Internal error: Bad _transmitterMode value"; + return; } file += imageFile; @@ -1045,3 +1055,34 @@ int RadioComponentController::_chanMax(void) const { return _px4Vehicle() ? _chanMaxPX4 : _chanMaxAPM; } + +bool RadioComponentController::_channelReversedParamValue(int channel) +{ + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _revParamFormat.arg(channel+1)); + if (paramFact) { + if (_revParamIsBool) { + return paramFact->rawValue().toBool(); + } else { + bool convertOk; + float floatReversed = paramFact->rawValue().toFloat(&convertOk); + if (!convertOk) { + floatReversed = 1.0f; + } + return floatReversed == -1.0f; + } + } + + return false; +} + +void RadioComponentController::_setChannelReversedParamValue(int channel, bool reversed) +{ + Fact* paramFact = getParameterFact(FactSystem::defaultComponentId, _revParamFormat.arg(channel+1)); + if (paramFact) { + if (_revParamIsBool) { + paramFact->setRawValue(reversed); + } else { + paramFact->setRawValue(reversed ? -1.0f : 1.0f); + } + } +} diff --git a/src/AutoPilotPlugins/Common/RadioComponentController.h b/src/AutoPilotPlugins/Common/RadioComponentController.h index 2b6062b7c6c9ee2690c568b28586e6e45dd85375..57f0ff02c403a5ecad54cea36ea82314b7b31739 100644 --- a/src/AutoPilotPlugins/Common/RadioComponentController.h +++ b/src/AutoPilotPlugins/Common/RadioComponentController.h @@ -24,6 +24,7 @@ #include "AutoPilotPlugin.h" Q_DECLARE_LOGGING_CATEGORY(RadioComponentControllerLog) +Q_DECLARE_LOGGING_CATEGORY(RadioComponentControllerVerboseLog) class RadioConfigest; @@ -232,7 +233,10 @@ private: void _signalAllAttiudeValueChanges(void); int _chanMax(void) const; - + + bool _channelReversedParamValue(int channel); + void _setChannelReversedParamValue(int channel, bool reversed); + // @brief Called by unit test code to set the mode to unit testing void _setUnitTestMode(void){ _unitTestMode = true; } @@ -259,20 +263,20 @@ private: int _transmitterMode; ///< 1: transmitter is mode 1, 2: transmitted is mode 2 static const int _updateInterval; ///< Interval for ui update timer - + static const struct FunctionInfo _rgFunctionInfoAPM[rcCalFunctionMax]; ///< Information associated with each function, PX4 firmware static const struct FunctionInfo _rgFunctionInfoPX4[rcCalFunctionMax]; ///< Information associated with each function, APM firmware int _rgFunctionChannelMapping[rcCalFunctionMax]; ///< Maps from rcCalFunctions to channel index. _chanMax indicates channel not set for this function. static const int _attitudeControls = 5; - + int _chanCount; ///< Number of actual rc channels available static const int _chanMaxPX4 = 18; ///< Maximum number of supported rc channels, PX4 Firmware static const int _chanMaxAPM = 14; ///< Maximum number of supported rc channels, APM firmware static const int _chanMaxAny = 18; ///< Maximum number of support rc channels by this implementation static const int _chanMinimum = 5; ///< Minimum numner of channels required to run - + struct ChannelInfo _rgChannelInfo[_chanMaxAny]; ///< Information associated with each rc channel QList _apmPossibleMissingRCChannelParams; ///< List of possible missing RC*_* params for APM stack @@ -292,7 +296,12 @@ private: static const int _rcCalMoveDelta; static const int _rcCalSettleDelta; static const int _rcCalMinDelta; - + + static const char* _px4RevParamFormat; + static const char* _apmNewRevParamFormat; + QString _revParamFormat; + bool _revParamIsBool; + int _rcValueSave[_chanMaxAny]; ///< Saved values prior to detecting channel movement int _rcRawValue[_chanMaxAny]; ///< Current set of raw channel values diff --git a/src/FactSystem/FactControls/FactCheckBox.qml b/src/FactSystem/FactControls/FactCheckBox.qml index 5dc7788a42a69355f359fa70f58eeb2252bbc230..06d0eec0ff0ed3a01d20739ac82a53dd039c3231 100644 --- a/src/FactSystem/FactControls/FactCheckBox.qml +++ b/src/FactSystem/FactControls/FactCheckBox.qml @@ -11,12 +11,9 @@ QGCCheckBox { property variant checkedValue: 1 property variant uncheckedValue: 0 - partiallyCheckedEnabled: fact ? fact.value !== checkedValue && fact.value !== uncheckedValue : false - checkedState: fact ? fact.value === checkedValue ? Qt.Checked : (fact.value === uncheckedValue ? Qt.Unchecked : Qt.PartiallyChecked) : false + checkedState: fact ? (fact.value === checkedValue ? Qt.Checked : Qt.Unchecked) : Qt.Unchecked text: qsTr("Label") - onClicked: { - fact.value = checked ? checkedValue : uncheckedValue - } + onClicked: fact.value = checked ? checkedValue : uncheckedValue } diff --git a/src/FactSystem/FactControls/FactPanelController.cc b/src/FactSystem/FactControls/FactPanelController.cc index 7e77599333d5dd7aa33926bacb76b14750b8bb95..b7059d7768c8f1b6c8757a78b24b2ea3c5442172 100644 --- a/src/FactSystem/FactControls/FactPanelController.cc +++ b/src/FactSystem/FactControls/FactPanelController.cc @@ -127,8 +127,9 @@ Fact* FactPanelController::getParameterFact(int componentId, const QString& name QQmlEngine::setObjectOwnership(fact, QQmlEngine::CppOwnership); return fact; } else { - if(reportMissing) + if (reportMissing) { _reportMissingParameter(componentId, name); + } return NULL; } } diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc index 54855385b9128955c8e4ec2f24536ce23192dcde..1a79754905c1540ff7ff3de65ff16dbdb3b6cbee 100644 --- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc @@ -735,6 +735,9 @@ void APMFirmwarePlugin::_artooSocketError(QAbstractSocket::SocketError socketErr QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) { + int majorVersion = vehicle->firmwareMajorVersion(); + int minorVersion = vehicle->firmwareMinorVersion(); + switch (vehicle->vehicleType()) { case MAV_TYPE_QUADROTOR: case MAV_TYPE_HEXAROTOR: @@ -742,22 +745,57 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle) case MAV_TYPE_TRICOPTER: case MAV_TYPE_COAXIAL: case MAV_TYPE_HELICOPTER: - if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) { + if (majorVersion < 3) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); - } else if (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() == 4) { - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"); - } else { - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); + } else if (majorVersion == 3) { + switch (minorVersion) { + case 3: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); + case 4: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.4.xml"); + case 5: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); + default: + if (minorVersion < 3) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.3.xml"); + } + } } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml"); case MAV_TYPE_FIXED_WING: - if (vehicle->firmwareMajorVersion() < 3 || (vehicle->firmwareMajorVersion() == 3 && vehicle->firmwareMinorVersion() <= 3)) { + if (majorVersion < 3) { return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); - } else { - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); + } else if (majorVersion == 3) { + switch (minorVersion) { + case 3: + case 4: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); + case 5: + case 6: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.5.xml"); + case 7: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.7.xml"); + default: + if (minorVersion < 3) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.3.xml"); + } + } } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml"); case MAV_TYPE_GROUND_ROVER: case MAV_TYPE_SURFACE_BOAT: - return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); + if (majorVersion < 3) { + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); + } else if (majorVersion == 3) { + switch (minorVersion) { + case 0: + case 1: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.0.xml"); + default: + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); + } + } + return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml"); case MAV_TYPE_SUBMARINE: return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Sub.3.4.xml"); default: diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml index 1734b74b8e62efea77446ab4727cd129ed5972dd..91f87f90fda231c636912b9c077dc5fae61f4993 100644 --- a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.5.xml @@ -128,11 +128,6 @@ L1Controller - -0 1 -0.1 -Percent - Automatic @@ -1253,6 +1248,7 @@ Avoidance PrecLoiter Object Avoidance +ArmDisarm @@ -1293,6 +1289,7 @@ Avoidance PrecLoiter Object Avoidance +ArmDisarm @@ -1333,6 +1330,7 @@ Avoidance PrecLoiter Object Avoidance +ArmDisarm @@ -1373,6 +1371,7 @@ Avoidance PrecLoiter Object Avoidance +ArmDisarm @@ -1413,6 +1412,7 @@ Avoidance PrecLoiter Object Avoidance +ArmDisarm @@ -1453,20 +1453,7 @@ Avoidance PrecLoiter Object Avoidance - - - -0:All,1:Baro,2:Compass,3:GPS,4:INS,5:Parameters+Rangefinder,6:RC,7:Voltage - -Disabled -Enabled -Skip Baro -Skip Compass -Skip GPS -Skip INS -Skip Params/Rangefinder -Skip RC -Skip Voltage +ArmDisarm @@ -2151,1002 +2138,799 @@ gravities - - + + -1200 -2400 -4800 -9600 -19200 -38400 -57600 -111100 -115200 -500000 -921600 -1500000 +Disabled +Enabled - - -MAVlink1 -MAVLink2 - + +1 100 - - -None -MAVLink1 -MAVLink2 -Frsky D -Frsky SPort -GPS -Alexmos Gimbal Serial -SToRM32 Gimbal Serial -Lidar -FrSky SPort Passthrough (OpenTX) -Lidar360 -Aerotenna uLanding -Pozyx Beacon - + +1 100000 - - -1200 -2400 -4800 -9600 -19200 -38400 -57600 -111100 -115200 -500000 -921600 -1500000 - + +-1 16777215 - + -None -MAVLink1 -MAVLink2 -Frsky D -Frsky SPort -GPS -Alexmos Gimbal Serial -SToRM32 Gimbal Serial -Lidar -FrSky SPort Passthrough (OpenTX) -Lidar360 -Aerotenna uLanding -Pozyx Beacon +NoInfo +Light +Small +Large +HighVortexlarge +Heavy +HighlyManuv +Rotocraft +RESERVED +Glider +LightAir +Parachute +UltraLight +RESERVED +UAV +Space +RESERVED +EmergencySurface +ServiceSurface +PointObstacle - + -1200 -2400 -4800 -9600 -19200 -38400 -57600 -111100 -115200 -500000 -921600 -1500000 +NO_DATA +L15W23 +L25W28P5 +L25W34 +L35W33 +L35W38 +L45W39P5 +L45W45 +L55W45 +L55W52 +L65W59P5 +L65W67 +L75W72P5 +L75W80 +L85W80 +L85W90 - + -None -MAVLink1 -MAVLink2 -Frsky D -Frsky SPort -GPS -Alexmos Gimbal Serial -SToRM32 Gimbal Serial -Lidar -FrSky SPort Passthrough (OpenTX) -Lidar360 -Aerotenna uLanding -Pozyx Beacon +NoData +Left2m +Left4m +Left6m +Center +Right2m +Right4m +Right6m - + -1200 -2400 -4800 -9600 -19200 -38400 -57600 -111100 -115200 -500000 -921600 -1500000 +NO_DATA +AppliedBySensor - + -None -MAVLink1 -MAVLink2 -Frsky D -Frsky SPort -GPS -Alexmos Gimbal Serial -SToRM32 Gimbal Serial -Lidar -FrSky SPort Passthrough (OpenTX) -Lidar360 -Aerotenna uLanding -Pozyx Beacon +Disabled +Rx-Only +Tx-Only +Rx and Tx Enabled - - -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 -Lidar -FrSky SPort Passthrough (OpenTX) -Lidar360 -Aerotenna uLanding -Pozyx Beacon - + - - -1200 -2400 -4800 -9600 -19200 -38400 -57600 -111100 -115200 -500000 -921600 -1500000 - + - - - -True -True -1 -pascals + - -True -True -1 -degrees celsius + - -0.1 + + + + + + + meters - - -FirstBaro -2ndBaro -3rdBaro - + +meters - - -Disabled -Bus0 - + +millibar + + + + + + + + + + + + + + +seconds - - + + +0.0 1.0 +.01 + + -None -AUTO -uBlox -MTK -MTK19 -NMEA -SiRF -HIL -SwiftNav -PX4-UAVCAN -SBF -GSOF -QURT -ERB -MAV -NOVA +Disabled +Enabled -True - + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + None -AUTO -uBlox -MTK -MTK19 -NMEA -SiRF -HIL -SwiftNav -PX4-UAVCAN -SBF -GSOF -QURT -ERB -MAV -NOVA +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 -True - - -Portable -Stationary -Pedestrian -Automotive -Sea -Airborne1G -Airborne2G -Airborne4G - + +0.001 0.5 +.01 - + +0 10 +1 + + Disabled -Enabled +Enable EKF2 +Enable EKF3 - + + + -Any -FloatRTK -IntegerRTK +Disabled +THR_MIN PWM when disarmed +0 PWM when disarmed -True - + +0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration -Disabled -Enabled -NoChange +None +All +Barometer +Compass +GPS Lock +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Failsafe +Board voltage +Battery Level +Airspeed +LoggingAvailable +Hardware safety switch +GPS configuration - --100 90 -Degrees + +0.25 3.0 +m/s/s - + +0.1 +Volts + + +0.1 +Volts + + + + -send to first GPS -send to 2nd GPS -send to all +None +I2C-MS4525D0 +Analog +I2C-MS5525 - + -None -All -External only +Use +Don't Use - + +0.1 + + +0.1 + + + + + + + + -Disabled -log every sample -log every 5 samples +Disable +Enable -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 +Bus0 +Bus1 - + + + +500 18000 +100 +Centi-Degrees/Sec + + +0 72000 -Do not save config -Save config -Save only when needed +Disabled +Slow +Medium +Fast +1000 +Centi-Degrees/Sec/Sec - -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 +Disabled +Enabled - + +0 180000 -Disables automatic configuration -Enable automatic configuration +Disabled +Slow +Medium +Fast +1000 +Centi-Degrees/Sec/Sec - + +0 180000 -10Hz -8Hz -5Hz +Disabled +Slow +Medium +Fast -milliseconds +1000 +Centi-Degrees/Sec/Sec - + -10Hz -8Hz -5Hz +Disabled +Enabled -milliseconds - -m + +3.000 12.000 - -m + +3.000 12.000 - -m + +3.000 6.000 - -m + +0.5 10.0 - -m + +0.08 0.30 +0.005 - -m + +0.01 0.5 +0.01 - - - - -Servo -Relay - + +0 1 +0.01 +Percent - -0 50 -seconds + +0.0 0.02 +0.001 - -1000 2000 -pwm + +1 100 +1 +Hz - -1000 2000 -pwm + +0.08 0.30 +0.005 - -0 1000 -meters + +0.01 0.5 +0.01 - - -Low -High - + +0 1 +0.01 +Percent - -0 10000 -milliseconds + +0.0 0.02 +0.001 - -0 180 -Degrees + +1 100 +1 +Hz - - -Disabled -PX4 AUX1 -PX4 AUX2 -PX4 AUX3 -PX4 AUX4(fast capture) -PX4 AUX5 -PX4 AUX6 - + +0.10 0.50 +0.005 - - -TriggerLow -TriggerHigh - + +0.010 0.05 +0.01 - - - - -Disabled -THR_MIN PWM when disarmed -0 PWM when disarmed - + +0 1 +0.01 +Percent - -0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration - -None -All -Barometer -Compass -GPS Lock -INS(INertial Sensors - accels & gyros) -Parameters(unused) -RC Failsafe -Board voltage -Battery Level -Airspeed -LoggingAvailable -Hardware safety switch -GPS configuration - + +0.000 0.02 +0.001 - -0.25 3.0 -m/s/s + +1 100 +1 +Hz - -0.1 -Volts + +0.1 0.25 - -0.1 -Volts + +0.5 0.9 - - - + +0.5 0.9 + + -Disabled -APM2 A9 pin -APM1 relay -Pixhawk AUXOUT1 -Pixhawk AUXOUT2 -Pixhawk AUXOUT3 -Pixhawk AUXOUT4 -Pixhawk AUXOUT5 -Pixhawk AUXOUT6 -PX4 FMU Relay1 -PX4 FMU Relay2 -PX4IO Relay1 -PX4IO Relay2 -PX4IO ACC1 -PX4IO ACC2 +Disabled 1 - - -Disabled -APM2 A9 pin -APM1 relay -Pixhawk AUXOUT1 -Pixhawk AUXOUT2 -Pixhawk AUXOUT3 -Pixhawk AUXOUT4 -Pixhawk AUXOUT5 -Pixhawk AUXOUT6 -PX4 FMU Relay1 -PX4 FMU Relay2 -PX4IO Relay1 -PX4IO Relay2 -PX4IO ACC1 -PX4IO ACC2 - - - - -Disabled -APM2 A9 pin -APM1 relay -Pixhawk AUXOUT1 -Pixhawk AUXOUT2 -Pixhawk AUXOUT3 -Pixhawk AUXOUT4 -Pixhawk AUXOUT5 -Pixhawk AUXOUT6 -PX4 FMU Relay1 -PX4 FMU Relay2 -PX4IO Relay1 -PX4IO Relay2 -PX4IO ACC1 -PX4IO ACC2 - + +0 1000 +Centi-Degrees - - -Disabled -APM2 A9 pin -APM1 relay -Pixhawk AUXOUT1 -Pixhawk AUXOUT2 -Pixhawk AUXOUT3 -Pixhawk AUXOUT4 -Pixhawk AUXOUT5 -Pixhawk AUXOUT6 -PX4 FMU Relay1 -PX4 FMU Relay2 -PX4IO Relay1 -PX4IO Relay2 -PX4IO ACC1 -PX4IO ACC2 - + +0.08 0.35 +0.005 - - -Off -On -NoChange - + +0.01 0.6 +0.01 - - - - -Disabled -Enabled - + +0 1 +0.01 - - -First Relay -Second Relay -Third Relay -Fourth Relay -Servo - + +0.001 0.03 +0.001 - -1000 2000 + +1 20 1 -pwm +Hz - -1000 2000 -1 -pwm + +0.08 0.35 +0.005 - -0 32000 -1 -Meters + +0.01 0.6 +0.01 - -0 5000 -1 -Milliseconds + +0 1 +0.01 - - - - -None -Analog -MaxbotixI2C -PulsedLightI2C -PX4-I2C -PX4-PWM -BBB-PRU -LightWareI2C -LightWareSerial -Bebop -MAVLink -uLanding -LeddarOne -MaxbotixSerial - + +0.001 0.03 +0.001 - - -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 - + +1 20 +1 +Hz - -0.001 -meters/Volt + +0.180 0.60 +0.005 - -0.001 -Volts + +0.01 0.06 +0.01 - - -Linear -Inverted -Hyperbolic - + +0 1 +0.01 - -1 -centimeters + +0.000 0.02 +0.001 - + +1 20 1 -centimeters +Hz - + + + -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 +Disabled +Enabled - -1 -milliseconds - - + -No -Yes +Remain in AVOID_ADSB +Resume previous flight mode +RTL +Resume if AUTO else Loiter - -0 32767 -meters + - -0 127 -1 -centimeters + +seconds - -0 127 -1 + +seconds - -m + +meters - -m + +meters - -m + +meters - + +meters + + + + +0:StopAtFence,1:UseProximitySensor None -Analog -MaxbotixI2C -PulsedLightI2C -PX4-I2C -PX4-PWM -BBB-PRU -LightWareI2C -LightWareSerial -Bebop -MAVLink -uLanding -LeddarOne -MaxbotixSerial - - - - -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 +StopAtFence +UseProximitySensor +All - -0.001 -meters/Volt + +0 4500 - -0.001 -Volts + +3 30 +meters - + + + -Linear -Inverted -Hyperbolic +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell - -1 -centimeters - - -1 -centimeters - - + -Not Used -Pixhawk AUXOUT1 -Pixhawk AUXOUT2 -Pixhawk AUXOUT3 -Pixhawk AUXOUT4 -Pixhawk AUXOUT5 -Pixhawk AUXOUT6 -PX4 FMU Relay1 -PX4 FMU Relay2 -PX4IO Relay1 -PX4IO Relay2 -PX4IO ACC1 -PX4IO ACC2 +Disabled +A0 +A1 +Pixhawk +A13 +PX4 - -1 -milliseconds - - + -No -Yes +Disabled +A1 +A2 +Pixhawk +A12 +PX4 - -0 127 -1 -centimeters + - -0 127 -1 + +Amps/Volt - -m + +Volts - -m + +50 +mAh - -m + +1 +Watts - + -None -Analog -APM2-MaxbotixI2C -APM2-PulsedLightI2C -PX4-I2C -PX4-PWM -BBB-PRU -LightWareI2C -LightWareSerial -Bebop -MAVLink -uLanding -LeddarOne -MaxbotixSerial +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell - + -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 +Disabled +A0 +A1 +Pixhawk +A13 +PX4 - -0.001 -meters/Volt - - -0.001 -Volts - - + -Linear -Inverted -Hyperbolic +Disabled +A1 +A2 +Pixhawk +A12 +PX4 - -1 -centimeters + - -1 -centimeters + +Amps/Volt - - -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 - + +Volts - + +50 +mAh + + 1 -milliseconds +Amps - + + + -No -Yes +None +Pozyx - -0 127 -1 -centimeters - - -0 127 -1 + +-90 90 +0.000001 +degrees - -m + +-180 180 +0.000001 +degrees - -m + +0 10000 +1 +meters - -m + +-180 +180 +1 +degrees - + + + -None -Analog -APM2-MaxbotixI2C -APM2-PulsedLightI2C -PX4-I2C -PX4-PWM -BBB-PRU -LightWareI2C -LightWareSerial -Bebop -MAVLink -uLanding -LeddarOne -MaxbotixSerial +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture +True - + -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 +Disabled +Enabled +Auto +True - -0.001 -meters/Volt + + +Disabled +Enabled +Auto + +True - -0.001 -Volts + + +Disabled +Enabled + +True - + -Linear -Inverted -Hyperbolic +Disabled +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz +True - -1 -centimeters + +-32767 32768 - -1 -centimeters + + +Disabled +Enabled +Dynamic ID/Update + - + +0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 -Not Used +Disabled +Enabled + +True + + +-1 80 +degreesC + + + +AUTO +PX4V1 +Pixhawk +Pixhawk2 +Pixracer +PixhawkMini +Pixhawk2Slim +VRBrain 5.1 +VRBrain 5.2 +VR Micro Brain 5.1 +VR Micro Brain 5.2 +VRBrain Core 1.0 +VRBrain 5.4 + +True + + + + + +Disabled +Enabled + + + + +Disabled Pixhawk AUXOUT1 Pixhawk AUXOUT2 Pixhawk AUXOUT3 @@ -3161,504 +2945,226 @@ PX4IO ACC2 - -1 -milliseconds - - + -No -Yes +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 127 -1 -centimeters - - -0 127 -1 - - -m + + +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 + - -m + + +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 + - -m + +0 3600 - - + + -Disable -Enable +Servo +Relay - -1 + +0 50 +deciseconds + + +1000 2000 +pwm + + +1000 2000 +pwm + + +0 1000 meters - - - + -Disabled -Enabled +Low +High - -1 100 + +0 10000 +milliseconds - -1 100000 + +0 180 +Degrees - --1 16777215 + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + - + -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 +TriggerLow +TriggerHigh - - + + Disabled Enabled - + -Remain in AVOID_ADSB -Resume previous flight mode -RTL -Resume if AUTO else Loiter +First Relay +Second Relay +Third Relay +Fourth Relay +Servo - - - -seconds + +1000 2000 +1 +pwm - -seconds + +1000 2000 +1 +pwm - -meters + +0 32000 +1 +Meters - -meters + +0 5000 +1 +Milliseconds - -meters + + + +0 10000 +100 +cm - -meters + +-90 90 +1 +deg/s - - - -Disable -Chan5 -Chan6 -Chan7 -Chan8 -Chan9 -Chan10 -Chan11 -Chan12 -Chan13 -Chan14 -Chan15 -Chan16 - + + +-400 400 +1 +milligauss - -900 2100 + +-400 400 +1 +milligauss - -900 2100 + +-400 400 +1 +milligauss - + +-3.142 3.142 +0.01 +Radians + + -Disable -Chan1 -Chan3 -Chan3 -Chan4 -Chan5 -Chan6 -Chan7 -Chan8 -Chan9 -Chan10 -Chan11 -Chan12 -Chan13 -Chan14 -Chan15 -Chan16 +Disabled +Internal-Learning +EKF-Learning - - - + -Disable -Enable +Disabled +Enabled - -0 1 - - - - -0.08 0.30 -0.005 - - -0.01 0.5 -0.01 - - -0 1 -0.01 -Percent + + +Disabled +Enabled + - -0.0 0.02 -0.001 + + +Disabled +Use Throttle +Use Current + - -1 100 + +-1000 1000 1 -Hz - - -0.08 0.30 -0.005 - - -0.01 0.5 -0.01 - - -0 1 -0.01 -Percent - - -0.0 0.02 -0.001 +Offset per Amp or at Full Throttle - -1 100 + +-1000 1000 1 -Hz +Offset per Amp or at Full Throttle - -0.10 0.50 -0.005 - - -0.010 0.05 -0.01 - - -0 1 -0.01 -Percent - - -0.000 0.02 -0.001 - - -1 100 -1 -Hz - - -0.1 0.25 - - -0.5 0.9 - - - - -0.4 1.0 -0.1 -seconds - - -0.1 4.0 -0.1 - - -0 0.1 -0.01 - - -0 1.0 -0.05 - - -0 180 -1 -degrees/second - - -0 4500 -1 - - -0.1 4.0 -0.1 - - - - -0.4 1.0 -0.1 -seconds - - -0.1 3.0 -0.1 - - -0 0.1 -0.01 - - -0 0.5 -0.05 - - -0 100 -1 -degrees/second - - -0 100 -1 -degrees/second - - -0.7 1.5 -0.05 - - -0 4500 -1 - - -0.1 4.0 -0.1 - - - - -0 4 -0.25 - - -0 2 -0.25 - - -0 2 -0.25 - - -0.8 1.2 -0.05 - - -0 4500 -1 - - - - -0.4 1.0 -0.1 -seconds - - -0.1 10.0 -0.1 - - -0 1.0 -0.05 - - -0 0.1 -0.01 - - -0 4500 -1 - - -0 5 -0.1 -m/s - - -0.0 10.0 -0.1 - - -0.0 30.0 -0.1 -m/s - - -0.0 50.0 -0.1 -degree/(m/s) - - -0.0 4500.0 -0.1 -Centidegrees - - - - --400 400 -1 -milligauss - - --400 400 -1 -milligauss - - --400 400 -1 -milligauss - - --3.142 3.142 -0.01 -Radians - - - -Disabled -Internal-Learning -EKF-Learning - - - - -Disabled -Enabled - - - - -Disabled -Enabled - - - - -Disabled -Use Throttle -Use Current - - - --1000 1000 -1 -Offset per Amp or at Full Throttle - - --1000 1000 -1 -Offset per Amp or at Full Throttle - - --1000 1000 -1 -Offset per Amp or at Full Throttle + +-1000 1000 +1 +Offset per Amp or at Full Throttle @@ -3935,1654 +3441,1738 @@ 4 32 Very Strict -Default -Relaxed -Very Relaxed +Strict +Default +Relaxed 0.1 - - + + Disabled -ShowSlips -ShowOverruns +Enabled - + -50Hz -100Hz -200Hz -250Hz -300Hz -400Hz +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS -True - - - -1 8 -1 -True - - -1 8 -1 -True + +0.05 5.0 +0.05 +m/s - -1 8 -1 -True + +0.05 5.0 +0.05 +m/s - -1 8 -1 -True + +100 1000 +25 - - - + +0.1 10.0 +0.1 +m - -rad/s + +100 1000 +25 - -rad/s + +10 100 +5 +m - -rad/s + +0 250 +10 +milliseconds - -rad/s + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + - -rad/s + +0.1 10.0 +0.1 +m - -rad/s + +100 1000 +25 - -rad/s + +0 250 +10 +milliseconds - + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 rad/s - + +0.05 1.0 +0.05 rad/s - -0.8 1.2 + +100 1000 +25 - -0.8 1.2 + +0 250 +10 +milliseconds - -0.8 1.2 + +0.0001 0.1 +0.0001 +rad/s - --3.5 3.5 + +0.01 1.0 +0.01 m/s/s - --3.5 3.5 -m/s/s + +0.00001 0.001 +rad/s/s - --3.5 3.5 + +0.000001 0.001 +1/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 m/s/s - -0.8 1.2 + +0.0 1.0 +0.1 - -0.8 1.2 + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed - -0.8 1.2 + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU - --3.5 3.5 -m/s/s + +50 200 +% - --3.5 3.5 -m/s/s + +0.5 50.0 +m - --3.5 3.5 -m/s/s + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU - -0.8 1.2 + +0.05 1.0 +0.05 +rad - -0.8 1.2 + +100 1000 +25 - -0.8 1.2 + +10 50 +5 +cs - --3.5 3.5 -m/s/s + +0.00001 0.01 +gauss/s - --3.5 3.5 -m/s/s + +0.00001 0.01 +gauss/s - --3.5 3.5 -m/s/s + +-1 70 +1 +% - -0 127 -Hz + +0 0.2 +0.01 - -0 127 -Hz + +0.1 10.0 +0.1 +m - - -Disabled -Enabled - + +100 1000 +25 - + +0 250 +10 +milliseconds + + +2.0 6.0 +0.5 +m/s + + + + Disabled -Enabled +Enabled - + -Disabled -Enabled +GPS 3D Vel and 2D Pos +GPS 2D vel and 2D pos +GPS 2D pos +No GPS - -0.05 50 + +0.05 5.0 +0.05 +m/s - - -Never -Start-up only - + +0.05 5.0 +0.05 +m/s - - -Don't adjust the trims -Assume first orientation was level -Assume ACC_BODYFIX is perfectly aligned to the vehicle - + +100 1000 +25 - + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + -IMU 1 -IMU 2 -IMU 3 +Use Baro +Use Range Finder +Use GPS +Use Range Beacon - + +0.1 10.0 +0.1 m - -m + +100 1000 +25 - -m + +0 250 +10 +milliseconds +True - -m + +0.01 0.5 +0.01 +gauss - -m + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + - -m + +100 1000 +25 - -m + +0.5 5.0 +0.1 +m/s - -m + +100 1000 +25 - + +0.1 10.0 +0.1 m - -True + +100 1000 +25 - -True + +1.0 4.0 +0.1 +rad/s - -True + +0.05 1.0 +0.05 +rad/s - -True + +100 1000 +25 - -True + +0 250 +10 +milliseconds +True - -True + +0.0001 0.1 +0.0001 +rad/s - + +0.01 1.0 +0.01 +m/s/s - - - + +0.00001 0.001 +rad/s/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 +m/s/s + + 0.0 1.0 -.01 +0.1 - - -Disabled -Enabled - + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed - -0.1 0.4 -.01 + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU - -0.1 0.4 -.01 + +50 200 +% - -0 127 + +0.5 50.0 +m + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +0.05 1.0 +0.05 +rad + + +100 1000 +25 + + +10 50 +5 +cs + + +0.00001 0.01 +gauss/s + + +0.00001 0.01 +gauss/s + + +-1 70 1 -m/s +% - --0.1745 +0.1745 + +0 0.2 0.01 -Radians - --0.1745 +0.1745 -0.01 -Radians + +0.1 10.0 +0.1 +m - --0.1745 +0.1745 -0.01 -Radians + +100 1000 +25 - - -None -Yaw45 -Yaw90 -Yaw135 -Yaw180 -Yaw225 -Yaw270 -Yaw315 -Roll180 -Roll180Yaw45 -Roll180Yaw90 -Roll180Yaw135 -Pitch180 -Roll180Yaw225 -Roll180Yaw270 -Roll180Yaw315 -Roll90 -Roll90Yaw45 -Roll90Yaw90 -Roll90Yaw135 -Roll270 -Roll270Yaw45 -Roll270Yaw90 -Roll270Yaw136 -Pitch90 -Pitch270 -Pitch180Yaw90 -Pitch180Yaw270 -Roll90Pitch90 -Roll180Pitch90 -Roll270Pitch90 -Roll90Pitch180 -Roll270Pitch180 -Roll90Pitch270 -Roll180Pitch270 -Roll270Pitch270 -Roll90Pitch180Yaw90 -Roll90Yaw270 - - - -0.001 0.5 -.01 - - -0 10 -1 - - + +0 250 +10 +milliseconds +True + + +2.0 6.0 +0.5 +m/s + + +0.5 2.5 +0.1 +m/s/s + + + + Disabled -Enable EKF2 -Enable EKF3 +Enabled - - - + +0:Altitude,1:Circle,2:Polygon None -I2C-MS4525D0 -Analog -I2C-MS5525 +Altitude +Circle +Altitude and Circle +Polygon +Altitude and Polygon +Circle and Polygon +All - + -Use -Don't Use +Report Only +RTL or Land - -0.1 - - -0.1 - - - - + +10 1000 +1 +Meters - + +30 10000 +Meters - - -Disable -Enable - + +1 10 +Meters - + +1 20 - + + + -Bus0 -Bus1 +Disabled +Enabled - - - -1 60 + +-200 +200 1 -seconds - - -0.6 1.0 -0.05 - - -0 0.1 -0.01 - - - - -0.1 20.0 -0.1 - - -0.1 10.0 -0.1 - - -3.0 10.0 -0.2 - - -0.1 1.0 -0.1 - - -0.0 0.5 -0.02 - - -1.0 10.0 -0.5 - - -1.0 5.0 -0.05 - - -0.5 2.0 -0.05 - - -5.0 30.0 -1.0 - - -0.0 2.0 -0.1 - - -0.1 1.0 -0.1 - - -0.0 20.0 -0.1 - --1 127 + +-200 +200 1 - --1 100 -0.1 - - --1.0 2.0 -0.1 - - -0 45 + +-18000 +18000 1 - --45 0 -1 + +m - -0.0 2.0 -0.1 + +m - -1.0 5.0 -0.2 + +m - -0.1 1.0 -0.1 + +0 255 - --5 40 + + + +True +True 1 +pascals - -0.0 20.0 -0.1 -m/s - - --2.0 2.0 -0.1 -m/s/m - - -0.1 1.0 -0.1 - - -0.0 0.5 -0.02 - - -0.0 0.5 -0.02 + +True +True +1 +degrees celsius - -0.1 1.0 + 0.1 +meters - + -Disable -Enable +FirstBaro +2ndBaro +3rdBaro - - - + -Retracted -Neutral -MavLink Targeting -RC Targeting -GPS Point +Disabled +Bus0 - --180.00 179.99 -1 -Degrees - - --180.00 179.99 -1 -Degrees - - --180.00 179.99 -1 -Degrees - - --180.00 179.99 -1 -Degrees - - --180.00 179.99 -1 -Degrees + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True - --180.00 179.99 -1 -Degrees + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True - + -Disabled -Enabled +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G - + Disabled Enabled - + -Disabled -Enabled +Any +FloatRTK +IntegerRTK +True - + Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +Enabled +NoChange - --18000 17999 -1 -Centi-Degrees - - --18000 17999 -1 -Centi-Degrees + +-100 90 +Degrees - + -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +send to first GPS +send to 2nd GPS +send to all - --18000 17999 -1 -Centi-Degrees - - --18000 17999 -1 -Centi-Degrees + + +None +All +External only + - + Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +log every sample +log every 5 samples +True - --18000 17999 -1 -Centi-Degrees - - --18000 17999 -1 -Centi-Degrees + +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 + - -0 100 -1 + + +Do not save config +Save config +Save only when needed + - -0.0 0.2 -.005 -Seconds + +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 + - -0.0 0.2 -.005 -Seconds + + +Disables automatic configuration +Enable automatic configuration + - + -None -Servo -3DR Solo -Alexmos Serial -SToRM32 MAVLink -SToRM32 Serial +10Hz +8Hz +5Hz -True +milliseconds - + -Retracted -Neutral -MavLink Targeting -RC Targeting -GPS Point +10Hz +8Hz +5Hz +milliseconds - --180.00 179.99 -1 -Degrees + +m - --180.00 179.99 -1 -Degrees + +m - --180.00 179.99 -1 -Degrees + +m - --180.00 179.99 -1 -Degrees + +m - --180.00 179.99 -1 -Degrees + +m - --180.00 179.99 -1 -Degrees + +m - - -Disabled -Enabled - + +0 250 +milliseconds - - -Disabled -Enabled - + +0 250 +milliseconds - + + + Disabled -Enabled +Enabled - + -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +None +Servo +EPM - --18000 17999 + +1000 2000 +PWM + + +1000 2000 +PWM + + +1000 2000 +PWM + + +0 255 +seconds + + +0 255 + + + + +-180 180 1 -Centi-Degrees +Degrees - --18000 17999 + +-180 180 1 -Centi-Degrees +Degrees - + +-180 180 +1 +Degrees + + -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +Servo only +Servo with ExtGyro +DirectDrive VarPitch +DirectDrive FixedPitch - --18000 17999 + + +3-Servo CCPM +H1 Mechanical Mixing + + + +0 1000 1 -Centi-Degrees +PWM - --18000 17999 + +-90 90 1 -Centi-Degrees +Degrees - + +-10 10 +0.1 + + -Disabled -RC5 -RC6 -RC7 -RC8 -RC9 -RC10 -RC11 -RC12 +NoFlybar +Flybar - --18000 17999 + +0 1000 1 -Centi-Degrees +PWM - --18000 17999 + +0 1000 1 -Centi-Degrees +PWM - -0.0 0.2 -.005 -Seconds + +0 2000 - -0.0 0.2 -.005 -Seconds + +0 2000 - + -None -Servo -3DR Solo -Alexmos Serial -SToRM32 MAVLink -SToRM32 Serial +Reversed +Normal - - - - -None -File -MAVLink -BothFileAndMAVLink - + +1000 2000 +1 +PWM - + +1000 2000 +1 +PWM - - -Disabled -Enabled - + +1000 2000 +1 +PWM - + Disabled -Enabled +Passthrough +Max collective +Mid collective +Min collective - - -Disabled -Enabled - + +0 1000 +10 +PWM - - - + -Disabled -Analog Voltage Only -Analog Voltage and Current -SMBus -Bebop +Ch8 Input +SetPoint +Throttle Curve - - -Disabled -A0 -A1 -Pixhawk -A13 -PX4 - + +0 500 +1 +pwm - - -Disabled -A1 -A2 -Pixhawk -A12 -PX4 - + +0 60 +Seconds - + +0 60 +Seconds - -Amps/Volt + +0 1000 +10 - -Volts + +0 500 +10 - -50 -mAh + +0 1000 +10 - + +0 1000 +10 + + +0 18000 +100 +Centi-Degrees + + +0 10 1 -Watts - + +1 1000 +10 + + +0 500 +10 + + + + Disabled -Analog Voltage Only -Analog Voltage and Current -SMBus -Bebop +Enabled - + -Disabled -A0 -A1 -Pixhawk -A13 -PX4 +None +Chan1 +Chan2 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 - - -Disabled -A1 -A2 -Pixhawk -A12 -PX4 - + +0.1 5 +Seconds - + +1 10 +Seconds - -Amps/Volt + +100 100000 - -Volts + +1000 2000 - -50 -mAh + +1000 2000 - -1 -Amps + +1000 2000 - - - - -No PWMs -Two PWMs -Four PWMs -Six PWMs -Three PWMs and One Capture - -True + +1000 2000 - + -Disabled -Enabled -Auto +None +RPM1 +RPM2 -True - - -Disabled -Enabled -Auto - -True + +0 100 - - -Disabled -Enabled - -True + + + +0 500 +1 +Percent*10 - - -Disabled -50Hz -75Hz -100Hz -150Hz -200Hz -250Hz -300Hz - -True + +0 500 +1 +Percent*10 - --32767 32768 + +500 1000 +1 +Percent*10 - - -Disabled -Enabled -Dynamic ID/Update - + +500 1000 +1 +Percent*10 - -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 -degreesC - - - -AUTO -PX4V1 -Pixhawk -Pixhawk2 -Pixracer -PixhawkMini -Pixhawk2Slim -VRBrain 5.1 -VRBrain 5.2 -VR Micro Brain 5.1 -VR Micro Brain 5.2 -VRBrain Core 1.0 -VRBrain 5.4 +Very Low +Low +Medium +High +Very High -True - - - - + + - + +rad/s - + +rad/s - + +rad/s - + +rad/s - + +rad/s - + +rad/s - -meters + +rad/s - -meters + +rad/s - -millibar + +rad/s - + +0.8 1.2 - + +0.8 1.2 - + +0.8 1.2 - + +-3.5 3.5 +m/s/s - + +-3.5 3.5 +m/s/s - + +-3.5 3.5 +m/s/s - -seconds + +0.8 1.2 - - - - -Disabled -Enabled - + +0.8 1.2 - --200 +200 -1 + +0.8 1.2 - --200 +200 -1 + +-3.5 3.5 +m/s/s - --18000 +18000 -1 + +-3.5 3.5 +m/s/s - -m + +-3.5 3.5 +m/s/s - -m + +0.8 1.2 - -m + +0.8 1.2 - -0 255 + +0.8 1.2 - - - -0 32766 -1 + +-3.5 3.5 +m/s/s - + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0 127 +Hz + + +0 127 +Hz + + -Resume Mission -Restart Mission +Disabled +Enabled - - - + + +Disabled +Enabled + - -0.1 -kilometers + + +Disabled +Enabled + - + +0.05 50 + + -DoNotIncludeHome -IncludeHome +Never +Start-up only - - - + -Disabled -Enabled +Don't adjust the trims +Assume first orientation was level +Assume ACC_BODYFIX is perfectly aligned to the vehicle - + -GPS 3D Vel and 2D Pos -GPS 2D vel and 2D pos -GPS 2D pos -No GPS +IMU 1 +IMU 2 +IMU 3 - -0.05 5.0 -0.05 -m/s + +m - -0.05 5.0 -0.05 -m/s + +m - -100 1000 -25 + +m - -0.1 10.0 -0.1 + m - -100 1000 -25 + +m - -10 100 -5 + m - -0 250 -10 -msec + +m - - -Use Baro -Use Range Finder -Use GPS -Use Range Beacon - + +m - -0.1 10.0 -0.1 + m - -100 1000 -25 + +True - -0 250 -10 -msec + +True - -0.01 0.5 -0.01 -gauss + +True - - -When flying -When manoeuvring -Never -After first climb yaw reset -Always - + +True - -100 1000 -25 + +True - -0.5 5.0 -0.1 -m/s + +True - -100 1000 -25 + - -0.1 10.0 + + + +0 5 +0.5 +meters + + +0 90 0.1 -m +degrees - -100 1000 -25 + +centi-Degrees - -1.0 4.0 + 0.1 -rad/s +meters - -0.05 1.0 -0.05 -rad/s - - -100 1000 -25 - - -0 250 -10 -msec - - -0.0001 0.1 -0.0001 -rad/s - - -0.01 1.0 -0.01 -m/s/s - - -0.00001 0.001 -rad/s/s - - -0.000001 0.001 -1/s - - -0.00001 0.001 -m/s/s/s - - -0.01 1.0 + 0.1 -m/s/s +seconds - -0.0 1.0 + +0 30 0.1 +meters - -0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + +0 10 +0.1 +seconds - -1 127 + +0 30 +0.1 +m/s - -50 200 -% + +0 127 +1 +percent - -0.5 50.0 -m/s + +0 127 +1 +seconds - + Disabled -FirstIMU -FirstAndSecondIMU -AllIMUs +Servos to Neutral +Servos to Zero PWM - -0.05 1.0 -0.05 -rad - - -100 1000 -25 - - -10 50 -5 -cs + + +Disabled +Enabled + - -0.00001 0.01 -gauss/s + +0 100 +Percent - -0.00001 0.01 -gauss/s + + +Standard Glide Slope + - --1 70 + + + +1000 2000 1 -% +pwm - -0 0.2 -0.01 + +1000 2000 +1 +pwm - -0.1 10.0 -0.1 -m + + + + +None +File +MAVLink +BothFileAndMAVLink + - -100 1000 -25 + - -0 250 -10 -msec + + +Disabled +Enabled + - -2.0 6.0 -0.5 -m + + +Disabled +Enabled + - - - + Disabled -Enabled +Enabled - + + + +0 32766 +1 + + -GPS 3D Vel and 2D Pos -GPS 2D vel and 2D pos -GPS 2D pos -No GPS +Resume Mission +Restart Mission - -0.05 5.0 -0.05 -m/s + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + - -0.05 5.0 -0.05 -m/s + +-180.00 179.99 +1 +Degrees - -100 1000 -25 + +-180.00 179.99 +1 +Degrees - -0.1 10.0 -0.1 -m + +-180.00 179.99 +1 +Degrees - -100 1000 -25 + +-180.00 179.99 +1 +Degrees - -10 100 -5 -m + +-180.00 179.99 +1 +Degrees - -0 250 -10 -msec + +-180.00 179.99 +1 +Degrees - + -Use Baro -Use Range Finder -Use GPS -Use Range Beacon +Disabled +Enabled - -0.1 10.0 -0.1 -m + + +Disabled +Enabled + - -100 1000 -25 + + +Disabled +Enabled + - -0 250 -10 -msec - - -0.01 0.5 -0.01 -gauss - - + -When flying -When manoeuvring -Never -After first climb yaw reset -Always +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 - -100 1000 -25 + +-18000 17999 +1 +Centi-Degrees - -0.5 5.0 -0.1 -m/s + +-18000 17999 +1 +Centi-Degrees - -100 1000 -25 + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.1 10.0 -0.1 -m + +-18000 17999 +1 +Centi-Degrees - -100 1000 -25 + +-18000 17999 +1 +Centi-Degrees - -1.0 4.0 -0.1 -rad/s + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.05 1.0 -0.05 -rad/s + +-18000 17999 +1 +Centi-Degrees - -100 1000 -25 + +-18000 17999 +1 +Centi-Degrees - -0 250 -10 -msec + +0 100 +1 - -0.0001 0.1 -0.0001 -rad/s + +0.0 0.2 +.005 +Seconds - -0.01 1.0 -0.01 -m/s/s + +0.0 0.2 +.005 +Seconds - -0.00001 0.001 -rad/s/s + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True - -0.00001 0.001 -m/s/s/s + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + - -0.01 1.0 -0.1 -m/s/s + +-180.00 179.99 +1 +Degrees - -0.0 1.0 -0.1 + +-180.00 179.99 +1 +Degrees - -0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + +-180.00 179.99 +1 +Degrees - -1 127 + +-180.00 179.99 +1 +Degrees - -50 200 -% + +-180.00 179.99 +1 +Degrees - -0.5 50.0 -m/s + +-180.00 179.99 +1 +Degrees - + Disabled -FirstIMU -FirstAndSecondIMU -AllIMUs +Enabled - -0.05 1.0 -0.05 -rad - - -100 1000 -25 + + +Disabled +Enabled + - -10 50 -5 -cs + + +Disabled +Enabled + - -0.00001 0.01 -gauss/s + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.00001 0.01 -gauss/s + +-18000 17999 +1 +Centi-Degrees - --1 70 + +-18000 17999 1 -% +Centi-Degrees - -0 0.2 -0.01 + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -0.1 10.0 -0.1 -m + +-18000 17999 +1 +Centi-Degrees - -100 1000 -25 + +-18000 17999 +1 +Centi-Degrees - -0 250 -10 -msec + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + - -2.0 6.0 -0.5 -m + +-18000 17999 +1 +Centi-Degrees - -0.5 2.5 -0.1 -m/s/s + +-18000 17999 +1 +Centi-Degrees - - - + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + None -PX4-PWM +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial - -0.001 + + + +0 500 +pwm - -1 + +0.25 0.8 - -1 + +0.9:Low, 0.95:Default, 1.0:High - -0.1 + +6 35 +Volts - + +6 35 +Volts + + +0 200 +Amps + + -None -PX4-PWM +Normal +OneShot +OneShot125 +Brushed16kHz +True - -0.001 + +0 2000 - - - + +0 2000 + + +0.0:Low, 0.15:Default, 0.3:High + + +0.0:Low, 0.1:Default, 0.2:High + + +0 10 +Seconds + + +0.2 0.8 + + Disabled -AnalogPin -RCChannelPwmValue +Learn +LearnAndSave - + -APM2 A0 -APM2 A1 -APM2 A13 -Pixracer -Pixhawk ADC4 -Pixhawk ADC3 - Pixhawk ADC6 -Pixhawk SBUS +PWM enabled while disarmed +PWM disabled while disarmed - -0 5.0 -0.01 -Volt + +5 80 +1 +Degrees - -0 5.0 -0.01 -Volt + +0 2 +0.1 +Seconds - - + + + +1 60 +1 +seconds - -0 2000 -Microseconds + +0.6 1.0 +0.05 - -0 2000 -Microseconds + +0 0.1 +0.01 @@ -5606,675 +5196,2950 @@ Enable - - - -0 5 -0.5 -meters - - -0 90 -0.1 -degrees - - -centi-Degrees - - -0.1 -meters - - -0.1 -seconds - - -0 30 -0.1 -meters - - -0 10 -0.1 -seconds - - -0 30 -0.1 -m/s - - -0 127 -1 -percent - - -0 127 -1 -seconds - - + -Disabled -Servos to Neutral -Servos to Zero PWM +Disable +ssd1306 +sh1106 - + + + Disabled -Enabled - - - -0 100 -Percent - - - -Standard Glide Slope +Enabled Always Land +Enabled Strict - - - + -Disabled -Enabled +None +CompanionComputer +IRLock +SITL_Gazebo +SITL - - -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 360 +1 +Centi-degrees - - -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 - + +-20 20 +1 +Centimeters - - -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 - + +-20 20 +1 +Centimeters - -0 3600 + + + +0.5 5 +0.1 +Hz - - + + -Disabled -Enabled +None +LightWareSF40C +MAVLink +TeraRangerTower - + -None -Chan1 -Chan2 -Chan3 -Chan4 -Chan5 -Chan6 -Chan7 -Chan8 -Chan9 -Chan10 -Chan11 -Chan12 -Chan13 -Chan14 -Chan15 -Chan16 +Default +Upside Down - -0.1 5 -Seconds + +-180 180 +degrees - -1 10 -Seconds + +0 360 +degrees - -100 100000 + +0 45 +degrees - -1000 2000 + +0 360 +degrees - -1000 2000 + +0 45 +degrees - -1000 2000 + +0 360 +degrees - -1000 2000 + +0 45 +degrees - + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + None -RPM1 -RPM2 +LightWareSF40C +MAVLink - -0 100 + + +Default +Upside Down + + + +-180 180 +degrees - - + + +0.4 1.0 +0.1 +seconds - + +0.1 3.0 +0.1 - + +0 0.1 +0.01 - + +0 0.5 +0.05 - - - -800 2200 + +0 100 1 -pwm +degrees/second - -800 2200 + +0 100 1 -pwm +degrees/second - -800 2200 + +0.7 1.5 +0.05 + + +0 4500 1 -pwm - - -Normal -Reversed - + +0.1 4.0 +0.1 - - -Disabled -RCPassThru -Flap -Flap_auto -Aileron -mount_pan -mount_tilt -mount_roll -mount_open -camera_trigger -release -mount2_pan -mount2_tilt -mount2_roll -mount2_open -DifferentialSpoiler1 -DifferentialSpoiler2 -AileronWithInput -Elevator -ElevatorWithInput -Rudder -Flaperon1 -Flaperon2 -GroundSteering -Parachute -EPM -LandingGear -EngineRunEnable -HeliRSC -HeliTailRSC -Motor1 -Motor2 -Motor3 -Motor4 -Motor5 -Motor6 -Motor7 -Motor8 -RCIN1 -RCIN2 -RCIN3 -RCIN4 -RCIN5 -RCIN6 -RCIN7 -RCIN8 -RCIN9 -RCIN10 -RCIN11 -RCIN12 -RCIN13 -RCIN14 -RCIN15 -RCIN16 -Ignition -Choke -Starter -Throttle -TrackerYaw -TrackerPitch - + + + +0.08 0.30 +0.005 - + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +0.1 0.25 + + +0.5 0.9 + + +0.5 0.9 + + + + + + +0.1 +kilometers + + -Disable -Enable +DoNotIncludeHome +IncludeHome - - + + 800 2200 1 pwm - + 800 2200 1 pwm - + 800 2200 1 pwm - + Normal Reversed - + 0 200 pwm - - -1000 2000 + + +800 2200 1 pwm - -1000 2000 + +800 2200 1 pwm - - - -0 500 + +800 2200 1 -Percent*10 +pwm - -0 500 + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 1 -Percent*10 +pwm - -500 1000 + +800 2200 1 -Percent*10 +pwm - -500 1000 + +800 2200 1 -Percent*10 +pwm - + -Disabled -Very Low -Low -Medium -High -Very High +Normal +Reversed - - - -20 2000 -50 -cm/s + +0 200 +pwm - -100 1000 + + + +800 2200 1 -cm - - -0 1000 -50 -cm/s +pwm - -0 500 -10 -cm/s + +800 2200 +1 +pwm - -0 2000 -50 -cm/s + +800 2200 +1 +pwm - -50 500 -10 -cm/s/s + + +Normal +Reversed + - -50 500 -10 -cm/s/s + +0 200 +pwm - -500 5000 + + + +800 2200 1 -cm/s/s/s +pwm - -100 981 + +800 2200 1 -cm/s/s +pwm - -25 250 + +800 2200 1 -cm/s/s +pwm - + -Disable -Enable +Normal +Reversed - - - -0 10000 -100 -cm + +0 200 +pwm - --90 90 + + + +800 2200 1 -deg/s +pwm - - - -500 18000 -100 -Centi-Degrees/Sec + +800 2200 +1 +pwm - -0 72000 + +800 2200 +1 +pwm + + -Disabled -Slow -Medium -Fast +Normal +Reversed -1000 -Centi-Degrees/Sec/Sec - + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + -Disabled -Enabled +Normal +Reversed - -0 180000 + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + -Disabled -Slow -Medium -Fast +Normal +Reversed -1000 -Centi-Degrees/Sec/Sec - -0 180000 + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + -Disabled -Slow -Medium -Fast +Normal +Reversed -1000 -Centi-Degrees/Sec/Sec - + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + -Disabled -Enabled +Normal +Reversed - -3.000 12.000 + +0 200 +pwm - -3.000 12.000 + + + +800 2200 +1 +pwm - -3.000 6.000 + +800 2200 +1 +pwm - -0.5 10.0 + +800 2200 +1 +pwm - -0.08 0.30 -0.005 + + +Normal +Reversed + - -0.01 0.5 -0.01 + +0 200 +pwm - -0 1 -0.01 -Percent + + + +800 2200 +1 +pwm - -0.0 0.02 -0.001 + +800 2200 +1 +pwm - -1 100 + +800 2200 1 -Hz +pwm - -0.08 0.30 -0.005 + + +Normal +Reversed + - -0.01 0.5 -0.01 + +0 200 +pwm - -0 1 -0.01 -Percent + + + +800 2200 +1 +pwm - -0.0 0.02 -0.001 + +800 2200 +1 +pwm - -1 100 + +800 2200 1 -Hz +pwm - -0.10 0.50 -0.005 + + +Normal +Reversed + - -0.010 0.05 -0.01 + +0 200 +pwm - -0 1 -0.01 -Percent + + + +800 2200 +1 +pwm - -0.000 0.02 -0.001 + +800 2200 +1 +pwm - -1 100 + +800 2200 1 -Hz +pwm - -0.1 0.25 + + +Normal +Reversed + - -0.5 0.9 + +0 200 +pwm - - -Disabled 1 + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Off +On +NoChange + + + + + +0.4 1.0 +0.1 +seconds + + +0.1 4.0 +0.1 + + +0 0.1 +0.01 + + +0 1.0 +0.05 + + +0 180 +1 +degrees/second + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 32767 +meters + + +5 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + + + +None +PX4-PWM + + + +0.001 + + +1 + + +1 + + +0.1 + + + +None +PX4-PWM + + + +0.001 + + + + + +Disabled +AnalogPin +RCChannelPwmValue + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixracer +Pixhawk ADC4 +Pixhawk ADC3 + Pixhawk ADC6 +Pixhawk SBUS + + + +0 5.0 +0.01 +Volt + + +0 5.0 +0.01 +Volt + + + + + +0 2000 +Microseconds + + +0 2000 +Microseconds + + + + + +Disabled +ShowSlips +ShowOverruns + + + + +50Hz +100Hz +200Hz +250Hz +300Hz +400Hz + +True + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +MAVlink1 +MAVLink2 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + + +Disable +Enable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch - -0 1000 -Centi-Degrees - - -0.08 0.35 -0.005 - - -0.01 0.6 -0.01 - - -0 1 -0.01 - - -0.001 0.03 -0.001 - - -1 20 + + + +800 2200 1 -Hz - - -0.08 0.35 -0.005 - - -0.01 0.6 -0.01 - - -0 1 -0.01 +pwm - -0.001 0.03 -0.001 + +800 2200 +1 +pwm - -1 20 + +800 2200 1 -Hz +pwm - -0.180 0.60 -0.005 + + +Normal +Reversed + - -0.01 0.06 -0.01 + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + - -0 1 -0.01 + + + - -0.000 0.02 -0.001 + - -1 20 -1 -Hz + - - - -0.5 5 -0.1 -Hz + @@ -6301,462 +8166,331 @@ percentage - - - -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 -Meters - - -30 10000 -Meters - - -1 10 -Meters - - -1 20 - - - - -0:StopAtFence,1:UseProximitySensor - -None -StopAtFence -UseProximitySensor -All - - - -0 4500 - - -3 30 -meters - - - - --180 180 -1 -Degrees - - --180 180 -1 -Degrees - - --180 180 -1 -Degrees - - - -Servo only -Servo with ExtGyro -DirectDrive VarPitch -DirectDrive FixedPitch - - - - -3-Servo CCPM -H1 Mechanical Mixing - - - -0 1000 -1 -PWM - - --90 90 -1 -Degrees + + - --10 10 -0.1 + +seconds - - -NoFlybar -Flybar - + +seconds - -0 1000 -1 -PWM + +seconds - -0 1000 -1 -PWM + + + +0.4 1.0 +0.1 +seconds - -0 2000 + +0.1 10.0 +0.1 - -0 2000 + +0 1.0 +0.05 - - -Reversed -Normal - + +0 0.1 +0.01 - -1000 2000 + +0 4500 1 -PWM - -1000 2000 -1 -PWM + +0 5 +0.1 +m/s - -1000 2000 -1 -PWM + +0.0 10.0 +0.1 - - -Disabled -Passthrough -Max collective -Mid collective -Min collective - + +0.0 30.0 +0.1 +m/s - -0 1000 -10 -PWM + +0.0 50.0 +0.1 +degree/(m/s) - - -Ch8 Input -SetPoint -Throttle Curve - + +0.0 4500.0 +0.1 +Centidegrees - -0 500 -1 -pwm + + + +0.1 20.0 +0.1 - -0 60 -Seconds + +0.1 10.0 +0.1 - -0 60 -Seconds + +3.0 10.0 +0.2 - -0 1000 -10 + +0.1 1.0 +0.1 - -0 500 -10 + +0.0 0.5 +0.02 - -0 1000 -10 + +1.0 10.0 +0.5 - -0 1000 -10 + +1.0 5.0 +0.05 - -0 18000 -100 -Centi-Degrees + +0.5 2.0 +0.05 - -0 10 -1 + +5.0 30.0 +1.0 - -1 1000 -10 + +0.0 2.0 +0.1 - -0 500 -10 + +0.1 1.0 +0.1 - - - -0 500 -pwm + +0.0 20.0 +0.1 - -0.25 0.8 + +-1 127 +1 - -0.9:Low, 0.95:Default, 1.0:High + +-1 100 +0.1 - -6 35 -Volts + +-1.0 2.0 +0.1 - -6 35 -Volts + +0 45 +1 - -0 200 -Amps + +-45 0 +1 - - -Normal -OneShot -OneShot125 -Brushed16kHz - -True + +0.0 2.0 +0.1 - -0 2000 + +1.0 5.0 +0.2 - -0 2000 + +0.1 1.0 +0.1 - -0.0:Low, 0.15:Default, 0.3:High + +-5 40 +1 - -0.0:Low, 0.1:Default, 0.2:High + +0.0 20.0 +0.1 +m/s - -0 10 -Seconds + +-2.0 2.0 +0.1 +m/s/m - -0.2 0.8 + +0.1 1.0 +0.1 - - -Disabled -Learn -LearnAndSave - + +0.0 0.5 +0.02 - - -PWM enabled while disarmed -PWM disabled while disarmed - + +0.0 0.5 +0.02 - -5 80 -1 -Degrees + +0.1 1.0 +0.1 - - - + -Disabled -Enabled Always Land -Enabled Strict +Disable +Enable - + + + -None -CompanionComputer -IRLock -SITL_Gazebo -SITL +Disable +Enable - -0 360 -1 -Centi-degrees - - --20 20 -1 -Centimeters - - --20 20 + 1 -Centimeters +meters - - + + -None -Pozyx +Disable +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 - --90 90 -0.000001 -degrees - - --180 180 -0.000001 -degrees - - -0 10000 -1 -meters + +900 2100 - --180 +180 -1 -degrees + +900 2100 - - - + -None -LightWareSF40C -MAVLink +Disable +Chan1 +Chan3 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 - + + + -Default -Upside Down +Disable +Enable - --180 180 - - -0 360 - - -0 45 - - -0 360 + +0 1 - -0 45 + + + +20 2000 +50 +cm/s - -0 360 + +100 1000 +1 +cm - -0 45 + +0 1000 +50 +cm/s - -0 360 + +0 500 +10 +cm/s - -0 45 + +0 2000 +50 +cm/s - -0 360 + +50 500 +10 +cm/s/s - -0 45 + +50 500 +10 +cm/s/s - -0 360 + +500 5000 +1 +cm/s/s/s - -0 45 + +100 981 +1 +cm/s/s - - -None -LightWareSF40C -MAVLink - + +25 250 +1 +cm/s/s - + -Default -Upside Down +Disable +Enable - --180 180 - - - - -Disabled -Enabled - - - - -None -Servo -EPM - - - -1000 2000 - - -1000 2000 - - -1000 2000 - - -0 255 -seconds - - -0 255 + + +0 4 +0.25 - - - + +0 2 +0.25 - + +0 2 +0.25 - + +0.8 1.2 +0.05 - + +0 4500 +1 diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml new file mode 100644 index 0000000000000000000000000000000000000000..91f87f90fda231c636912b9c077dc5fae61f4993 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Plane.3.8.xml @@ -0,0 +1,8496 @@ + + + + + + + + +True + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +1 10 +1 + + +0 30 +1 +seconds + + +0:Roll,1:Pitch,2:Yaw + + +0 1 +0.01 + + +0 5 +0.01 + + +0 15 +0.1 +Degrees + + +0 1000 +1 +meters + + +0 100 +1 +meters + + + +Disabled +FBWMixing +DirectMixing + + + + +Disabled +Enabled + + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s/s + + +0 127 +1 +0.1 seconds + + +-100 100 +1 +Percent + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s + + +0 127 +1 +percent + + +0 10 +0.5 +seconds + + +0 100 +Percent + + + + +0 45 +1 +degrees + + +0:AUTO_ALWAYS,1:AUTO_LAND,2:AUTO_LOITER_TO_ALT,3:AUTO_LOITER_ALL,4:AUTO_WAYPOINTS,5:LOITER,6:RTL,7:CIRCLE,8:CRUISE,9:FBWB,10:GUIDED + + + +Default +L1Controller + + + + +Automatic + + + +-32767 32767 +1 +Meters + + +1 32767 +1 +Meters + + +0 32767 +1 +Meters + + +-32767 32767 +1 +Meters + + +-32767 32767 +1 +Meters + + + +None +GuidedMode +ReportOnly +GuidedModeThrPass +RTL_Mode + + + + + + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + + +NoAutoEnable +AutoEnable +AutoEnableDisableFloorOnly + + + + +FenceReturnPoint +NearestRallyPoint + + + + +Disabled +Enabled + + + +5 100 +1 +m/s + + +5 100 +1 +m/s + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 10000 +meters + + +1 10 +0.1 +m/s + + +-100 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 127 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +925 2200 +1 + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +CIRCLE/no change(if already in AUTO|GUIDED|LOITER) +CIRCLE +FBWA + + + +1 100 +0.5 +seconds + + + +Continue +ReturnToLaunch +Glide +Deploy Parachute + + + +1 300 +0.5 +seconds + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Heartbeat +HeartbeatAndREMRSSI +HeartbeatAndAUTO + + + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + +0 9000 +1 +centi-Degrees + + +0 9000 +1 +centi-Degrees + + +-9000 0 +1 +centi-Degrees + + +10 500 +1 +degrees/second + + +10 500 +1 +degrees/second + + + +Disabled +Enabled + + + +-100 100 +0.1 +Meters + + +10 360 +1 +degrees/second + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + +0.5 1.2 + + + +Disabled +Enabled + + + +-1000 1000 +percent + + +-1000 1000 +percent + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW + +Disabled +PX4/Pixhawk-Default + + + + + + + +cm/s + + +m/s + + +cm/s + + +centi-Degrees + + +centimeters + + +centimeters + + + +Disabled +Enabled + + + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + +0 100 +Percent + + +0 100 +1 +m/s + + +0 100 +Percent + + +0 100 +1 +m/s + + + + + + + +Disabled +Channel1 +Channel2 +Channel3 +Channel4 +Channel5 +Channel6 +Channel7 +Channel8 + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 90 +0.1 +degrees + + + +Disable +Enable - go HOME then land +Enable - go directly to landing sequence + + + + +Disable +Enable + + + +10 127 +m/s/s + + +0:Disarm + + + + + +Disabled +Enabled + + + + + +True + + +True + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + + +Mission Planner and DroidPlanner + AP Planner 2 + + + + +Disabled +Enabled + + + +0 10 +.5 +Hz + + +0.0 1000.0 +10 +Centimeters + + +0.0 500.0 +10 + + +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 +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 8000 +1 +Centimeters + + +0.5 10.0 + +Disabled +Shallow +Steep + +.1 + + +0 2000 +50 +cm/s + + +0.01 2.0 +0.01 + + + +Disabled +Land +RTL + + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode + + + +100 900 + + + +Disabled +Enabled + + + + +Disabled +Mode1 +Mode2 +Mode1+2 +Mode3 +Mode1+3 +Mode2+3 +Mode1+2+3 +Mode4 +Mode1+4 +Mode2+4 +Mode1+2+4 +Mode3+4 +Mode1+3+4 +Mode2+3+4 +Mode1+2+3+4 +Mode5 +Mode1+5 +Mode2+5 +Mode1+2+5 +Mode3+5 +Mode1+3+5 +Mode2+3+5 +Mode1+2+3+5 +Mode4+5 +Mode1+4+5 +Mode2+4+5 +Mode1+2+4+5 +Mode3+4+5 +Mode1+3+4+5 +Mode2+3+4+5 +Mode1+2+3+4+5 +Mode6 +Mode1+6 +Mode2+6 +Mode1+2+6 +Mode3+6 +Mode1+3+6 +Mode2+3+6 +Mode1+2+3+6 +Mode4+6 +Mode1+4+6 +Mode2+4+6 +Mode1+2+4+6 +Mode3+4+6 +Mode1+3+4+6 +Mode2+3+4+6 +Mode1+2+3+4+6 +Mode5+6 +Mode1+5+6 +Mode2+5+6 +Mode1+2+5+6 +Mode3+5+6 +Mode1+3+5+6 +Mode2+3+5+6 +Mode1+2+3+5+6 +Mode4+5+6 +Mode1+4+5+6 +Mode2+4+5+6 +Mode1+2+4+5+6 +Mode3+4+5+6 +Mode1+3+4+5+6 +Mode2+3+4+5+6 +Mode1+2+3+4+5+6 + + + +-1 1000 +1 +Centimeters + + +0 3000 +10 +Centimeters + + + +Never change yaw +Face next waypoint +Face next waypoint except RTL +Face along GPS course + + + +0 60000 +1000 +ms + + +30 200 +10 +cm/s + + +0 500 +10 +cm/s + + +50 500 +10 +Centimeters/Second + + +50 500 +10 +cm/s/s + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always LAND + + + +925 1100 +1 +pwm + + +0 300 +1 +pwm + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + + +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 +Altitude Hold kP +Throttle Rate kP +Throttle Accel kP +Throttle Accel kI +Throttle Accel kD +Loiter Speed +Loiter Pos kP +Velocity XY kP +Velocity XY kI +WP Speed +Acro RollPitch kP +Acro Yaw kP +Heli Ext Gyro +OF Loiter kP +OF Loiter kI +OF Loiter kD +Declination +Circle Rate +RangeFinder Gain +Rate Pitch kP +Rate Pitch kI +Rate Pitch kD +Rate Roll kP +Rate Roll kI +Rate Roll kD +Rate Pitch FF +Rate Roll FF +Rate Yaw FF + + + +0 32767 + + +0 32767 + + + +Plus +X +V +H +V-Tail +A-Tail +Y6B + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + +0 127 +Seconds + + +1000 8000 +Centi-degrees + + +0 100 + +Very Soft +Soft +Medium +Crisp +Very Crisp + +10 + + +4 12 +deg/sec + + +2000 4500 +Centi-degrees + + + +No repositioning +Repositioning + + + + +Land +AltHold +Land even in Stabilize + + + +0.6:Strict, 0.8:Default, 1.0:Relaxed + + + +Disabled +Enabled + + + +50 490 +1 +Hz + + +1 10 + + +1 10 + + +0 3 +0.1 + + +0 3 +0.1 + + + +Disabled +Leveling +Leveling and Limited + + + +-0.5 1.0 + +Disabled +Very Low +Low +Medium +High +Very High + + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0 4500 +10 +cm/s/s + + +1.000 8.000 + + +0.500 1.500 +0.05 + + +0.000 3.000 + + +0 1000 +Percent*10 + + +0.000 0.400 + + +1.000 100.000 +Hz + + +1.000 3.000 + + +0.500 2.000 + + +0:Roll,1:Pitch,2:Yaw + +All +Roll Only +Pitch Only +Yaw Only +Roll and Pitch +Roll and Yaw +Pitch and Yaw + + + +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 +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 + + + +Undefined +Quad +Hexa +Octa +OctaQuad +Y6 +Heli +Tri +SingleCopter +CoaxCopter + + + + + + + +True + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 20 +0.1 +seconds + + +0 20 +0.1 +seconds + + +0 100 +1 +degrees/second + + +0 20 +1 +seconds + + +-90 90 +0.000001 +degrees + + +-180 180 +0.000001 +degrees + + +0 10 +0.1 +seconds + + + +Position +OnOff +ContinuousRotation + + + + +Position +OnOff +ContinuousRotation + + + +0 50 +0.1 +degrees/second + + +0 50 +0.1 +degrees/second + + +0 2 +0.01 +seconds + + +0 2 +0.01 +seconds + + +-10 10 +0.1 +degrees + + +-10 10 +0.1 +degrees + + +0 360 +0.1 +degrees + + +0 100 +1 +meters + + + +Barometer +GPS +GPS vehicle only + + + +1 10 +1 +Hz + + +-90 0 +1 +Degrees + + +0 90 +1 +Degrees + + +0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS + +Default +Disabled + + + +0.0 3.0 +0.01 + + +0.0 3.0 +0.01 + + +0 4000 +10 +Percent*10 + + +0.001 0.1 +0.001 + + +0.0 3.0 +0.01 + + +0.0 3.0 +0.01 + + +0 4000 +10 +Percent*10 + + +0.001 0.1 +0.001 + + +1 255 + + + + + + +True + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW + +Disabled +APM2-Default +PX4/Pixhawk-Default + + + + + + + + +MANUAL +LEARNING +STEERING +HOLD +AUTO +RTL +GUIDED + + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 30 +1 +seconds + + +0:Steering,1:Throttle + +None +Steering +Throttle + + + + +Disabled +Enabled + + + + +Disabled +APM TriggerPin0 +APM TriggerPin1 +APM TriggerPin2 +APM TriggerPin3 +APM TriggerPin4 +APM TriggerPin5 +APM TriggerPin6 +APM TriggerPin7 +APM TriggerPin8 +Pixhawk TriggerPin50 +Pixhawk TriggerPin51 +Pixhawk TriggerPin52 +Pixhawk TriggerPin53 +Pixhawk TriggerPin54 +Pixhawk TriggerPin55 + + + +0 20 +0.1 +m/s/s + + +0 100 +0.1 +m/s + + +0 100 +1 +percent + + +0 100 +0.1 +meters + + +0 100 +1 +percent + + +0 100 +1 +m/s + + +0 360 +1 +degrees + + + +Nothing +LearnWaypoint + + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +SkidSteeringOutput + + + + +Disabled +SkidSteeringInput + + + + +Nothing +RTL +HOLD + + + +seconds + + + +Disabled +Enabled + + + +925 1100 +1 + + + +Disabled +Enabled + + + + +Disabled +HOLD +HoldAndDisarm + + + +0 1000 +1 +centimeters + + +-45 45 +1 +centimeters + + +0 100 +0.1 +seconds + + +1 100 +1 + + + + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + +0 1000 +0.1 +meters + + +0.2 10 +0.1 +gravities + + + + + +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 + + + + + + + + + + + + + + + + + + + + + +meters + + +meters + + +millibar + + + + + + + + + + + + + + +seconds + + + + +0.0 1.0 +.01 + + + +Disabled +Enabled + + + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 + + + +0.001 0.5 +.01 + + +0 10 +1 + + + +Disabled +Enable EKF2 +Enable EKF3 + + + + + + +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,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration + +None +All +Barometer +Compass +GPS Lock +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Failsafe +Board voltage +Battery Level +Airspeed +LoggingAvailable +Hardware safety switch +GPS configuration + + + +0.25 3.0 +m/s/s + + +0.1 +Volts + + +0.1 +Volts + + + + + +None +I2C-MS4525D0 +Analog +I2C-MS5525 + + + + +Use +Don't Use + + + +0.1 + + +0.1 + + + + + + + + + +Disable +Enable + + + + + + +Bus0 +Bus1 + + + + + +500 18000 +100 +Centi-Degrees/Sec + + +0 72000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +3.000 12.000 + + +3.000 12.000 + + +3.000 6.000 + + +0.5 10.0 + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +0.1 0.25 + + +0.5 0.9 + + +0.5 0.9 + + + +Disabled 1 + + + +0 1000 +Centi-Degrees + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +1 20 +1 +Hz + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +1 20 +1 +Hz + + +0.180 0.60 +0.005 + + +0.01 0.06 +0.01 + + +0 1 +0.01 + + +0.000 0.02 +0.001 + + +1 20 +1 +Hz + + + + + +Disabled +Enabled + + + + +Remain in AVOID_ADSB +Resume previous flight mode +RTL +Resume if AUTO else Loiter + + + + + +seconds + + +seconds + + +meters + + +meters + + +meters + + +meters + + + + +0:StopAtFence,1:UseProximitySensor + +None +StopAtFence +UseProximitySensor +All + + + +0 4500 + + +3 30 +meters + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Watts + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Amps + + + + + +None +Pozyx + + + +-90 90 +0.000001 +degrees + + +-180 180 +0.000001 +degrees + + +0 10000 +1 +meters + + +-180 +180 +1 +degrees + + + + + +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled + +True + + + +Disabled +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz + +True + + +-32767 32768 + + + +Disabled +Enabled +Dynamic ID/Update + + + +0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 + +Disabled +Enabled + +True + + +-1 80 +degreesC + + + +AUTO +PX4V1 +Pixhawk +Pixhawk2 +Pixracer +PixhawkMini +Pixhawk2Slim +VRBrain 5.1 +VRBrain 5.2 +VR Micro Brain 5.1 +VR Micro Brain 5.2 +VRBrain Core 1.0 +VRBrain 5.4 + +True + + + + + +Disabled +Enabled + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +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 +deciseconds + + +1000 2000 +pwm + + +1000 2000 +pwm + + +0 1000 +meters + + + +Low +High + + + +0 10000 +milliseconds + + +0 180 +Degrees + + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + + + + +TriggerLow +TriggerHigh + + + + + + +Disabled +Enabled + + + + +First Relay +Second Relay +Third Relay +Fourth Relay +Servo + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + +0 32000 +1 +Meters + + +0 5000 +1 +Milliseconds + + + + +0 10000 +100 +cm + + +-90 90 +1 +deg/s + + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-3.142 3.142 +0.01 +Radians + + + +Disabled +Internal-Learning +EKF-Learning + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +FirstCompass +SecondCompass +ThirdCompass + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + + + + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +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 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +4 32 + +Very Strict +Strict +Default +Relaxed + +0.1 + + + + + +Disabled +Enabled + + + + +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 + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + +0 250 +10 +milliseconds + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s + + +0.05 1.0 +0.05 +rad/s + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +0.0001 0.1 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.00001 0.001 +rad/s/s + + +0.000001 0.001 +1/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +50 200 +% + + +0.5 50.0 +m + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +0.05 1.0 +0.05 +rad + + +100 1000 +25 + + +10 50 +5 +cs + + +0.00001 0.01 +gauss/s + + +0.00001 0.01 +gauss/s + + +-1 70 +1 +% + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +2.0 6.0 +0.5 +m/s + + + + + +Disabled +Enabled + + + + +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 + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s + + +0.05 1.0 +0.05 +rad/s + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +0.0001 0.1 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.00001 0.001 +rad/s/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +50 200 +% + + +0.5 50.0 +m + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +0.05 1.0 +0.05 +rad + + +100 1000 +25 + + +10 50 +5 +cs + + +0.00001 0.01 +gauss/s + + +0.00001 0.01 +gauss/s + + +-1 70 +1 +% + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +2.0 6.0 +0.5 +m/s + + +0.5 2.5 +0.1 +m/s/s + + + + + +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 +Meters + + +30 10000 +Meters + + +1 10 +Meters + + +1 20 + + + + + +Disabled +Enabled + + + +-200 +200 +1 + + +-200 +200 +1 + + +-18000 +18000 +1 + + +m + + +m + + +m + + +0 255 + + + + +True +True +1 +pascals + + +True +True +1 +degrees celsius + + +0.1 +meters + + + +FirstBaro +2ndBaro +3rdBaro + + + + +Disabled +Bus0 + + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + + + + +Disabled +Enabled + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + + + +-100 90 +Degrees + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None +All +External only + + + + +Disabled +log every sample +log every 5 samples + +True + + +0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS + +Leave as currently configured +GPS-NoSBAS +GPS+SBAS +Galileo-NoSBAS +Galileo+SBAS +Beidou +GPS+IMES+QZSS+SBAS (Japan Only) +GLONASS +GLONASS+SBAS +GPS+GLONASS+SBAS + + + + +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 + + + + +10Hz +8Hz +5Hz + +milliseconds + + + +10Hz +8Hz +5Hz + +milliseconds + + +m + + +m + + +m + + +m + + +m + + +m + + +0 250 +milliseconds + + +0 250 +milliseconds + + + + + +Disabled +Enabled + + + + +None +Servo +EPM + + + +1000 2000 +PWM + + +1000 2000 +PWM + + +1000 2000 +PWM + + +0 255 +seconds + + +0 255 + + + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + + +Servo only +Servo with ExtGyro +DirectDrive VarPitch +DirectDrive FixedPitch + + + + +3-Servo CCPM +H1 Mechanical Mixing + + + +0 1000 +1 +PWM + + +-90 90 +1 +Degrees + + +-10 10 +0.1 + + + +NoFlybar +Flybar + + + +0 1000 +1 +PWM + + +0 1000 +1 +PWM + + +0 2000 + + +0 2000 + + + +Reversed +Normal + + + +1000 2000 +1 +PWM + + +1000 2000 +1 +PWM + + +1000 2000 +1 +PWM + + + +Disabled +Passthrough +Max collective +Mid collective +Min collective + + + +0 1000 +10 +PWM + + + +Ch8 Input +SetPoint +Throttle Curve + + + +0 500 +1 +pwm + + +0 60 +Seconds + + +0 60 +Seconds + + +0 1000 +10 + + +0 500 +10 + + +0 1000 +10 + + +0 1000 +10 + + +0 18000 +100 +Centi-Degrees + + +0 10 +1 + + +1 1000 +10 + + +0 500 +10 + + + + + +Disabled +Enabled + + + + +None +Chan1 +Chan2 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + +0.1 5 +Seconds + + +1 10 +Seconds + + +100 100000 + + +1000 2000 + + +1000 2000 + + +1000 2000 + + +1000 2000 + + + +None +RPM1 +RPM2 + + + +0 100 + + + + +0 500 +1 +Percent*10 + + +0 500 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + + +Disabled +Very Low +Low +Medium +High +Very High + + + + + + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0 127 +Hz + + +0 127 +Hz + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0.05 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 + + +m + + +m + + +m + + +m + + +m + + +m + + +m + + +m + + +True + + +True + + +True + + +True + + +True + + +True + + + + + + +0 5 +0.5 +meters + + +0 90 +0.1 +degrees + + +centi-Degrees + + +0.1 +meters + + +0.1 +seconds + + +0 30 +0.1 +meters + + +0 10 +0.1 +seconds + + +0 30 +0.1 +m/s + + +0 127 +1 +percent + + +0 127 +1 +seconds + + + +Disabled +Servos to Neutral +Servos to Zero PWM + + + + +Disabled +Enabled + + + +0 100 +Percent + + + +Standard Glide Slope + + + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + + +0 32766 +1 + + + +Resume Mission +Restart Mission + + + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0 100 +1 + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + + + +0 500 +pwm + + +0.25 0.8 + + +0.9:Low, 0.95:Default, 1.0:High + + +6 35 +Volts + + +6 35 +Volts + + +0 200 +Amps + + + +Normal +OneShot +OneShot125 +Brushed16kHz + +True + + +0 2000 + + +0 2000 + + +0.0:Low, 0.15:Default, 0.3:High + + +0.0:Low, 0.1:Default, 0.2:High + + +0 10 +Seconds + + +0.2 0.8 + + + +Disabled +Learn +LearnAndSave + + + + +PWM enabled while disarmed +PWM disabled while disarmed + + + +5 80 +1 +Degrees + + +0 2 +0.1 +Seconds + + + + +1 60 +1 +seconds + + +0.6 1.0 +0.05 + + +0 0.1 +0.01 + + + + + +Off +Low +Medium +High + + + + +Disable +Enable + + + + +Disable +Enable + + + + +Disable +ssd1306 +sh1106 + + + + + + +Disabled +Enabled Always Land +Enabled Strict + + + + +None +CompanionComputer +IRLock +SITL_Gazebo +SITL + + + +0 360 +1 +Centi-degrees + + +-20 20 +1 +Centimeters + + +-20 20 +1 +Centimeters + + + + +0.5 5 +0.1 +Hz + + + + + +None +LightWareSF40C +MAVLink +TeraRangerTower + + + + +Default +Upside Down + + + +-180 180 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + + +None +LightWareSF40C +MAVLink + + + + +Default +Upside Down + + + +-180 180 +degrees + + + + +0.4 1.0 +0.1 +seconds + + +0.1 3.0 +0.1 + + +0 0.1 +0.01 + + +0 0.5 +0.05 + + +0 100 +1 +degrees/second + + +0 100 +1 +degrees/second + + +0.7 1.5 +0.05 + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +0.1 0.25 + + +0.5 0.9 + + +0.5 0.9 + + + + + + +0.1 +kilometers + + + +DoNotIncludeHome +IncludeHome + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Off +On +NoChange + + + + + +0.4 1.0 +0.1 +seconds + + +0.1 4.0 +0.1 + + +0 0.1 +0.01 + + +0 1.0 +0.05 + + +0 180 +1 +degrees/second + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 32767 +meters + + +5 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + + + +None +PX4-PWM + + + +0.001 + + +1 + + +1 + + +0.1 + + + +None +PX4-PWM + + + +0.001 + + + + + +Disabled +AnalogPin +RCChannelPwmValue + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixracer +Pixhawk ADC4 +Pixhawk ADC3 + Pixhawk ADC6 +Pixhawk SBUS + + + +0 5.0 +0.01 +Volt + + +0 5.0 +0.01 +Volt + + + + + +0 2000 +Microseconds + + +0 2000 +Microseconds + + + + + +Disabled +ShowSlips +ShowOverruns + + + + +50Hz +100Hz +200Hz +250Hz +300Hz +400Hz + +True + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +MAVlink1 +MAVLink2 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + + +Disable +Enable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + + + + + + + + + + + + +Disabled +Enabled + + + +0 100 +percentage + + +1000 2000 +ms + + +0 1000 +cm/s + + +0 100 +percentage + + + + + + +seconds + + +seconds + + +seconds + + + + +0.4 1.0 +0.1 +seconds + + +0.1 10.0 +0.1 + + +0 1.0 +0.05 + + +0 0.1 +0.01 + + +0 4500 +1 + + +0 5 +0.1 +m/s + + +0.0 10.0 +0.1 + + +0.0 30.0 +0.1 +m/s + + +0.0 50.0 +0.1 +degree/(m/s) + + +0.0 4500.0 +0.1 +Centidegrees + + + + +0.1 20.0 +0.1 + + +0.1 10.0 +0.1 + + +3.0 10.0 +0.2 + + +0.1 1.0 +0.1 + + +0.0 0.5 +0.02 + + +1.0 10.0 +0.5 + + +1.0 5.0 +0.05 + + +0.5 2.0 +0.05 + + +5.0 30.0 +1.0 + + +0.0 2.0 +0.1 + + +0.1 1.0 +0.1 + + +0.0 20.0 +0.1 + + +-1 127 +1 + + +-1 100 +0.1 + + +-1.0 2.0 +0.1 + + +0 45 +1 + + +-45 0 +1 + + +0.0 2.0 +0.1 + + +1.0 5.0 +0.2 + + +0.1 1.0 +0.1 + + +-5 40 +1 + + +0.0 20.0 +0.1 +m/s + + +-2.0 2.0 +0.1 +m/s/m + + +0.1 1.0 +0.1 + + +0.0 0.5 +0.02 + + +0.0 0.5 +0.02 + + +0.1 1.0 +0.1 + + + +Disable +Enable + + + + + + +Disable +Enable + + + +1 +meters + + + + + +Disable +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + +900 2100 + + +900 2100 + + + +Disable +Chan1 +Chan3 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + + + + +Disable +Enable + + + +0 1 + + + + +20 2000 +50 +cm/s + + +100 1000 +1 +cm + + +0 1000 +50 +cm/s + + +0 500 +10 +cm/s + + +0 2000 +50 +cm/s + + +50 500 +10 +cm/s/s + + +50 500 +10 +cm/s/s + + +500 5000 +1 +cm/s/s/s + + +100 981 +1 +cm/s/s + + +25 250 +1 +cm/s/s + + + +Disable +Enable + + + + + +0 4 +0.25 + + +0 2 +0.25 + + +0 2 +0.25 + + +0.8 1.2 +0.05 + + +0 4500 +1 + + + diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml new file mode 100644 index 0000000000000000000000000000000000000000..91f87f90fda231c636912b9c077dc5fae61f4993 --- /dev/null +++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Rover.3.2.xml @@ -0,0 +1,8496 @@ + + + + + + + + +True + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +1 10 +1 + + +0 30 +1 +seconds + + +0:Roll,1:Pitch,2:Yaw + + +0 1 +0.01 + + +0 5 +0.01 + + +0 15 +0.1 +Degrees + + +0 1000 +1 +meters + + +0 100 +1 +meters + + + +Disabled +FBWMixing +DirectMixing + + + + +Disabled +Enabled + + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s/s + + +0 127 +1 +0.1 seconds + + +-100 100 +1 +Percent + + +0 30 +0.1 +m/s + + +0 30 +0.1 +m/s + + +0 127 +1 +percent + + +0 10 +0.5 +seconds + + +0 100 +Percent + + + + +0 45 +1 +degrees + + +0:AUTO_ALWAYS,1:AUTO_LAND,2:AUTO_LOITER_TO_ALT,3:AUTO_LOITER_ALL,4:AUTO_WAYPOINTS,5:LOITER,6:RTL,7:CIRCLE,8:CRUISE,9:FBWB,10:GUIDED + + + +Default +L1Controller + + + + +Automatic + + + +-32767 32767 +1 +Meters + + +1 32767 +1 +Meters + + +0 32767 +1 +Meters + + +-32767 32767 +1 +Meters + + +-32767 32767 +1 +Meters + + + +None +GuidedMode +ReportOnly +GuidedModeThrPass +RTL_Mode + + + + + + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + +0 32767 +1 +meters + + + +NoAutoEnable +AutoEnable +AutoEnableDisableFloorOnly + + + + +FenceReturnPoint +NearestRallyPoint + + + + +Disabled +Enabled + + + +5 100 +1 +m/s + + +5 100 +1 +m/s + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 10000 +meters + + +1 10 +0.1 +m/s + + +-100 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 127 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +925 2200 +1 + + +0 100 +1 +Percent + + + +Disabled +Enabled + + + + +CIRCLE/no change(if already in AUTO|GUIDED|LOITER) +CIRCLE +FBWA + + + +1 100 +0.5 +seconds + + + +Continue +ReturnToLaunch +Glide +Deploy Parachute + + + +1 300 +0.5 +seconds + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Heartbeat +HeartbeatAndREMRSSI +HeartbeatAndAUTO + + + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + + +Manual +CIRCLE +STABILIZE +TRAINING +ACRO +FBWA +FBWB +CRUISE +AUTOTUNE +Auto +RTL +Loiter +AVOID_ADSB +Guided +QSTABILIZE +QHOVER +QLOITER +QLAND +QRTL + + + +0 9000 +1 +centi-Degrees + + +0 9000 +1 +centi-Degrees + + +-9000 0 +1 +centi-Degrees + + +10 500 +1 +degrees/second + + +10 500 +1 +degrees/second + + + +Disabled +Enabled + + + +-100 100 +0.1 +Meters + + +10 360 +1 +degrees/second + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + +0.5 1.2 + + + +Disabled +Enabled + + + +-1000 1000 +percent + + +-1000 1000 +percent + + + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW + +Disabled +PX4/Pixhawk-Default + + + + + + + +cm/s + + +m/s + + +cm/s + + +centi-Degrees + + +centimeters + + +centimeters + + + +Disabled +Enabled + + + + + + +Disabled +UpUp +UpDown +DownUp +DownDown +UpUpSwap +UpDownSwap +DownUpSwap +DownDownSwap + + + +0 100 +Percent + + +0 100 +1 +m/s + + +0 100 +Percent + + +0 100 +1 +m/s + + + + + + + +Disabled +Channel1 +Channel2 +Channel3 +Channel4 +Channel5 +Channel6 +Channel7 +Channel8 + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0 90 +0.1 +degrees + + + +Disable +Enable - go HOME then land +Enable - go directly to landing sequence + + + + +Disable +Enable + + + +10 127 +m/s/s + + +0:Disarm + + + + + +Disabled +Enabled + + + + + +True + + +True + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + + +Mission Planner and DroidPlanner + AP Planner 2 + + + + +Disabled +Enabled + + + +0 10 +.5 +Hz + + +0.0 1000.0 +10 +Centimeters + + +0.0 500.0 +10 + + +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 +seconds + + +0:Roll,1:Pitch,2:Yaw + +None +Roll +Pitch +Yaw + + + +0 8000 +1 +Centimeters + + +0.5 10.0 + +Disabled +Shallow +Steep + +.1 + + +0 2000 +50 +cm/s + + +0.01 2.0 +0.01 + + + +Disabled +Land +RTL + + + +0.1 +Volts + + +50 +mAh + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode + + + +100 900 + + + +Disabled +Enabled + + + + +Disabled +Mode1 +Mode2 +Mode1+2 +Mode3 +Mode1+3 +Mode2+3 +Mode1+2+3 +Mode4 +Mode1+4 +Mode2+4 +Mode1+2+4 +Mode3+4 +Mode1+3+4 +Mode2+3+4 +Mode1+2+3+4 +Mode5 +Mode1+5 +Mode2+5 +Mode1+2+5 +Mode3+5 +Mode1+3+5 +Mode2+3+5 +Mode1+2+3+5 +Mode4+5 +Mode1+4+5 +Mode2+4+5 +Mode1+2+4+5 +Mode3+4+5 +Mode1+3+4+5 +Mode2+3+4+5 +Mode1+2+3+4+5 +Mode6 +Mode1+6 +Mode2+6 +Mode1+2+6 +Mode3+6 +Mode1+3+6 +Mode2+3+6 +Mode1+2+3+6 +Mode4+6 +Mode1+4+6 +Mode2+4+6 +Mode1+2+4+6 +Mode3+4+6 +Mode1+3+4+6 +Mode2+3+4+6 +Mode1+2+3+4+6 +Mode5+6 +Mode1+5+6 +Mode2+5+6 +Mode1+2+5+6 +Mode3+5+6 +Mode1+3+5+6 +Mode2+3+5+6 +Mode1+2+3+5+6 +Mode4+5+6 +Mode1+4+5+6 +Mode2+4+5+6 +Mode1+2+4+5+6 +Mode3+4+5+6 +Mode1+3+4+5+6 +Mode2+3+4+5+6 +Mode1+2+3+4+5+6 + + + +-1 1000 +1 +Centimeters + + +0 3000 +10 +Centimeters + + + +Never change yaw +Face next waypoint +Face next waypoint except RTL +Face along GPS course + + + +0 60000 +1000 +ms + + +30 200 +10 +cm/s + + +0 500 +10 +cm/s + + +50 500 +10 +Centimeters/Second + + +50 500 +10 +cm/s/s + + + +Disabled +Enabled always RTL +Enabled Continue with Mission in Auto Mode +Enabled always LAND + + + +925 1100 +1 +pwm + + +0 300 +1 +pwm + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + +Stabilize +Acro +AltHold +Auto +Guided +Loiter +RTL +Circle +Land +Drift +Sport +Flip +AutoTune +PosHold +Brake +Throw +Avoid_ADSB +Guided_NoGPS + + + + + +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 +Altitude Hold kP +Throttle Rate kP +Throttle Accel kP +Throttle Accel kI +Throttle Accel kD +Loiter Speed +Loiter Pos kP +Velocity XY kP +Velocity XY kI +WP Speed +Acro RollPitch kP +Acro Yaw kP +Heli Ext Gyro +OF Loiter kP +OF Loiter kI +OF Loiter kD +Declination +Circle Rate +RangeFinder Gain +Rate Pitch kP +Rate Pitch kI +Rate Pitch kD +Rate Roll kP +Rate Roll kI +Rate Roll kD +Rate Pitch FF +Rate Roll FF +Rate Yaw FF + + + +0 32767 + + +0 32767 + + + +Plus +X +V +H +V-Tail +A-Tail +Y6B + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + + +Do Nothing +Flip +Simple Mode +RTL +Save Trim +Save WP +Camera Trigger +RangeFinder +Fence +Super Simple Mode +Acro Trainer +Sprayer +Auto +AutoTune +Land +Gripper +Parachute Enable +Parachute Release +Parachute 3pos +Auto Mission Reset +AttCon Feed Forward +AttCon Accel Limits +Retract Mount +Relay On/Off +Relay2 On/Off +Relay3 On/Off +Relay4 On/Off +Landing Gear +Lost Copter Sound +Motor Emergency Stop +Motor Interlock +Brake +Throw +Avoidance +PrecLoiter +Object Avoidance +ArmDisarm + + + +0 127 +Seconds + + +1000 8000 +Centi-degrees + + +0 100 + +Very Soft +Soft +Medium +Crisp +Very Crisp + +10 + + +4 12 +deg/sec + + +2000 4500 +Centi-degrees + + + +No repositioning +Repositioning + + + + +Land +AltHold +Land even in Stabilize + + + +0.6:Strict, 0.8:Default, 1.0:Relaxed + + + +Disabled +Enabled + + + +50 490 +1 +Hz + + +1 10 + + +1 10 + + +0 3 +0.1 + + +0 3 +0.1 + + + +Disabled +Leveling +Leveling and Limited + + + +-0.5 1.0 + +Disabled +Very Low +Low +Medium +High +Very High + + + +0.1 6.0 +0.1 + + +0.02 1.00 +0.01 + + +0 4500 +10 +cm/s/s + + +1.000 8.000 + + +0.500 1.500 +0.05 + + +0.000 3.000 + + +0 1000 +Percent*10 + + +0.000 0.400 + + +1.000 100.000 +Hz + + +1.000 3.000 + + +0.500 2.000 + + +0:Roll,1:Pitch,2:Yaw + +All +Roll Only +Pitch Only +Yaw Only +Roll and Pitch +Roll and Yaw +Pitch and Yaw + + + +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 +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 + + + +Undefined +Quad +Hexa +Octa +OctaQuad +Y6 +Heli +Tri +SingleCopter +CoaxCopter + + + + + + + +True + +ArduPlane +AntennaTracker +Copter +Rover + + + +1 255 + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 20 +0.1 +seconds + + +0 20 +0.1 +seconds + + +0 100 +1 +degrees/second + + +0 20 +1 +seconds + + +-90 90 +0.000001 +degrees + + +-180 180 +0.000001 +degrees + + +0 10 +0.1 +seconds + + + +Position +OnOff +ContinuousRotation + + + + +Position +OnOff +ContinuousRotation + + + +0 50 +0.1 +degrees/second + + +0 50 +0.1 +degrees/second + + +0 2 +0.01 +seconds + + +0 2 +0.01 +seconds + + +-10 10 +0.1 +degrees + + +-10 10 +0.1 +degrees + + +0 360 +0.1 +degrees + + +0 100 +1 +meters + + + +Barometer +GPS +GPS vehicle only + + + +1 10 +1 +Hz + + +-90 0 +1 +Degrees + + +0 90 +1 +Degrees + + +0:ATTITUDE,1:GPS,2:RCIN,3:IMU,4:RCOUT,5:COMPASS + +Default +Disabled + + + +0.0 3.0 +0.01 + + +0.0 3.0 +0.01 + + +0 4000 +10 +Percent*10 + + +0.001 0.1 +0.001 + + +0.0 3.0 +0.01 + + +0.0 3.0 +0.01 + + +0 4000 +10 +Percent*10 + + +0.001 0.1 +0.001 + + +1 255 + + + + + + +True + + +0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:MODE,7:IMU,8:CMD,9:CURRENT,10:COMPASS,11:TECS,12:CAMERA,13:RC,14:SONAR,15:ARM/DISARM,19:IMU_RAW + +Disabled +APM2-Default +PX4/Pixhawk-Default + + + + + + + + +MANUAL +LEARNING +STEERING +HOLD +AUTO +RTL +GUIDED + + + +1 255 + + +1 255 + + + +Disabled +Enabled + + + +0 30 +1 +seconds + + +0:Steering,1:Throttle + +None +Steering +Throttle + + + + +Disabled +Enabled + + + + +Disabled +APM TriggerPin0 +APM TriggerPin1 +APM TriggerPin2 +APM TriggerPin3 +APM TriggerPin4 +APM TriggerPin5 +APM TriggerPin6 +APM TriggerPin7 +APM TriggerPin8 +Pixhawk TriggerPin50 +Pixhawk TriggerPin51 +Pixhawk TriggerPin52 +Pixhawk TriggerPin53 +Pixhawk TriggerPin54 +Pixhawk TriggerPin55 + + + +0 20 +0.1 +m/s/s + + +0 100 +0.1 +m/s + + +0 100 +1 +percent + + +0 100 +0.1 +meters + + +0 100 +1 +percent + + +0 100 +1 +m/s + + +0 360 +1 +degrees + + + +Nothing +LearnWaypoint + + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + +0 100 +1 +Percent + + + +Disabled +SkidSteeringOutput + + + + +Disabled +SkidSteeringInput + + + + +Nothing +RTL +HOLD + + + +seconds + + + +Disabled +Enabled + + + +925 1100 +1 + + + +Disabled +Enabled + + + + +Disabled +HOLD +HoldAndDisarm + + + +0 1000 +1 +centimeters + + +-45 45 +1 +centimeters + + +0 100 +0.1 +seconds + + +1 100 +1 + + + + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + + +Manual +LEARNING +STEERING +HOLD +Auto +RTL +Guided + + + +0 1000 +0.1 +meters + + +0.2 10 +0.1 +gravities + + + + + +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 + + + + + + + + + + + + + + + + + + + + + +meters + + +meters + + +millibar + + + + + + + + + + + + + + +seconds + + + + +0.0 1.0 +.01 + + + +Disabled +Enabled + + + +0.1 0.4 +.01 + + +0.1 0.4 +.01 + + +0 127 +1 +m/s + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + +-0.1745 +0.1745 +0.01 +Radians + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 + + + +0.001 0.5 +.01 + + +0 10 +1 + + + +Disabled +Enable EKF2 +Enable EKF3 + + + + + + +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,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration + +None +All +Barometer +Compass +GPS Lock +INS(INertial Sensors - accels & gyros) +Parameters(unused) +RC Failsafe +Board voltage +Battery Level +Airspeed +LoggingAvailable +Hardware safety switch +GPS configuration + + + +0.25 3.0 +m/s/s + + +0.1 +Volts + + +0.1 +Volts + + + + + +None +I2C-MS4525D0 +Analog +I2C-MS5525 + + + + +Use +Don't Use + + + +0.1 + + +0.1 + + + + + + + + + +Disable +Enable + + + + + + +Bus0 +Bus1 + + + + + +500 18000 +100 +Centi-Degrees/Sec + + +0 72000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + +0 180000 + +Disabled +Slow +Medium +Fast + +1000 +Centi-Degrees/Sec/Sec + + + +Disabled +Enabled + + + +3.000 12.000 + + +3.000 12.000 + + +3.000 6.000 + + +0.5 10.0 + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +0.1 0.25 + + +0.5 0.9 + + +0.5 0.9 + + + +Disabled 1 + + + +0 1000 +Centi-Degrees + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +1 20 +1 +Hz + + +0.08 0.35 +0.005 + + +0.01 0.6 +0.01 + + +0 1 +0.01 + + +0.001 0.03 +0.001 + + +1 20 +1 +Hz + + +0.180 0.60 +0.005 + + +0.01 0.06 +0.01 + + +0 1 +0.01 + + +0.000 0.02 +0.001 + + +1 20 +1 +Hz + + + + + +Disabled +Enabled + + + + +Remain in AVOID_ADSB +Resume previous flight mode +RTL +Resume if AUTO else Loiter + + + + + +seconds + + +seconds + + +meters + + +meters + + +meters + + +meters + + + + +0:StopAtFence,1:UseProximitySensor + +None +StopAtFence +UseProximitySensor +All + + + +0 4500 + + +3 30 +meters + + + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Watts + + + +Disabled +Analog Voltage Only +Analog Voltage and Current +Solo +Bebop +SMBus-Maxell + + + + +Disabled +A0 +A1 +Pixhawk +A13 +PX4 + + + + +Disabled +A1 +A2 +Pixhawk +A12 +PX4 + + + + + +Amps/Volt + + +Volts + + +50 +mAh + + +1 +Amps + + + + + +None +Pozyx + + + +-90 90 +0.000001 +degrees + + +-180 180 +0.000001 +degrees + + +0 10000 +1 +meters + + +-180 +180 +1 +degrees + + + + + +No PWMs +Two PWMs +Four PWMs +Six PWMs +Three PWMs and One Capture + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled +Auto + +True + + + +Disabled +Enabled + +True + + + +Disabled +50Hz +75Hz +100Hz +150Hz +200Hz +250Hz +300Hz + +True + + +-32767 32768 + + + +Disabled +Enabled +Dynamic ID/Update + + + +0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14 + +Disabled +Enabled + +True + + +-1 80 +degreesC + + + +AUTO +PX4V1 +Pixhawk +Pixhawk2 +Pixracer +PixhawkMini +Pixhawk2Slim +VRBrain 5.1 +VRBrain 5.2 +VR Micro Brain 5.1 +VR Micro Brain 5.2 +VRBrain Core 1.0 +VRBrain 5.4 + +True + + + + + +Disabled +Enabled + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +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 +deciseconds + + +1000 2000 +pwm + + +1000 2000 +pwm + + +0 1000 +meters + + + +Low +High + + + +0 10000 +milliseconds + + +0 180 +Degrees + + + +Disabled +PX4 AUX1 +PX4 AUX2 +PX4 AUX3 +PX4 AUX4(fast capture) +PX4 AUX5 +PX4 AUX6 + + + + +TriggerLow +TriggerHigh + + + + + + +Disabled +Enabled + + + + +First Relay +Second Relay +Third Relay +Fourth Relay +Servo + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + +0 32000 +1 +Meters + + +0 5000 +1 +Milliseconds + + + + +0 10000 +100 +cm + + +-90 90 +1 +deg/s + + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-3.142 3.142 +0.01 +Radians + + + +Disabled +Internal-Learning +EKF-Learning + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Use Throttle +Use Current + + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + +FirstCompass +SecondCompass +ThirdCompass + + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-400 400 +1 +milligauss + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + +-1000 1000 +1 +Offset per Amp or at Full Throttle + + + + + + + + + +Disabled +Enabled + + + + +None +Yaw45 +Yaw90 +Yaw135 +Yaw180 +Yaw225 +Yaw270 +Yaw315 +Roll180 +Roll180Yaw45 +Roll180Yaw90 +Roll180Yaw135 +Pitch180 +Roll180Yaw225 +Roll180Yaw270 +Roll180Yaw315 +Roll90 +Roll90Yaw45 +Roll90Yaw90 +Roll90Yaw135 +Roll270 +Roll270Yaw45 +Roll270Yaw90 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +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 +Roll270Yaw136 +Pitch90 +Pitch270 +Pitch180Yaw90 +Pitch180Yaw270 +Roll90Pitch90 +Roll180Pitch90 +Roll270Pitch90 +Roll90Pitch180 +Roll270Pitch180 +Roll90Pitch270 +Roll180Pitch270 +Roll270Pitch270 +Roll90Pitch180Yaw90 +Roll90Yaw270 +Yaw293Pitch68Roll90 + + + + +Internal +External +ForcedExternal + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +4 32 + +Very Strict +Strict +Default +Relaxed + +0.1 + + + + + +Disabled +Enabled + + + + +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 + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + +0 250 +10 +milliseconds + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s + + +0.05 1.0 +0.05 +rad/s + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +0.0001 0.1 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.00001 0.001 +rad/s/s + + +0.000001 0.001 +1/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +50 200 +% + + +0.5 50.0 +m + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +0.05 1.0 +0.05 +rad + + +100 1000 +25 + + +10 50 +5 +cs + + +0.00001 0.01 +gauss/s + + +0.00001 0.01 +gauss/s + + +-1 70 +1 +% + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds + + +2.0 6.0 +0.5 +m/s + + + + + +Disabled +Enabled + + + + +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 + + +0.05 5.0 +0.05 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +10 100 +5 +m + + + +Use Baro +Use Range Finder +Use GPS +Use Range Beacon + + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +0.01 0.5 +0.01 +gauss + + + +When flying +When manoeuvring +Never +After first climb yaw reset +Always + + + +100 1000 +25 + + +0.5 5.0 +0.1 +m/s + + +100 1000 +25 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +1.0 4.0 +0.1 +rad/s + + +0.05 1.0 +0.05 +rad/s + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +0.0001 0.1 +0.0001 +rad/s + + +0.01 1.0 +0.01 +m/s/s + + +0.00001 0.001 +rad/s/s + + +0.00001 0.001 +m/s/s/s + + +0.01 1.0 +0.1 +m/s/s + + +0.0 1.0 +0.1 + + +0:NSats,1:HDoP,2:speed error,3:horiz pos error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +50 200 +% + + +0.5 50.0 +m + + +0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU + + +0.05 1.0 +0.05 +rad + + +100 1000 +25 + + +10 50 +5 +cs + + +0.00001 0.01 +gauss/s + + +0.00001 0.01 +gauss/s + + +-1 70 +1 +% + + +0 0.2 +0.01 + + +0.1 10.0 +0.1 +m + + +100 1000 +25 + + +0 250 +10 +milliseconds +True + + +2.0 6.0 +0.5 +m/s + + +0.5 2.5 +0.1 +m/s/s + + + + + +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 +Meters + + +30 10000 +Meters + + +1 10 +Meters + + +1 20 + + + + + +Disabled +Enabled + + + +-200 +200 +1 + + +-200 +200 +1 + + +-18000 +18000 +1 + + +m + + +m + + +m + + +0 255 + + + + +True +True +1 +pascals + + +True +True +1 +degrees celsius + + +0.1 +meters + + + +FirstBaro +2ndBaro +3rdBaro + + + + +Disabled +Bus0 + + + + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True + + + +None +AUTO +uBlox +MTK +MTK19 +NMEA +SiRF +HIL +SwiftNav +PX4-UAVCAN +SBF +GSOF +QURT +ERB +MAV +NOVA + +True + + + +Portable +Stationary +Pedestrian +Automotive +Sea +Airborne1G +Airborne2G +Airborne4G + + + + +Disabled +Enabled + + + + +Any +FloatRTK +IntegerRTK + +True + + + +Disabled +Enabled +NoChange + + + +-100 90 +Degrees + + + +send to first GPS +send to 2nd GPS +send to all + + + + +None +All +External only + + + + +Disabled +log every sample +log every 5 samples + +True + + +0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS + +Leave as currently configured +GPS-NoSBAS +GPS+SBAS +Galileo-NoSBAS +Galileo+SBAS +Beidou +GPS+IMES+QZSS+SBAS (Japan Only) +GLONASS +GLONASS+SBAS +GPS+GLONASS+SBAS + + + + +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 + + + + +10Hz +8Hz +5Hz + +milliseconds + + + +10Hz +8Hz +5Hz + +milliseconds + + +m + + +m + + +m + + +m + + +m + + +m + + +0 250 +milliseconds + + +0 250 +milliseconds + + + + + +Disabled +Enabled + + + + +None +Servo +EPM + + + +1000 2000 +PWM + + +1000 2000 +PWM + + +1000 2000 +PWM + + +0 255 +seconds + + +0 255 + + + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + +-180 180 +1 +Degrees + + + +Servo only +Servo with ExtGyro +DirectDrive VarPitch +DirectDrive FixedPitch + + + + +3-Servo CCPM +H1 Mechanical Mixing + + + +0 1000 +1 +PWM + + +-90 90 +1 +Degrees + + +-10 10 +0.1 + + + +NoFlybar +Flybar + + + +0 1000 +1 +PWM + + +0 1000 +1 +PWM + + +0 2000 + + +0 2000 + + + +Reversed +Normal + + + +1000 2000 +1 +PWM + + +1000 2000 +1 +PWM + + +1000 2000 +1 +PWM + + + +Disabled +Passthrough +Max collective +Mid collective +Min collective + + + +0 1000 +10 +PWM + + + +Ch8 Input +SetPoint +Throttle Curve + + + +0 500 +1 +pwm + + +0 60 +Seconds + + +0 60 +Seconds + + +0 1000 +10 + + +0 500 +10 + + +0 1000 +10 + + +0 1000 +10 + + +0 18000 +100 +Centi-Degrees + + +0 10 +1 + + +1 1000 +10 + + +0 500 +10 + + + + + +Disabled +Enabled + + + + +None +Chan1 +Chan2 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + +0.1 5 +Seconds + + +1 10 +Seconds + + +100 100000 + + +1000 2000 + + +1000 2000 + + +1000 2000 + + +1000 2000 + + + +None +RPM1 +RPM2 + + + +0 100 + + + + +0 500 +1 +Percent*10 + + +0 500 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + +500 1000 +1 +Percent*10 + + + +Disabled +Very Low +Low +Medium +High +Very High + + + + + + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +rad/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0.8 1.2 + + +0.8 1.2 + + +0.8 1.2 + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +-3.5 3.5 +m/s/s + + +0 127 +Hz + + +0 127 +Hz + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + +0.05 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 + + +m + + +m + + +m + + +m + + +m + + +m + + +m + + +m + + +True + + +True + + +True + + +True + + +True + + +True + + + + + + +0 5 +0.5 +meters + + +0 90 +0.1 +degrees + + +centi-Degrees + + +0.1 +meters + + +0.1 +seconds + + +0 30 +0.1 +meters + + +0 10 +0.1 +seconds + + +0 30 +0.1 +m/s + + +0 127 +1 +percent + + +0 127 +1 +seconds + + + +Disabled +Servos to Neutral +Servos to Zero PWM + + + + +Disabled +Enabled + + + +0 100 +Percent + + + +Standard Glide Slope + + + + + +1000 2000 +1 +pwm + + +1000 2000 +1 +pwm + + + + + +None +File +MAVLink +BothFileAndMAVLink + + + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + + +0 32766 +1 + + + +Resume Mission +Restart Mission + + + + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0 100 +1 + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + +True + + + +Retracted +Neutral +MavLink Targeting +RC Targeting +GPS Point + + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + +-180.00 179.99 +1 +Degrees + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +Enabled + + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + + +Disabled +RC5 +RC6 +RC7 +RC8 +RC9 +RC10 +RC11 +RC12 + + + +-18000 17999 +1 +Centi-Degrees + + +-18000 17999 +1 +Centi-Degrees + + +0.0 0.2 +.005 +Seconds + + +0.0 0.2 +.005 +Seconds + + + +None +Servo +3DR Solo +Alexmos Serial +SToRM32 MAVLink +SToRM32 Serial + + + + + +0 500 +pwm + + +0.25 0.8 + + +0.9:Low, 0.95:Default, 1.0:High + + +6 35 +Volts + + +6 35 +Volts + + +0 200 +Amps + + + +Normal +OneShot +OneShot125 +Brushed16kHz + +True + + +0 2000 + + +0 2000 + + +0.0:Low, 0.15:Default, 0.3:High + + +0.0:Low, 0.1:Default, 0.2:High + + +0 10 +Seconds + + +0.2 0.8 + + + +Disabled +Learn +LearnAndSave + + + + +PWM enabled while disarmed +PWM disabled while disarmed + + + +5 80 +1 +Degrees + + +0 2 +0.1 +Seconds + + + + +1 60 +1 +seconds + + +0.6 1.0 +0.05 + + +0 0.1 +0.01 + + + + + +Off +Low +Medium +High + + + + +Disable +Enable + + + + +Disable +Enable + + + + +Disable +ssd1306 +sh1106 + + + + + + +Disabled +Enabled Always Land +Enabled Strict + + + + +None +CompanionComputer +IRLock +SITL_Gazebo +SITL + + + +0 360 +1 +Centi-degrees + + +-20 20 +1 +Centimeters + + +-20 20 +1 +Centimeters + + + + +0.5 5 +0.1 +Hz + + + + + +None +LightWareSF40C +MAVLink +TeraRangerTower + + + + +Default +Upside Down + + + +-180 180 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + +0 360 +degrees + + +0 45 +degrees + + + +None +LightWareSF40C +MAVLink + + + + +Default +Upside Down + + + +-180 180 +degrees + + + + +0.4 1.0 +0.1 +seconds + + +0.1 3.0 +0.1 + + +0 0.1 +0.01 + + +0 0.5 +0.05 + + +0 100 +1 +degrees/second + + +0 100 +1 +degrees/second + + +0.7 1.5 +0.05 + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.08 0.30 +0.005 + + +0.01 0.5 +0.01 + + +0 1 +0.01 +Percent + + +0.0 0.02 +0.001 + + +1 100 +1 +Hz + + +0.10 0.50 +0.005 + + +0.010 0.05 +0.01 + + +0 1 +0.01 +Percent + + +0.000 0.02 +0.001 + + +1 100 +1 +Hz + + +0.1 0.25 + + +0.5 0.9 + + +0.5 0.9 + + + + + + +0.1 +kilometers + + + +DoNotIncludeHome +IncludeHome + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + +0 200 +pwm + + + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + +1 8 +1 +True + + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Disabled +APM2 A9 pin +APM1 relay +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + + +Off +On +NoChange + + + + + +0.4 1.0 +0.1 +seconds + + +0.1 4.0 +0.1 + + +0 0.1 +0.01 + + +0 1.0 +0.05 + + +0 180 +1 +degrees/second + + +0 4500 +1 + + +0.1 4.0 +0.1 + + + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 32767 +meters + + +5 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +MaxbotixI2C +PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial +TrOneI2C + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + +None +Analog +APM2-MaxbotixI2C +APM2-PulsedLightI2C +PX4-PWM +BBB-PRU +LightWareI2C +LightWareSerial +Bebop +MAVLink +uLanding +LeddarOne +MaxbotixSerial + + + + +Not Used +APM2-A0 +APM2-A1 +APM2-A2 +APM2-A3 +APM2-A4 +APM2-A5 +APM2-A6 +APM2-A7 +APM2-A8 +APM2-A9 +PX4-airspeed port +Pixhawk-airspeed port +APM1-airspeed port + + + +0.001 +meters/Volt + + +0.001 +Volts + + + +Linear +Inverted +Hyperbolic + + + +1 +centimeters + + +1 +centimeters + + + +Not Used +Pixhawk AUXOUT1 +Pixhawk AUXOUT2 +Pixhawk AUXOUT3 +Pixhawk AUXOUT4 +Pixhawk AUXOUT5 +Pixhawk AUXOUT6 +PX4 FMU Relay1 +PX4 FMU Relay2 +PX4IO Relay1 +PX4IO Relay2 +PX4IO ACC1 +PX4IO ACC2 + + + +1 +milliseconds + + + +No +Yes + + + +0 127 +1 +centimeters + + +0 127 +1 + + +m + + +m + + +m + + + + + +None +PX4-PWM + + + +0.001 + + +1 + + +1 + + +0.1 + + + +None +PX4-PWM + + + +0.001 + + + + + +Disabled +AnalogPin +RCChannelPwmValue + + + + +APM2 A0 +APM2 A1 +APM2 A13 +Pixracer +Pixhawk ADC4 +Pixhawk ADC3 + Pixhawk ADC6 +Pixhawk SBUS + + + +0 5.0 +0.01 +Volt + + +0 5.0 +0.01 +Volt + + + + + +0 2000 +Microseconds + + +0 2000 +Microseconds + + + + + +Disabled +ShowSlips +ShowOverruns + + + + +50Hz +100Hz +200Hz +250Hz +300Hz +400Hz + +True + + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + +MAVlink1 +MAVLink2 + + + + +None +MAVLink1 +MAVLink2 +Frsky D +Frsky SPort +GPS +Alexmos Gimbal Serial +SToRM32 Gimbal Serial +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +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 +Lidar +FrSky SPort Passthrough (OpenTX) +Lidar360 +Aerotenna uLanding +Pozyx Beacon + + + + +1200 +2400 +4800 +9600 +19200 +38400 +57600 +111100 +115200 +500000 +921600 +1500000 + + + + + + +Disable +Enable + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + +800 2200 +1 +pwm + + + +Normal +Reversed + + + + +Disabled +RCPassThru +Flap +Flap_auto +Aileron +mount_pan +mount_tilt +mount_roll +mount_open +camera_trigger +release +mount2_pan +mount2_tilt +mount2_roll +mount2_open +DifferentialSpoiler1 +DifferentialSpoiler2 +AileronWithInput +Elevator +ElevatorWithInput +Rudder +Flaperon1 +Flaperon2 +GroundSteering +Parachute +EPM +LandingGear +EngineRunEnable +HeliRSC +HeliTailRSC +Motor1 +Motor2 +Motor3 +Motor4 +Motor5 +Motor6 +Motor7 +Motor8 +RCIN1 +RCIN2 +RCIN3 +RCIN4 +RCIN5 +RCIN6 +RCIN7 +RCIN8 +RCIN9 +RCIN10 +RCIN11 +RCIN12 +RCIN13 +RCIN14 +RCIN15 +RCIN16 +Ignition +Choke +Starter +Throttle +TrackerYaw +TrackerPitch + + + + + + + + + + + + + + + + +Disabled +Enabled + + + +0 100 +percentage + + +1000 2000 +ms + + +0 1000 +cm/s + + +0 100 +percentage + + + + + + +seconds + + +seconds + + +seconds + + + + +0.4 1.0 +0.1 +seconds + + +0.1 10.0 +0.1 + + +0 1.0 +0.05 + + +0 0.1 +0.01 + + +0 4500 +1 + + +0 5 +0.1 +m/s + + +0.0 10.0 +0.1 + + +0.0 30.0 +0.1 +m/s + + +0.0 50.0 +0.1 +degree/(m/s) + + +0.0 4500.0 +0.1 +Centidegrees + + + + +0.1 20.0 +0.1 + + +0.1 10.0 +0.1 + + +3.0 10.0 +0.2 + + +0.1 1.0 +0.1 + + +0.0 0.5 +0.02 + + +1.0 10.0 +0.5 + + +1.0 5.0 +0.05 + + +0.5 2.0 +0.05 + + +5.0 30.0 +1.0 + + +0.0 2.0 +0.1 + + +0.1 1.0 +0.1 + + +0.0 20.0 +0.1 + + +-1 127 +1 + + +-1 100 +0.1 + + +-1.0 2.0 +0.1 + + +0 45 +1 + + +-45 0 +1 + + +0.0 2.0 +0.1 + + +1.0 5.0 +0.2 + + +0.1 1.0 +0.1 + + +-5 40 +1 + + +0.0 20.0 +0.1 +m/s + + +-2.0 2.0 +0.1 +m/s/m + + +0.1 1.0 +0.1 + + +0.0 0.5 +0.02 + + +0.0 0.5 +0.02 + + +0.1 1.0 +0.1 + + + +Disable +Enable + + + + + + +Disable +Enable + + + +1 +meters + + + + + +Disable +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + +900 2100 + + +900 2100 + + + +Disable +Chan1 +Chan3 +Chan3 +Chan4 +Chan5 +Chan6 +Chan7 +Chan8 +Chan9 +Chan10 +Chan11 +Chan12 +Chan13 +Chan14 +Chan15 +Chan16 + + + + + + +Disable +Enable + + + +0 1 + + + + +20 2000 +50 +cm/s + + +100 1000 +1 +cm + + +0 1000 +50 +cm/s + + +0 500 +10 +cm/s + + +0 2000 +50 +cm/s + + +50 500 +10 +cm/s/s + + +50 500 +10 +cm/s/s + + +500 5000 +1 +cm/s/s/s + + +100 981 +1 +cm/s/s + + +25 250 +1 +cm/s/s + + + +Disable +Enable + + + + + +0 4 +0.25 + + +0 2 +0.25 + + +0 2 +0.25 + + +0.8 1.2 +0.05 + + +0 4500 +1 + + + diff --git a/src/FirmwarePlugin/APM/APMResources.qrc b/src/FirmwarePlugin/APM/APMResources.qrc index 7e2b6a21202ea477affb22af2874629a48dd4fba..941a2a14aaa6a06d189830d5dff85059c0a7135b 100644 --- a/src/FirmwarePlugin/APM/APMResources.qrc +++ b/src/FirmwarePlugin/APM/APMResources.qrc @@ -43,10 +43,12 @@ APMParameterFactMetaData.Plane.3.3.xml APMParameterFactMetaData.Plane.3.5.xml APMParameterFactMetaData.Plane.3.7.xml + APMParameterFactMetaData.Plane.3.8.xml APMParameterFactMetaData.Copter.3.3.xml APMParameterFactMetaData.Copter.3.4.xml APMParameterFactMetaData.Copter.3.5.xml APMParameterFactMetaData.Rover.3.0.xml + APMParameterFactMetaData.Rover.3.2.xml APMParameterFactMetaData.Sub.3.4.xml CopterGeoFenceEditor.qml PlaneGeoFenceEditor.qml diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc index 33fb7fb026424141248f7b798af6b704c3141755..3c3ef9e5ef05bb093a999ac3a4a0558a77377f01 100644 --- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc @@ -67,36 +67,51 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void) setSupportedModes(supportedFlightModes); if (!_remapParamNameIntialized) { - FirmwarePlugin::remapParamNameMap_t& remap = _remapParamName[3][4]; - - remap["ATC_ANG_RLL_P"] = QStringLiteral("STB_RLL_P"); - remap["ATC_ANG_PIT_P"] = QStringLiteral("STB_PIT_P"); - remap["ATC_ANG_YAW_P"] = QStringLiteral("STB_YAW_P"); - - remap["ATC_RAT_RLL_P"] = QStringLiteral("RATE_RLL_P"); - remap["ATC_RAT_RLL_I"] = QStringLiteral("RATE_RLL_I"); - remap["ATC_RAT_RLL_IMAX"] = QStringLiteral("RATE_RLL_IMAX"); - remap["ATC_RAT_RLL_D"] = QStringLiteral("RATE_RLL_D"); - remap["ATC_RAT_RLL_FILT"] = QStringLiteral("RATE_RLL_FILT_HZ"); - - remap["ATC_RAT_PIT_P"] = QStringLiteral("RATE_PIT_P"); - remap["ATC_RAT_PIT_I"] = QStringLiteral("RATE_PIT_I"); - remap["ATC_RAT_PIT_IMAX"] = QStringLiteral("RATE_PIT_IMAX"); - remap["ATC_RAT_PIT_D"] = QStringLiteral("RATE_PIT_D"); - remap["ATC_RAT_PIT_FILT"] = QStringLiteral("RATE_PIT_FILT_HZ"); - - remap["ATC_RAT_YAW_P"] = QStringLiteral("RATE_YAW_P"); - remap["ATC_RAT_YAW_I"] = QStringLiteral("RATE_YAW_I"); - remap["ATC_RAT_YAW_IMAX"] = QStringLiteral("RATE_YAW_IMAX"); - remap["ATC_RAT_YAW_D"] = QStringLiteral("RATE_YAW_D"); - remap["ATC_RAT_YAW_FILT"] = QStringLiteral("RATE_YAW_FILT_HZ"); + FirmwarePlugin::remapParamNameMap_t& remapV3_4 = _remapParamName[3][4]; + + remapV3_4["ATC_ANG_RLL_P"] = QStringLiteral("STB_RLL_P"); + remapV3_4["ATC_ANG_PIT_P"] = QStringLiteral("STB_PIT_P"); + remapV3_4["ATC_ANG_YAW_P"] = QStringLiteral("STB_YAW_P"); + + remapV3_4["ATC_RAT_RLL_P"] = QStringLiteral("RATE_RLL_P"); + remapV3_4["ATC_RAT_RLL_I"] = QStringLiteral("RATE_RLL_I"); + remapV3_4["ATC_RAT_RLL_IMAX"] = QStringLiteral("RATE_RLL_IMAX"); + remapV3_4["ATC_RAT_RLL_D"] = QStringLiteral("RATE_RLL_D"); + remapV3_4["ATC_RAT_RLL_FILT"] = QStringLiteral("RATE_RLL_FILT_HZ"); + + remapV3_4["ATC_RAT_PIT_P"] = QStringLiteral("RATE_PIT_P"); + remapV3_4["ATC_RAT_PIT_I"] = QStringLiteral("RATE_PIT_I"); + remapV3_4["ATC_RAT_PIT_IMAX"] = QStringLiteral("RATE_PIT_IMAX"); + remapV3_4["ATC_RAT_PIT_D"] = QStringLiteral("RATE_PIT_D"); + remapV3_4["ATC_RAT_PIT_FILT"] = QStringLiteral("RATE_PIT_FILT_HZ"); + + remapV3_4["ATC_RAT_YAW_P"] = QStringLiteral("RATE_YAW_P"); + remapV3_4["ATC_RAT_YAW_I"] = QStringLiteral("RATE_YAW_I"); + remapV3_4["ATC_RAT_YAW_IMAX"] = QStringLiteral("RATE_YAW_IMAX"); + remapV3_4["ATC_RAT_YAW_D"] = QStringLiteral("RATE_YAW_D"); + remapV3_4["ATC_RAT_YAW_FILT"] = QStringLiteral("RATE_YAW_FILT_HZ"); + + FirmwarePlugin::remapParamNameMap_t& remapV3_5 = _remapParamName[3][5]; + + remapV3_5["SERVO5_FUNCTION"] = QStringLiteral("RC5_FUNCTION"); + remapV3_5["SERVO6_FUNCTION"] = QStringLiteral("RC6_FUNCTION"); + remapV3_5["SERVO7_FUNCTION"] = QStringLiteral("RC7_FUNCTION"); + remapV3_5["SERVO8_FUNCTION"] = QStringLiteral("RC8_FUNCTION"); + remapV3_5["SERVO9_FUNCTION"] = QStringLiteral("RC9_FUNCTION"); + remapV3_5["SERVO10_FUNCTION"] = QStringLiteral("RC10_FUNCTION"); + remapV3_5["SERVO11_FUNCTION"] = QStringLiteral("RC11_FUNCTION"); + remapV3_5["SERVO12_FUNCTION"] = QStringLiteral("RC12_FUNCTION"); + remapV3_5["SERVO13_FUNCTION"] = QStringLiteral("RC13_FUNCTION"); + remapV3_5["SERVO14_FUNCTION"] = QStringLiteral("RC14_FUNCTION"); + + _remapParamNameIntialized = true; } } int ArduCopterFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const { - // Remapping supports up to 3.4 - return majorVersionNumber == 3 ? 4: Vehicle::versionNotSetValue; + // Remapping supports up to 3.5 + return majorVersionNumber == 3 ? 5 : Vehicle::versionNotSetValue; } bool ArduCopterFirmwarePlugin::isCapable(const Vehicle* vehicle, FirmwareCapabilities capabilities) diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc index da2380d4f5a4e0b379a71bfda2134166584589a2..88a380a1ba39243388e0855fd1dc50ab73faa6fc 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.cc @@ -7,12 +7,11 @@ * ****************************************************************************/ - -/// @file -/// @author Pritam Ghanghas - #include "ArduPlaneFirmwarePlugin.h" +bool ArduPlaneFirmwarePlugin::_remapParamNameIntialized = false; +FirmwarePlugin::remapParamNameMajorVersionMap_t ArduPlaneFirmwarePlugin::_remapParamName; + APMPlaneMode::APMPlaneMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) { @@ -63,6 +62,29 @@ ArduPlaneFirmwarePlugin::ArduPlaneFirmwarePlugin(void) supportedFlightModes << APMPlaneMode(APMPlaneMode::QLAND ,true); supportedFlightModes << APMPlaneMode(APMPlaneMode::QRTL ,true); setSupportedModes(supportedFlightModes); + + if (!_remapParamNameIntialized) { + FirmwarePlugin::remapParamNameMap_t& remapV3_8 = _remapParamName[3][8]; + + remapV3_8["SERVO5_FUNCTION"] = QStringLiteral("RC5_FUNCTION"); + remapV3_8["SERVO6_FUNCTION"] = QStringLiteral("RC6_FUNCTION"); + remapV3_8["SERVO7_FUNCTION"] = QStringLiteral("RC7_FUNCTION"); + remapV3_8["SERVO8_FUNCTION"] = QStringLiteral("RC8_FUNCTION"); + remapV3_8["SERVO9_FUNCTION"] = QStringLiteral("RC9_FUNCTION"); + remapV3_8["SERVO10_FUNCTION"] = QStringLiteral("RC10_FUNCTION"); + remapV3_8["SERVO11_FUNCTION"] = QStringLiteral("RC11_FUNCTION"); + remapV3_8["SERVO12_FUNCTION"] = QStringLiteral("RC12_FUNCTION"); + remapV3_8["SERVO13_FUNCTION"] = QStringLiteral("RC13_FUNCTION"); + remapV3_8["SERVO14_FUNCTION"] = QStringLiteral("RC14_FUNCTION"); + + _remapParamNameIntialized = true; + } +} + +int ArduPlaneFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const +{ + // Remapping supports up to 3.8 + return majorVersionNumber == 3 ? 8 : Vehicle::versionNotSetValue; } QString ArduPlaneFirmwarePlugin::takeControlFlightMode(void) diff --git a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h index 8067354b9ab802043e7894fa003579e0e56f9485..3ec63a61adccd076e3ef781458c470a6f72383da 100644 --- a/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduPlaneFirmwarePlugin.h @@ -58,6 +58,12 @@ public: // Overrides from FirmwarePlugin QString offlineEditingParamFile(Vehicle* vehicle) final { Q_UNUSED(vehicle); return QStringLiteral(":/FirmwarePlugin/APM/Plane.OfflineEditing.params"); } QString takeControlFlightMode(void) final; + const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; } + int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final; + +private: + static bool _remapParamNameIntialized; + static FirmwarePlugin::remapParamNameMajorVersionMap_t _remapParamName; }; #endif diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc index 5c4a57599e6e40a7f532cb0964decc0b4a9b72df..bbb7ed961e1155518bd6d6a17c87d2f326a768f2 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.cc @@ -7,12 +7,11 @@ * ****************************************************************************/ - -/// @file -/// @author Pritam Ghanghas - #include "ArduRoverFirmwarePlugin.h" +bool ArduRoverFirmwarePlugin::_remapParamNameIntialized = false; +FirmwarePlugin::remapParamNameMajorVersionMap_t ArduRoverFirmwarePlugin::_remapParamName; + APMRoverMode::APMRoverMode(uint32_t mode, bool settable) : APMCustomMode(mode, settable) { @@ -41,4 +40,28 @@ ArduRoverFirmwarePlugin::ArduRoverFirmwarePlugin(void) supportedFlightModes << APMRoverMode(APMRoverMode::GUIDED ,true); supportedFlightModes << APMRoverMode(APMRoverMode::INITIALIZING ,false); setSupportedModes(supportedFlightModes); + + if (!_remapParamNameIntialized) { + FirmwarePlugin::remapParamNameMap_t& remapV3_2 = _remapParamName[3][2]; + + remapV3_2["SERVO5_FUNCTION"] = QStringLiteral("RC5_FUNCTION"); + remapV3_2["SERVO6_FUNCTION"] = QStringLiteral("RC6_FUNCTION"); + remapV3_2["SERVO7_FUNCTION"] = QStringLiteral("RC7_FUNCTION"); + remapV3_2["SERVO8_FUNCTION"] = QStringLiteral("RC8_FUNCTION"); + remapV3_2["SERVO9_FUNCTION"] = QStringLiteral("RC9_FUNCTION"); + remapV3_2["SERVO10_FUNCTION"] = QStringLiteral("RC10_FUNCTION"); + remapV3_2["SERVO11_FUNCTION"] = QStringLiteral("RC11_FUNCTION"); + remapV3_2["SERVO12_FUNCTION"] = QStringLiteral("RC12_FUNCTION"); + remapV3_2["SERVO13_FUNCTION"] = QStringLiteral("RC13_FUNCTION"); + remapV3_2["SERVO14_FUNCTION"] = QStringLiteral("RC14_FUNCTION"); + + _remapParamNameIntialized = true; + } } + +int ArduRoverFirmwarePlugin::remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const +{ + // Remapping supports up to 3.2 + return majorVersionNumber == 3 ? 2 : Vehicle::versionNotSetValue; +} + diff --git a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h index 78a43877e55ee5ab557dfcaff61b314a5029ec78..88e5e5272560a50678b4c2dd696e09a44e5348f9 100644 --- a/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h +++ b/src/FirmwarePlugin/APM/ArduRoverFirmwarePlugin.h @@ -49,6 +49,14 @@ class ArduRoverFirmwarePlugin : public APMFirmwarePlugin public: ArduRoverFirmwarePlugin(void); + + // Overrides from FirmwarePlugin + const FirmwarePlugin::remapParamNameMajorVersionMap_t& paramNameRemapMajorVersionMap(void) const final { return _remapParamName; } + int remapParamNameHigestMinorVersionNumber(int majorVersionNumber) const final; + +private: + static bool _remapParamNameIntialized; + static FirmwarePlugin::remapParamNameMajorVersionMap_t _remapParamName; }; #endif