diff --git a/ChangeLog.md b/ChangeLog.md
index a93f9093f7f2104bb4ed3c5c675c139074665c59..8949f05135d46d10676e2018aa2d71fae3a1f653 100644
--- a/ChangeLog.md
+++ b/ChangeLog.md
@@ -6,6 +6,7 @@ Note: This file only contains high level features or important fixes.
### 3.6.0 - Daily Build
+* ArduCopter: Handle 3.7 parameter name change from CH#_OPT to RC#_OPTION.
* Improved support for flashing/connecting to ChibiOS bootloaders boards.
* Making the camera API available to all firmwares, not just PX4.
* ArduPilot: Support configurable mavlink stream rates. Available from Settings/Mavlink page.
diff --git a/src/AutoPilotPlugins/APM/APMTuningComponent.cc b/src/AutoPilotPlugins/APM/APMTuningComponent.cc
index 5406ef495bd2a855ed80759a54108262c73d6855..a51b0f634e93680cda912ce78072aef2e5a0c998 100644
--- a/src/AutoPilotPlugins/APM/APMTuningComponent.cc
+++ b/src/AutoPilotPlugins/APM/APMTuningComponent.cc
@@ -60,10 +60,7 @@ QUrl APMTuningComponent::setupSource(void) const
case MAV_TYPE_HEXAROTOR:
case MAV_TYPE_OCTOROTOR:
case MAV_TYPE_TRICOPTER:
- // Older firmwares do not have CH9_OPT, we don't support Tuning on older firmwares
- if (_vehicle->parameterManager()->parameterExists(-1, QStringLiteral("CH9_OPT"))) {
- qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
- }
+ qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentCopter.qml");
break;
case MAV_TYPE_SUBMARINE:
qmlFile = QStringLiteral("qrc:/qml/APMTuningComponentSub.qml");
diff --git a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
index bfe22008f76eae6c413e0a8a83466a8471f3bfd7..50b9f0aa10fc890895ab9a79d00de718684b72c6 100644
--- a/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
+++ b/src/AutoPilotPlugins/APM/APMTuningComponentCopter.qml
@@ -43,12 +43,12 @@ SetupPage {
property Fact _rateClimbP: controller.getParameterFact(-1, "r.PSC_ACCZ_P")
property Fact _rateClimbI: controller.getParameterFact(-1, "r.PSC_ACCZ_I")
- property Fact _ch7Opt: controller.getParameterFact(-1, "CH7_OPT")
- property Fact _ch8Opt: controller.getParameterFact(-1, "CH8_OPT")
- property Fact _ch9Opt: controller.getParameterFact(-1, "CH9_OPT")
- property Fact _ch10Opt: controller.getParameterFact(-1, "CH10_OPT")
- property Fact _ch11Opt: controller.getParameterFact(-1, "CH11_OPT")
- property Fact _ch12Opt: controller.getParameterFact(-1, "CH12_OPT")
+ property Fact _ch7Opt: controller.getParameterFact(-1, "r.RC7_OPTION")
+ property Fact _ch8Opt: controller.getParameterFact(-1, "r.RC8_OPTION")
+ property Fact _ch9Opt: controller.getParameterFact(-1, "r.RC9_OPTION")
+ property Fact _ch10Opt: controller.getParameterFact(-1, "r.RC10_OPTION")
+ property Fact _ch11Opt: controller.getParameterFact(-1, "r.RC11_OPTION")
+ property Fact _ch12Opt: controller.getParameterFact(-1, "r.RC12_OPTION")
readonly property int _firstOptionChannel: 7
readonly property int _lastOptionChannel: 12
@@ -84,12 +84,12 @@ SetupPage {
calcAutoTuneChannel()
}
- /// The AutoTune switch is stored in one of the CH#_OPT parameters. We need to loop through those
+ /// The AutoTune switch is stored in one of the RC#_OPTION parameters. We need to loop through those
/// to find them and setup the ui accordindly.
function calcAutoTuneChannel() {
_autoTuneSwitchChannelIndex = 0
for (var channel=_firstOptionChannel; channel<=_lastOptionChannel; channel++) {
- var optionFact = controller.getParameterFact(-1, "CH" + channel + "_OPT")
+ var optionFact = controller.getParameterFact(-1, "r.RC" + channel + "_OPTION")
if (optionFact.value == _autoTuneOption) {
_autoTuneSwitchChannelIndex = channel - _firstOptionChannel + 1
break
@@ -101,7 +101,7 @@ SetupPage {
function setChannelAutoTuneOption(channel) {
// First clear any previous settings for AutTune
for (var optionChannel=_firstOptionChannel; optionChannel<=_lastOptionChannel; optionChannel++) {
- var optionFact = controller.getParameterFact(-1, "CH" + optionChannel + "_OPT")
+ var optionFact = controller.getParameterFact(-1, "r.RC" + optionChannel + "_OPTION")
if (optionFact.value == _autoTuneOption) {
optionFact.value = 0
}
@@ -109,7 +109,7 @@ SetupPage {
// Now set the function into the new channel
if (channel != 0) {
- var optionFact = controller.getParameterFact(-1, "CH" + channel + "_OPT")
+ var optionFact = controller.getParameterFact(-1, "r.RC" + channel + "_OPTION")
optionFact.value = _autoTuneOption
}
}
@@ -368,7 +368,7 @@ SetupPage {
QGCLabel {
anchors.baseline: optCombo.baseline
- text: qsTr("Channel Option 6 (Tuning):")
+ text: qsTr("RC Channel 6 Option (Tuning):")
//color: controller.channelOptionEnabled[modelData] ? "yellow" : qgcPal.text
}
diff --git a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
index c9b52dc2ba2f042c44a51fea0907b83d70a5ebd6..76fcda2bbae8b3c754c5a6f0715fbed5d25d19ee 100644
--- a/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/APMFirmwarePlugin.cc
@@ -807,6 +807,9 @@ QString APMFirmwarePlugin::internalParameterMetaDataFile(Vehicle* vehicle)
case MAV_TYPE_TRICOPTER:
case MAV_TYPE_COAXIAL:
case MAV_TYPE_HELICOPTER:
+ if (vehicle->versionCompare(3, 7, 0) >= 0) { // 3.7.0 and higher
+ return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml");
+ }
if (vehicle->versionCompare(3, 6, 0) >= 0) { // 3.6.0 and higher
return QStringLiteral(":/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.6.xml");
}
diff --git a/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml
new file mode 100644
index 0000000000000000000000000000000000000000..195ecb7a786929d6b7b1253b4e47038c11408dfd
--- /dev/null
+++ b/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml
@@ -0,0 +1,14791 @@
+
+
+
+
+
+
+True
+
+
+1 255
+
+
+
+Mission Planner and DroidPlanner
+ AP Planner 2
+
+
+
+0 10
+.5
+Hz
+hertz
+
+
+0.0 1000.0
+10
+cm
+centimeters
+
+
+0 500
+10
+
+
+0:Feedback from mid stick,1:High throttle cancels landing,2:Disarm on land detection
+
+None
+Feedback from mid stick
+High throttle cancels landing
+Disarm on land detection
+
+
+
+0 30
+1
+s
+seconds
+
+
+0:Roll,1:Pitch,2:Yaw
+
+None
+Roll
+Pitch
+Yaw
+
+
+
+200 8000
+1
+cm
+centimeters
+
+
+0.5 10.0
+
+Disabled
+Shallow
+Steep
+
+.1
+
+
+0 2000
+50
+cm/s
+centimeters per second
+
+
+-1 1000
+1
+cm
+centimeters
+
+
+0 3000
+10
+cm
+centimeters
+
+
+0 60000
+1000
+ms
+milliseconds
+
+
+0.01 2.0
+0.01
+
+
+
+Disabled
+Enabled always RTL
+Enabled Continue with Mission in Auto Mode
+Enabled always SmartRTL or RTL
+Enabled always SmartRTL or Land
+
+
+
+100 900
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Mode1
+Mode2
+Mode1+2
+Mode3
+Mode1+3
+Mode2+3
+Mode1+2+3
+Mode4
+Mode1+4
+Mode2+4
+Mode1+2+4
+Mode3+4
+Mode1+3+4
+Mode2+3+4
+Mode1+2+3+4
+Mode5
+Mode1+5
+Mode2+5
+Mode1+2+5
+Mode3+5
+Mode1+3+5
+Mode2+3+5
+Mode1+2+3+5
+Mode4+5
+Mode1+4+5
+Mode2+4+5
+Mode1+2+4+5
+Mode3+4+5
+Mode1+3+4+5
+Mode2+3+4+5
+Mode1+2+3+4+5
+Mode6
+Mode1+6
+Mode2+6
+Mode1+2+6
+Mode3+6
+Mode1+3+6
+Mode2+3+6
+Mode1+2+3+6
+Mode4+6
+Mode1+4+6
+Mode2+4+6
+Mode1+2+4+6
+Mode3+4+6
+Mode1+3+4+6
+Mode2+3+4+6
+Mode1+2+3+4+6
+Mode5+6
+Mode1+5+6
+Mode2+5+6
+Mode1+2+5+6
+Mode3+5+6
+Mode1+3+5+6
+Mode2+3+5+6
+Mode1+2+3+5+6
+Mode4+5+6
+Mode1+4+5+6
+Mode2+4+5+6
+Mode1+2+4+5+6
+Mode3+4+5+6
+Mode1+3+4+5+6
+Mode2+3+4+5+6
+Mode1+2+3+4+5+6
+
+
+
+
+Never change yaw
+Face next waypoint
+Face next waypoint except RTL
+Face along GPS course
+
+
+
+30 200
+10
+cm/s
+centimeters per second
+
+
+0 500
+10
+cm/s
+centimeters per second
+
+
+50 500
+10
+cm/s
+centimeters per second
+
+
+50 500
+10
+cm/s/s
+centimeters per square second
+
+
+
+Disabled
+Enabled always RTL
+Enabled Continue with Mission in Auto Mode
+Enabled always Land
+Enabled always SmartRTL or RTL
+Enabled always SmartRTL or Land
+
+
+
+925 1100
+1
+PWM
+PWM in microseconds
+
+
+0 300
+1
+PWM
+PWM in microseconds
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+Smart_RTL
+FlowHold
+Follow
+ZigZag
+
+
+
+
+Disabled
+Channel5
+Channel6
+Channel7
+Channel8
+
+
+
+
+
+0:ATTITUDE_FAST,1:ATTITUDE_MED,2:GPS,3:PM,4:CTUN,5:NTUN,6:RCIN,7:IMU,8:CMD,9:CURRENT,10:RCOUT,11:OPTFLOW,12:PID,13:COMPASS,14:INAV,15:CAMERA,17:MOTBATT,18:IMU_FAST,19:IMU_RAW
+
+Default
+Default+RCIN
+Default+IMU
+Default+Motors
+NearlyAll-AC315
+NearlyAll
+All+FastATT
+All+MotBatt
+All+FastIMU
+All+FastIMU+PID
+All+FullIMU
+Disabled
+
+
+
+
+Normal Start-up
+Start-up in ESC Calibration mode if throttle high
+Start-up in ESC Calibration mode regardless of throttle
+Start-up and automatically calibrate ESCs
+Disabled
+
+
+
+
+None
+Stab Roll/Pitch kP
+Rate Roll/Pitch kP
+Rate Roll/Pitch kI
+Rate Roll/Pitch kD
+Stab Yaw kP
+Rate Yaw kP
+Rate Yaw kD
+Rate Yaw Filter
+Motor Yaw Headroom
+AltHold kP
+Throttle Rate kP
+Throttle Accel kP
+Throttle Accel kI
+Throttle Accel kD
+Loiter Pos kP
+Velocity XY kP
+Velocity XY kI
+WP Speed
+Acro RollPitch kP
+Acro Yaw kP
+RC Feel
+Heli Ext Gyro
+Declination
+Circle Rate
+RangeFinder Gain
+Rate Pitch kP
+Rate Pitch kI
+Rate Pitch kD
+Rate Roll kP
+Rate Roll kI
+Rate Roll kD
+Rate Pitch FF
+Rate Roll FF
+Rate Yaw FF
+Winch
+
+
+
+0 32767
+
+
+0 32767
+
+
+
+Plus
+X
+V
+H
+V-Tail
+A-Tail
+Y6B
+Y6F
+BetaFlightX
+DJIX
+ClockwiseX
+
+True
+
+
+0 127
+s
+seconds
+
+
+1000 8000
+cdeg
+centidegrees
+
+
+4 12
+deg/s
+degrees per second
+
+
+2000 4500
+cdeg
+centidegrees
+
+
+
+No repositioning
+Repositioning
+
+
+
+
+Land
+AltHold
+Land even in Stabilize
+
+
+
+0.6:Strict, 0.8:Default, 1.0:Relaxed
+
+
+
+Disabled
+Enabled
+
+
+
+50 490
+1
+Hz
+hertz
+
+
+1 10
+
+
+1 10
+
+
+0 3
+0.1
+
+
+0 3
+0.1
+
+
+
+Disabled
+Leveling
+Leveling and Limited
+
+
+
+-0.5 1.0
+
+Disabled
+Very Low
+Low
+Medium
+High
+Very High
+
+
+
+
+Stopped
+Running
+
+
+
+
+Do Not Use in RTL and Land
+Use in RTL and Land
+
+
+
+0 5
+
+
+
+Auto
+Guided
+LOITER
+RTL
+Land
+Brake
+Throw
+
+
+
+
+Upward Throw
+Drop
+
+
+
+
+Disabled
+Enabled
+
+
+
+0:ADSBMavlinkProcessing,1:DevOptionVFR_HUDRelativeAlt
+
+
+-0.5 1.0
+
+Disabled
+Very Low
+Low
+Medium
+High
+Very High
+
+
+
+0 1
+
+
+
+NotEnforced
+Enforced
+
+
+
+
+Undefined
+Quad
+Hexa
+Octa
+OctaQuad
+Y6
+Heli
+Tri
+SingleCopter
+CoaxCopter
+BiCopter
+Heli_Dual
+DodecaHexa
+HeliQuad
+
+True
+
+
+50 500
+10
+cm/s
+centimeters per second
+
+
+100 10000
+10
+cm
+centimeters
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Object Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+1 100
+
+
+0 100000
+m
+meters
+
+
+-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
+
+
+
+0 7777
+octal
+octal
+
+
+0:UAT_in,1:1090ES_in,2:UAT_out,3:1090ES_out
+
+Unknown
+Rx UAT only
+Rx UAT and 1090ES
+Rx&Tx UAT and 1090ES
+
+
+
+0 32767
+m
+meters
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+m
+meters
+
+
+m
+meters
+
+
+mbar
+millibar
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+s
+seconds
+
+
+
+
+0.0 1.0
+.01
+
+
+
+Disabled
+Enabled
+
+
+
+0.1 0.4
+.01
+
+
+0.1 0.4
+.01
+
+
+0 127
+1
+m/s
+meters per second
+
+
+-0.1745 +0.1745
+0.01
+rad
+radians
+
+
+-0.1745 +0.1745
+0.01
+rad
+radians
+
+
+-0.1745 +0.1745
+0.01
+rad
+radians
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw90
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw135
+Pitch90
+Pitch270
+Pitch180Yaw90
+Pitch180Yaw270
+Roll90Pitch90
+Roll180Pitch90
+Roll270Pitch90
+Roll90Pitch180
+Roll270Pitch180
+Roll90Pitch270
+Roll180Pitch270
+Roll270Pitch270
+Roll90Pitch180Yaw90
+Roll90Yaw270
+Yaw293Pitch68Roll180
+Pitch315
+Roll90Pitch315
+Custom
+
+
+
+0.001 0.5
+.01
+
+
+0 10
+1
+
+
+
+Disabled
+Enable EKF2
+Enable EKF3
+
+
+
+-180 180
+1
+deg
+degrees
+
+
+-180 180
+1
+deg
+degrees
+
+
+-180 180
+1
+deg
+degrees
+
+
+
+
+
+Disabled
+THR_MIN PWM when disarmed
+0 PWM when disarmed
+
+
+
+0:All,1:Barometer,2:Compass,3:GPS lock,4:INS,5:Parameters,6:RC Channels,7:Board voltage,8:Battery Level,9:Airspeed,10:Logging Available,11:Hardware safety switch,12:GPS Configuration,13:System
+
+None
+All
+Barometer
+Compass
+GPS Lock
+INS(INertial Sensors - accels & gyros)
+Parameters(unused)
+RC Channels
+Board voltage
+Battery Level
+Airspeed
+LoggingAvailable
+Hardware safety switch
+GPS configuration
+System
+
+
+
+0.25 3.0
+m/s/s
+meters per square second
+
+
+
+Disabled
+ArmingOnly
+ArmOrDisarm
+
+
+
+0:Land,1:VTOL Land,2:DO_LAND_START,3:Takeoff,4:VTOL Takeoff,5:Rallypoint
+
+
+
+
+500 18000
+100
+cdeg/s
+centidegrees per second
+
+
+0 72000
+
+Disabled
+VerySlow
+Slow
+Medium
+Fast
+
+1000
+cdeg/s/s
+centidegrees per square second
+
+
+
+Disabled
+Enabled
+
+
+
+0 180000
+
+Disabled
+VerySlow
+Slow
+Medium
+Fast
+
+1000
+cdeg/s/s
+centidegrees per square second
+
+
+0 180000
+
+Disabled
+VerySlow
+Slow
+Medium
+Fast
+
+1000
+cdeg/s/s
+centidegrees per square second
+
+
+
+Disabled
+Enabled
+
+
+
+0.0 12.000
+
+
+0.0 12.000
+
+
+0.0 6.000
+
+
+0.5 10.0
+
+
+0 1080
+
+Disabled
+Slow
+Medium
+Fast
+
+1
+deg/s
+degrees per second
+
+
+0 1080
+
+Disabled
+Slow
+Medium
+Fast
+
+1
+deg/s
+degrees per second
+
+
+0 1080
+
+Disabled
+Slow
+Medium
+Fast
+
+1
+deg/s
+degrees per second
+
+
+0 1
+0.5:Very Soft, 0.2:Soft, 0.15:Medium, 0.1:Crisp, 0.05:Very Crisp
+0.01
+s
+seconds
+
+
+0.05 0.5
+0.005
+
+
+0.01 2.0
+0.01
+
+
+0 1
+0.01
+%
+percent
+
+
+0.0 0.02
+0.001
+
+
+0 0.5
+0.001
+
+
+1 100
+1
+Hz
+hertz
+
+
+0.05 0.50
+0.005
+
+
+0.01 2.0
+0.01
+
+
+0 1
+0.01
+%
+percent
+
+
+0.0 0.02
+0.001
+
+
+0 0.5
+0.001
+
+
+1 100
+1
+Hz
+hertz
+
+
+0.10 2.50
+0.005
+
+
+0.010 1.0
+0.01
+
+
+0 1
+0.01
+%
+percent
+
+
+0.000 0.02
+0.001
+
+
+0 0.5
+0.001
+
+
+1 10
+1
+Hz
+hertz
+
+
+0.1 0.25
+
+
+0.5 0.9
+
+
+0.1 0.9
+
+
+0 1000
+cdeg
+centidegrees
+
+
+0.08 0.35
+0.005
+
+
+0.01 0.6
+0.01
+
+
+0 1
+0.01
+
+
+0.001 0.03
+0.001
+
+
+0 0.5
+0.001
+
+
+1 20
+1
+Hz
+hertz
+
+
+0.08 0.35
+0.005
+
+
+0.01 0.6
+0.01
+
+
+0 1
+0.01
+
+
+0.001 0.03
+0.001
+
+
+0 0.5
+0.001
+
+
+1 20
+1
+Hz
+hertz
+
+
+0.180 0.60
+0.005
+
+
+0.01 0.06
+0.01
+
+
+0 1
+0.01
+
+
+0.000 0.02
+0.001
+
+
+0 0.5
+0.001
+
+
+1 20
+1
+Hz
+hertz
+
+
+
+Disabled
+Enabled
+
+
+
+
+
+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
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Remain in AVOID_ADSB
+Resume previous flight mode
+RTL
+Resume if AUTO else Loiter
+
+
+
+
+
+s
+seconds
+
+
+s
+seconds
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+
+0:StopAtFence,1:UseProximitySensor,2:StopAtBeaconFence
+
+None
+StopAtFence
+UseProximitySensor
+StopAtFence and UseProximitySensor
+StopAtBeaconFence
+All
+
+
+
+0 4500
+cdeg
+centidegrees
+
+
+1 30
+m
+meters
+
+
+1 10
+m
+meters
+
+
+
+Slide
+Stop
+
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+Disabled
+Analog Voltage Only
+Analog Voltage and Current
+Solo
+Bebop
+SMBus-Maxell
+UAVCAN-BatteryInfo
+BLHeli ESC
+SumOfFollowing
+FuelFlow
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+Disabled
+Pixhawk/Pixracer/Navio2/Pixhawk2_PM1
+Pixhawk2_PM2
+PX4-v1
+
+True
+
+
+
+
+A/V
+ampere per volt
+
+
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+1
+W
+watt
+
+
+
+
+0 120
+1
+s
+seconds
+
+
+
+Raw Voltage
+Sag Compensated Voltage
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+
+None
+Land
+RTL
+SmartRTL or RTL
+SmartRTL or Land
+Terminate
+
+
+
+0.1
+V
+volt
+
+
+50
+mAh
+milliampere hour
+
+
+
+
+
+None
+Pozyx
+Marvelmind
+
+
+
+-90 90
+0.000001
+deg
+degrees
+
+
+-180 180
+0.000001
+deg
+degrees
+
+
+0 10000
+1
+m
+meters
+
+
+-180 +180
+1
+deg
+degrees
+
+
+
+
+
+No PWMs
+One PWMs
+Two PWMs
+Three PWMs
+Four PWMs
+Five PWMs
+Six PWMs
+Seven PWMs
+Eight PWMs
+
+True
+
+
+
+Disabled
+Enabled
+Auto
+
+True
+
+
+
+Disabled
+Enabled
+Auto
+
+True
+
+
+
+Disabled
+Enabled
+
+True
+
+
+
+Disabled
+50Hz
+75Hz
+100Hz
+150Hz
+200Hz
+250Hz
+300Hz
+
+True
+
+
+-32768 32767
+
+
+0:Ch1,1:Ch2,2:Ch3,3:Ch4,4:Ch5,5:Ch6,6:Ch7,7:Ch8,8:Ch9,9:Ch10,10:Ch11,11:Ch12,12:Ch13,13:Ch14
+
+Disabled
+Enabled
+
+True
+
+
+-1 80
+degC
+degrees Celsius
+
+
+
+AUTO
+PX4V1
+Pixhawk
+Cube/Pixhawk2
+Pixracer
+PixhawkMini
+Pixhawk2Slim
+VRBrain 5.1
+VRBrain 5.2
+VR Micro Brain 5.1
+VR Micro Brain 5.2
+VRBrain Core 1.0
+VRBrain 5.4
+Intel Aero FC
+AUAV2.1
+
+True
+
+
+
+Disabled
+Enabled
+
+True
+
+
+0:ActiveForSafetyEnable,1:ActiveForSafetyDisable,2:ActiveWhenArmed,3:Force safety on when the aircraft disarms
+
+
+4.0 5.5
+0.1
+V
+volt
+
+
+3.3 12.0
+0.1
+V
+volt
+
+
+0 32
+1
+
+
+
+
+
+None
+CYRF6936
+
+
+
+
+Auto
+DSM2
+DSMX
+
+
+
+0 4
+
+
+
+NotDisabled
+Disabled
+
+
+
+0 16
+
+
+0 16
+
+
+
+Disabled
+Enabled
+
+
+
+1 8
+
+
+
+Disabled
+MinChannel
+MidChannel
+MaxChannel
+MinChannelCW
+MidChannelCW
+MaxChannelCW
+
+
+
+
+Mode1
+Mode2
+
+
+
+
+Disabled
+TestChan1
+TestChan2
+TestChan3
+TestChan4
+TestChan5
+TestChan6
+TestChan7
+TestChan8
+
+
+
+0 16
+
+
+0 16
+
+
+1 8
+
+
+0 40
+
+
+0 120
+
+
+0 31
+
+
+
+
+0:GPS,1:MAVLINK_SYSTEM_TIME,2:HW
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+
+
+
+
+Disabled
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+
+
+
+
+Disabled
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+
+
+
+
+Disabled
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+
+
+
+0 3600
+
+
+
+
+
+Servo
+Relay
+
+
+
+0 50
+ds
+deciseconds
+
+
+1000 2000
+PWM
+PWM in microseconds
+
+
+1000 2000
+PWM
+PWM in microseconds
+
+
+0 1000
+m
+meters
+
+
+
+Low
+High
+
+
+
+0 10000
+ms
+milliseconds
+
+
+0 180
+deg
+degrees
+
+
+
+Disabled
+AUX1
+AUX2
+AUX3
+AUX4
+AUX5
+AUX6
+
+True
+
+
+
+TriggerLow
+TriggerHigh
+
+
+
+
+Always
+Only when in AUTO
+
+
+
+
+Default
+BMMCC
+
+
+
+
+
+
+Disabled
+UAVCAN
+KDECAN
+ToshibaCAN
+
+True
+
+
+
+
+
+
+
+
+1 250
+
+
+0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
+
+
+0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16
+
+
+1 200
+Hz
+hertz
+
+
+
+
+
+Disabled
+UAVCAN
+KDECAN
+ToshibaCAN
+
+True
+
+
+
+
+
+
+
+
+1 250
+
+
+0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
+
+
+0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16
+
+
+1 200
+Hz
+hertz
+
+
+
+
+
+Disabled
+UAVCAN
+KDECAN
+ToshibaCAN
+
+True
+
+
+
+
+
+
+
+
+1 250
+
+
+0: Servo 1, 1: Servo 2, 2: Servo 3, 3: Servo 4, 4: Servo 5, 5: Servo 6, 6: Servo 7, 7: Servo 8, 8: Servo 9, 9: Servo 10, 10: Servo 11, 11: Servo 12, 12: Servo 13, 13: Servo 14, 14: Servo 15
+
+
+0: ESC 1, 1: ESC 2, 2: ESC 3, 3: ESC 4, 4: ESC 5, 5: ESC 6, 6: ESC 7, 7: ESC 8, 8: ESC 9, 9: ESC 10, 10: ESC 11, 11: ESC 12, 12: ESC 13, 13: ESC 14, 14: ESC 15, 15: ESC 16
+
+
+1 200
+Hz
+hertz
+
+
+
+
+
+Disabled
+First driver
+Second driver
+
+True
+
+
+10000 1000000
+
+
+
+Disabled
+Major messages
+All messages
+
+
+
+
+
+
+Disabled
+First driver
+Second driver
+
+True
+
+
+10000 1000000
+
+
+
+Disabled
+Major messages
+All messages
+
+
+
+
+
+
+Disabled
+First driver
+Second driver
+
+True
+
+
+10000 1000000
+
+
+
+Disabled
+Major messages
+All messages
+
+
+
+
+
+
+Disabled
+First driver
+Second driver
+
+True
+
+
+
+Disabled
+Serial0
+Serial1
+Serial2
+Serial3
+Serial4
+Serial5
+Serial6
+
+
+
+0 32767
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+First Relay
+Second Relay
+Third Relay
+Fourth Relay
+Servo
+
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+0 32000
+1
+m
+meters
+
+
+0 5000
+1
+ms
+milliseconds
+
+
+
+
+0 10000
+100
+cm
+centimeters
+
+
+-90 90
+1
+deg/s
+degrees per second
+
+
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-3.142 3.142
+0.01
+rad
+radians
+
+
+
+Disabled
+Internal-Learning
+EKF-Learning
+InFlight-Learning
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Use Throttle
+Use Current
+
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw90
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw135
+Pitch90
+Pitch270
+Pitch180Yaw90
+Pitch180Yaw270
+Roll90Pitch90
+Roll180Pitch90
+Roll270Pitch90
+Roll90Pitch180
+Roll270Pitch180
+Roll90Pitch270
+Roll180Pitch270
+Roll270Pitch270
+Roll90Pitch180Yaw90
+Roll90Yaw270
+Yaw293Pitch68Roll180
+Pitch315
+Roll90Pitch315
+
+
+
+
+Internal
+External
+ForcedExternal
+
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+
+FirstCompass
+SecondCompass
+ThirdCompass
+
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-400 400
+1
+mGauss
+milligauss
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+-1000 1000
+1
+mGauss/A
+milligauss per ampere
+
+
+True
+
+
+True
+
+
+True
+
+
+
+Disabled
+Enabled
+
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw90
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw135
+Pitch90
+Pitch270
+Pitch180Yaw90
+Pitch180Yaw270
+Roll90Pitch90
+Roll180Pitch90
+Roll270Pitch90
+Roll90Pitch180
+Roll270Pitch180
+Roll90Pitch270
+Roll180Pitch270
+Roll270Pitch270
+Roll90Pitch180Yaw90
+Roll90Yaw270
+Yaw293Pitch68Roll180
+Pitch315
+Roll90Pitch315
+
+
+
+
+Internal
+External
+ForcedExternal
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+None
+Yaw45
+Yaw90
+Yaw135
+Yaw180
+Yaw225
+Yaw270
+Yaw315
+Roll180
+Roll180Yaw45
+Roll180Yaw90
+Roll180Yaw135
+Pitch180
+Roll180Yaw225
+Roll180Yaw270
+Roll180Yaw315
+Roll90
+Roll90Yaw45
+Roll90Yaw90
+Roll90Yaw135
+Roll270
+Roll270Yaw45
+Roll270Yaw90
+Roll270Yaw135
+Pitch90
+Pitch270
+Pitch180Yaw90
+Pitch180Yaw270
+Roll90Pitch90
+Roll180Pitch90
+Roll270Pitch90
+Roll90Pitch180
+Roll270Pitch180
+Roll90Pitch270
+Roll180Pitch270
+Roll270Pitch270
+Roll90Pitch180Yaw90
+Roll90Yaw270
+Yaw293Pitch68Roll180
+Pitch315
+Roll90Pitch315
+
+
+
+
+Internal
+External
+ForcedExternal
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+4 32
+
+Very Strict
+Strict
+Default
+Relaxed
+
+0.1
+
+
+500 3000
+1
+
+
+0:HMC5883,1:LSM303D,2:AK8963,3:BMM150,4:LSM9DS1,5:LIS3MDL,6:AK09916,7:IST8310,8:ICM20948,9:MMC3416,11:UAVCAN,12:QMC5883,14:MAG3110,15:IST8308
+
+
+0 100
+1
+%
+percent
+
+
+
+Disabled
+CheckOnly
+CheckAndFix
+
+
+
+
+
+
+
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 2
+0.01
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+
+Disabled
+Enabled
+
+True
+
+
+
+GPS 3D Vel and 2D Pos
+GPS 2D vel and 2D pos
+GPS 2D pos
+No GPS
+
+
+
+0.05 5.0
+0.05
+m/s
+meters per second
+
+
+0.05 5.0
+0.05
+m/s
+meters per second
+
+
+100 1000
+25
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+10 100
+5
+m
+meters
+
+
+
+Use Baro
+Use Range Finder
+Use GPS
+Use Range Beacon
+
+True
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+0 250
+10
+ms
+milliseconds
+True
+
+
+0.01 0.5
+0.01
+Gauss
+gauss
+
+
+
+When flying
+When manoeuvring
+Never
+After first climb yaw reset
+Always
+
+
+
+100 1000
+25
+
+
+0.5 5.0
+0.1
+m/s
+meters per second
+
+
+100 1000
+25
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+1.0 4.0
+0.1
+rad/s
+radians per second
+
+
+0.05 1.0
+0.05
+rad/s
+radians per second
+
+
+100 1000
+25
+
+
+0 127
+10
+ms
+milliseconds
+True
+
+
+0.0001 0.1
+0.0001
+rad/s
+radians per second
+
+
+0.01 1.0
+0.01
+m/s/s
+meters per square second
+
+
+0.00001 0.001
+rad/s/s
+radians per square second
+
+
+0.000001 0.001
+Hz
+hertz
+
+
+0.00001 0.005
+m/s/s/s
+meters per cubic second
+
+
+0.01 1.0
+0.1
+m/s/s
+meters per square second
+
+
+0.0 1.0
+0.1
+
+
+0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
+True
+
+
+50 200
+%
+percent
+
+
+0.5 50.0
+m
+meters
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
+True
+
+
+0.05 1.0
+0.05
+rad
+radians
+
+
+100 1000
+25
+
+
+10 50
+5
+cs
+centiseconds
+
+
+0.00001 0.01
+Gauss/s
+gauss per second
+
+
+0.00001 0.01
+Gauss/s
+gauss per second
+
+
+-1 70
+1
+%
+percent
+
+
+0 0.2
+0.01
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+0 127
+10
+ms
+milliseconds
+True
+
+
+2.0 6.0
+0.5
+m/s
+meters per second
+
+
+0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
+True
+
+
+0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position
+True
+
+
+0 127
+1
+ms
+milliseconds
+True
+
+
+
+
+
+Disabled
+Enabled
+
+True
+
+
+
+GPS 3D Vel and 2D Pos
+GPS 2D vel and 2D pos
+GPS 2D pos
+No GPS
+
+
+
+0.05 5.0
+0.05
+m/s
+meters per second
+
+
+0.05 5.0
+0.05
+m/s
+meters per second
+
+
+100 1000
+25
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+10 100
+5
+m
+meters
+
+
+
+Use Baro
+Use Range Finder
+Use GPS
+Use Range Beacon
+
+True
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+0 250
+10
+ms
+milliseconds
+True
+
+
+0.01 0.5
+0.01
+Gauss
+gauss
+
+
+
+When flying
+When manoeuvring
+Never
+After first climb yaw reset
+Always
+
+True
+
+
+100 1000
+25
+
+
+0.5 5.0
+0.1
+m/s
+meters per second
+
+
+100 1000
+25
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+1.0 4.0
+0.1
+rad/s
+radians per second
+
+
+0.05 1.0
+0.05
+rad/s
+radians per second
+
+
+100 1000
+25
+
+
+0 250
+10
+ms
+milliseconds
+True
+
+
+0.0001 0.1
+0.0001
+rad/s
+radians per second
+
+
+0.01 1.0
+0.01
+m/s/s
+meters per square second
+
+
+0.00001 0.001
+rad/s/s
+radians per square second
+
+
+0.00001 0.005
+m/s/s/s
+meters per cubic second
+
+
+0.01 1.0
+0.1
+m/s/s
+meters per square second
+
+
+0.0 1.0
+0.1
+
+
+0:NSats,1:HDoP,2:speed error,3:position error,4:yaw error,5:pos drift,6:vert speed,7:horiz speed
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
+True
+
+
+50 200
+%
+percent
+
+
+0.5 50.0
+m
+meters
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU,3:FourthIMU,4:FifthIMU,5:SixthIMU
+True
+
+
+0.05 1.0
+0.05
+rad
+radians
+
+
+100 1000
+25
+
+
+10 50
+5
+cs
+centiseconds
+
+
+0.00001 0.01
+Gauss/s
+gauss per second
+
+
+0.00001 0.01
+Gauss/s
+gauss per second
+
+
+-1 70
+1
+%
+percent
+
+
+0 0.2
+0.01
+
+
+0.1 10.0
+0.1
+m
+meters
+
+
+100 1000
+25
+
+
+0 250
+10
+ms
+milliseconds
+True
+
+
+2.0 6.0
+0.5
+m/s
+meters per second
+
+
+0.5 2.5
+0.1
+m/s/s
+meters per square second
+
+
+0:FirstEKF,1:SecondEKF,2:ThirdEKF,3:FourthEKF,4:FifthEKF,5:SixthEKF
+True
+
+
+0:Correct when using Baro height,1:Correct when using range finder height,2:Apply corrections to local position
+True
+
+
+0.05 0.5
+0.05
+m/s
+meters per second
+
+
+0.5 5.0
+0.1
+m/s
+meters per second
+
+
+0.01 1.0
+0.1
+m/s
+meters per second
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0:Altitude,1:Circle,2:Polygon
+
+None
+Altitude
+Circle
+Altitude and Circle
+Polygon
+Altitude and Polygon
+Circle and Polygon
+All
+
+
+
+
+Report Only
+RTL or Land
+Always Land
+SmartRTL or RTL or Land
+Brake or Land
+
+
+
+10 1000
+1
+m
+meters
+
+
+30 10000
+m
+meters
+
+
+1 10
+m
+meters
+
+
+1 20
+
+
+-100 100
+1
+m
+meters
+
+
+
+
+0.1 6.0
+0.1
+
+
+0.02 1.00
+0.01
+
+
+0 4500
+10
+cdeg
+centidegrees
+
+
+0 100
+Hz
+hertz
+
+
+0.1 2.5
+
+
+1 100
+Hz
+hertz
+
+
+0 255
+
+
+1 30
+deg/s
+degrees per second
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+-200 +200
+1
+
+
+-200 +200
+1
+
+
+-18000 +18000
+1
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+0 127
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 255
+
+
+1 1000
+m
+meters
+
+
+
+North-East-Down
+Relative to lead vehicle heading
+
+
+
+-100 100
+1
+m
+meters
+
+
+-100 100
+1
+m
+meters
+
+
+-100 100
+1
+m
+meters
+
+
+
+None
+Face Lead Vehicle
+Same as Lead vehicle
+Direction of Flight
+
+
+
+0.01 1.00
+0.01
+
+
+
+absolute
+ relative
+
+
+
+
+
+True
+True
+1
+Pa
+pascal
+
+
+True
+1
+degC
+degrees Celsius
+
+
+0.1
+m
+meters
+
+
+
+FirstBaro
+2ndBaro
+3rdBaro
+
+
+
+
+Disabled
+Bus0
+Bus1
+
+
+
+1.0:Freshwater,1.024:Saltwater
+
+
+True
+True
+1
+Pa
+pascal
+
+
+True
+True
+1
+Pa
+pascal
+
+
+0 100
+1
+%
+percent
+
+
+0:BMP085,1:BMP280,2:MS5611,3:MS5607,4:MS5637,5:FBM320,6:DPS280,7:LPS25H,8:Keller
+
+BMP085
+BMP280
+MS5611
+MS5607
+MS5637
+FBM320
+DPS280
+LPS25H
+Keller
+
+
+
+
+
+
+None
+AUTO
+uBlox
+MTK
+MTK19
+NMEA
+SiRF
+HIL
+SwiftNav
+UAVCAN
+SBF
+GSOF
+ERB
+MAV
+NOVA
+
+True
+
+
+
+None
+AUTO
+uBlox
+MTK
+MTK19
+NMEA
+SiRF
+HIL
+SwiftNav
+UAVCAN
+SBF
+GSOF
+ERB
+MAV
+NOVA
+
+True
+
+
+
+Portable
+Stationary
+Pedestrian
+Automotive
+Sea
+Airborne1G
+Airborne2G
+Airborne4G
+
+
+
+
+Disabled
+UseBest
+Blend
+UseSecond
+
+
+
+
+Any
+FloatRTK
+IntegerRTK
+
+True
+
+
+
+Disabled
+Enabled
+NoChange
+
+
+
+-100 90
+deg
+degrees
+
+
+
+send to first GPS
+send to 2nd GPS
+send to all
+
+
+
+
+None (0x0000)
+All (0xFFFF)
+External only (0xFF00)
+
+
+
+
+Ignore
+Always log
+Stop logging when disarmed (SBF only)
+Only log every five samples (uBlox only)
+
+True
+
+
+0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
+
+Leave as currently configured
+GPS-NoSBAS
+GPS+SBAS
+Galileo-NoSBAS
+Galileo+SBAS
+Beidou
+GPS+IMES+QZSS+SBAS (Japan Only)
+GLONASS
+GLONASS+SBAS
+GPS+GLONASS+SBAS
+
+
+
+
+Do not save config
+Save config
+Save only when needed
+
+
+
+0:GPS,1:SBAS,2:Galileo,3:Beidou,4:IMES,5:QZSS,6:GLOSNASS
+
+Leave as currently configured
+GPS-NoSBAS
+GPS+SBAS
+Galileo-NoSBAS
+Galileo+SBAS
+Beidou
+GPS+IMES+QZSS+SBAS (Japan Only)
+GLONASS
+GLONASS+SBAS
+GPS+GLONASS+SBAS
+
+
+
+
+Disables automatic configuration
+Enable automatic configuration
+
+
+
+50 200
+
+10Hz
+8Hz
+5Hz
+
+ms
+milliseconds
+
+
+50 200
+
+10Hz
+8Hz
+5Hz
+
+ms
+milliseconds
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+0 250
+ms
+milliseconds
+True
+
+
+0 250
+ms
+milliseconds
+True
+
+
+0:Horiz Pos,1:Vert Pos,2:Speed
+
+
+5.0 30.0
+s
+seconds
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+None
+Servo
+EPM
+
+
+
+1000 2000
+PWM
+PWM in microseconds
+
+
+1000 2000
+PWM
+PWM in microseconds
+
+
+1000 2000
+PWM
+PWM in microseconds
+
+
+0 255
+s
+seconds
+
+
+0 255
+
+
+
+
+
+Servo only
+Servo with ExtGyro
+DirectDrive VarPitch
+DirectDrive FixedPitch
+
+
+
+0 1000
+1
+PWM
+PWM in microseconds
+
+
+-10 10
+0.1
+
+
+
+NoFlybar
+Flybar
+
+
+
+0 1000
+1
+PWM
+PWM in microseconds
+
+
+0 1000
+1
+PWM
+PWM in microseconds
+
+
+
+Longitudinal
+Transverse
+
+
+
+0 1
+
+
+-10 10
+0.1
+
+
+-10 10
+0.1
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+1000 2000
+1
+PWM
+PWM in microseconds
+
+
+
+Disabled
+Passthrough
+Max collective
+Mid collective
+Min collective
+
+
+
+0 1000
+10
+PWM
+PWM in microseconds
+
+
+
+Ch8 Input
+SetPoint
+Throttle Curve
+
+
+
+0 500
+1
+PWM
+PWM in microseconds
+
+
+0 60
+s
+seconds
+
+
+0 60
+s
+seconds
+
+
+0 1000
+10
+
+
+0 500
+10
+
+
+0 18000
+100
+cdeg
+centidegrees
+
+
+0 10
+1
+
+
+0 500
+10
+
+
+0 1000
+10
+
+
+0 1000
+10
+
+
+0 1000
+10
+
+
+0 1000
+10
+
+
+0 1000
+10
+
+
+
+
+
+H3 Generic
+H1 non-CPPM
+H3_140
+H3_120
+H4_90
+H4_45
+
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-30 30
+1
+deg
+degrees
+
+
+
+
+
+H3 Generic
+H1 non-CPPM
+H3_140
+H3_120
+H4_90
+H4_45
+
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-30 30
+1
+deg
+degrees
+
+
+
+
+
+H3 Generic
+H1 non-CPPM
+H3_140
+H3_120
+H4_90
+H4_45
+
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-180 180
+deg
+degrees
+
+
+-30 30
+1
+deg
+degrees
+
+
+
+
+0 500
+1
+d%
+decipercent
+
+
+0 500
+1
+d%
+decipercent
+
+
+500 1000
+1
+d%
+decipercent
+
+
+500 1000
+1
+d%
+decipercent
+
+
+
+Disabled
+Very Low
+Low
+Medium
+High
+Very High
+
+
+
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+rad/s
+radians per second
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+0.8 1.2
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+-3.5 3.5
+m/s/s
+meters per square second
+
+
+0 127
+Hz
+hertz
+
+
+0 127
+Hz
+hertz
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+0.05 50
+
+
+
+Never
+Start-up only
+
+
+
+
+Don't adjust the trims
+Assume first orientation was level
+Assume ACC_BODYFIX is perfectly aligned to the vehicle
+
+
+
+
+IMU 1
+IMU 2
+IMU 3
+
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+-10 10
+m
+meters
+
+
+True
+
+
+True
+
+
+True
+
+
+True
+
+
+True
+
+
+True
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU
+
+FirstIMUOnly
+FirstAndSecondIMU
+
+
+
+0:FirstIMU,1:SecondIMU,2:ThirdIMU
+
+FirstIMUOnly
+FirstAndSecondIMU
+FirstSecondAndThirdIMU
+AllIMUs
+
+
+
+
+
+32
+
+
+0:IMU1,1:IMU2,2:IMU3
+
+None
+First IMU
+All
+
+
+
+0:Sensor-Rate Logging (sample at full sensor rate seen by AP)
+
+
+10
+ms
+milliseconds
+
+
+1
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+10 200
+Hz
+hertz
+
+
+5 50
+Hz
+hertz
+
+
+5 30
+dB
+decibel
+
+
+
+
+
+WaitForPilotInput
+Retract
+Deploy
+
+
+
+
+Disabled
+AUX1
+AUX2
+AUX3
+AUX4
+AUX5
+AUX6
+
+True
+
+
+
+Low
+High
+
+
+
+
+Disabled
+AUX1
+AUX2
+AUX3
+AUX4
+AUX5
+AUX6
+
+True
+
+
+
+Low
+High
+
+
+
+0 1000
+1
+m
+meters
+
+
+0 1000
+1
+m
+meters
+
+
+
+
+0:File,1:MAVLink,2:Block
+
+None
+File
+MAVLink
+File and MAVLink
+Block
+Block and MAVLink
+
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+kB
+kilobytes
+
+
+
+
+0 45
+1
+deg
+degrees
+
+
+20 2000
+50
+cm/s
+centimeters per second
+
+
+100 981
+1
+cm/s/s
+centimeters per square second
+
+
+25 250
+1
+cm/s/s
+centimeters per square second
+
+
+500 5000
+1
+cm/s/s/s
+centimeters per cubic second
+
+
+0 2
+0.1
+s
+seconds
+
+
+
+
+0 32766
+1
+
+
+
+Resume Mission
+Restart Mission
+
+
+
+0:Clear Mission on reboot
+
+
+
+
+
+Retracted
+Neutral
+MavLink Targeting
+RC Targeting
+GPS Point
+
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+0 100
+1
+
+
+0.0 0.2
+.005
+s
+seconds
+
+
+0.0 0.2
+.005
+s
+seconds
+
+
+
+None
+Servo
+3DR Solo
+Alexmos Serial
+SToRM32 MAVLink
+SToRM32 Serial
+
+True
+
+
+
+Retracted
+Neutral
+MavLink Targeting
+RC Targeting
+GPS Point
+
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+-180.00 179.99
+1
+deg
+degrees
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+
+Disabled
+RC5
+RC6
+RC7
+RC8
+RC9
+RC10
+RC11
+RC12
+
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+-18000 17999
+1
+cdeg
+centidegrees
+
+
+0.0 0.2
+.005
+s
+seconds
+
+
+0.0 0.2
+.005
+s
+seconds
+
+
+
+None
+Servo
+3DR Solo
+Alexmos Serial
+SToRM32 MAVLink
+SToRM32 Serial
+
+
+
+
+
+0 500
+PWM
+PWM in microseconds
+
+
+0.25 0.8
+
+
+0.9:Low, 0.95:Default, 1.0:High
+
+
+6 35
+V
+volt
+
+
+6 35
+V
+volt
+
+
+0 200
+A
+ampere
+
+
+
+Normal
+OneShot
+OneShot125
+Brushed
+DShot150
+DShot300
+DShot600
+DShot1200
+
+True
+
+
+0 2000
+PWM
+PWM in microseconds
+
+
+0 2000
+PWM
+PWM in microseconds
+
+
+0.0:Low, 0.15:Default, 0.3:High
+
+
+0.0:Low, 0.1:Default, 0.2:High
+
+
+0 10
+s
+seconds
+
+
+0.2 0.8
+
+
+
+Disabled
+Learn
+LearnAndSave
+
+
+
+
+PWM enabled while disarmed
+PWM disabled while disarmed
+
+
+
+5 80
+1
+deg
+degrees
+
+
+0 2
+0.1
+s
+seconds
+
+
+0 5
+0.1
+
+
+
+First battery
+Second battery
+
+
+
+0 .5
+0.001
+s
+seconds
+
+
+0 .5
+0.001
+s
+seconds
+
+
+
+
+
+Off
+Low
+Medium
+High
+
+
+
+
+Disable
+Enable
+
+
+
+
+Standard
+MAVLink
+OutbackChallenge
+
+
+
+
+Disable
+ssd1306
+sh1106
+
+
+
+
+Disabled
+Aircraft
+Rover
+
+
+
+
+Disabled
+
+
+
+0:Build in LED, 1:Internal ToshibaLED, 2:External ToshibaLED, 3:External PCA9685, 4:Oreo LED, 5:UAVCAN, 6:NCP5623 External, 7:NCP5623 Internal
+
+
+
+LowIsOn
+HighIsOn
+
+
+
+
+
+
+None
+MAX7456
+
+True
+
+
+
+Disable
+Chan5
+Chan6
+Chan7
+Chan8
+Chan9
+Chan10
+Chan11
+Chan12
+Chan13
+Chan14
+Chan15
+Chan16
+
+
+
+0:UseDecimalPack, 1:InvertedWindPointer, 2:InvertedAHRoll
+
+
+True
+
+
+0 31
+True
+
+
+0 63
+True
+
+
+0 99
+
+
+1 30
+
+
+0 100
+
+
+
+Metric
+Imperial
+SI
+Aviation
+
+
+
+1 20
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+900 2100
+
+
+900 2100
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+900 2100
+
+
+900 2100
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+900 2100
+
+
+900 2100
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+900 2100
+
+
+900 2100
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 29
+
+
+0 15
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+None
+CompanionComputer
+IRLock
+SITL_Gazebo
+SITL
+
+
+
+0 360
+1
+cdeg
+centidegrees
+
+
+-20 20
+1
+cm
+centimeters
+
+
+-20 20
+1
+cm
+centimeters
+
+
+
+RawSensor
+KalmanFilter
+
+
+
+0.5 5
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+DefaultBus
+InternalI2C
+ExternalI2C
+
+
+
+0.02 0.250
+1
+s
+seconds
+True
+
+
+
+
+
+None
+LightWareSF40C
+MAVLink
+TeraRangerTower
+RangeFinder
+RPLidarA2
+TeraRangerTowerEvo
+SITL
+MorseSITL
+
+True
+
+
+
+Default
+Upside Down
+
+
+
+-180 180
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+0 360
+deg
+degrees
+
+
+0 45
+deg
+degrees
+
+
+
+None
+LightWareSF40C
+MAVLink
+TeraRangerTower
+RangeFinder
+RPLidarA2
+TeraRangerTowerEvo
+
+True
+
+
+
+Default
+Upside Down
+
+
+
+-180 180
+deg
+degrees
+
+
+
+
+0.5 5
+0.1
+Hz
+hertz
+
+
+1.000 3.000
+
+
+1.000 8.000
+
+
+0.500 1.500
+0.05
+
+
+0.000 3.000
+
+
+0 1000
+d%
+decipercent
+
+
+0.000 0.400
+
+
+1.000 100.000
+Hz
+hertz
+
+
+0.500 2.000
+
+
+0.1 6.0
+0.1
+
+
+0.02 1.00
+0.01
+
+
+0.00 1.00
+0.001
+
+
+0 4500
+10
+cm/s/s
+centimeters per square second
+
+
+0 100
+Hz
+hertz
+
+
+0 100
+Hz
+hertz
+
+
+0 45
+1
+deg
+degrees
+
+
+
+
+
+
+0.1
+km
+kilometers
+
+
+
+DoNotIncludeHome
+IncludeHome
+
+
+
+
+
+0.0 120.0
+s
+seconds
+
+
+0:Ignore RC Receiver, 1:Ignore MAVLink Overrides, 2:Ignore Receiver Failsafe
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+0 200
+PWM
+PWM in microseconds
+
+
+
+Do Nothing
+Flip
+Simple Mode
+RTL
+Save Trim
+Save WP
+Camera Trigger
+RangeFinder
+Fence
+Super Simple Mode
+Acro Trainer
+Sprayer
+Auto
+AutoTune
+Land
+Gripper
+Parachute Enable
+Parachute Release
+Parachute 3pos
+Auto Mission Reset
+AttCon Feed Forward
+AttCon Accel Limits
+Retract Mount
+Relay On/Off
+Relay2 On/Off
+Relay3 On/Off
+Relay4 On/Off
+Landing Gear
+Lost Copter Sound
+Motor Emergency Stop
+Motor Interlock
+Brake
+Throw
+ADSB-Avoidance
+PrecLoiter
+Proximity Avoidance
+ArmDisarm
+SmartRTL
+InvertedFlight
+Winch Enable
+WinchControl
+RC Override Enable
+User Function 1
+User Function 2
+User Function 3
+Clear Waypoints
+ZigZag
+ZigZag SaveWP
+Compass Learn
+GPS Disable
+ Relay5
+ Relay6
+
+
+
+
+
+1 8
+1
+True
+
+
+1 8
+1
+True
+
+
+1 8
+1
+True
+
+
+1 8
+1
+True
+
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+Off
+On
+NoChange
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+Disabled
+BB Blue GP0 pin 4
+AUXOUT1
+AUXOUT2
+AUXOUT3
+AUXOUT4
+AUXOUT5
+AUXOUT6
+BB Blue GP0 pin 3
+BB Blue GP0 pin 6
+BB Blue GP0 pin 5
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+Analog
+MaxbotixI2C
+LidarLiteV2-I2C
+PX4-PWM
+BBB-PRU
+LightWareI2C
+LightWareSerial
+Bebop
+MAVLink
+uLanding
+LeddarOne
+MaxbotixSerial
+TeraRangerI2C
+LidarLiteV3-I2C
+VL53L0X
+NMEA
+WASP-LRF
+BenewakeTF02
+BenewakeTFmini
+
+
+
+
+Not Used
+PX4-airspeed port
+Pixhawk-airspeed port
+
+
+
+0.001
+m/V
+meters per volt
+
+
+0.001
+V
+volt
+
+
+
+Linear
+Inverted
+Hyperbolic
+
+
+
+1
+cm
+centimeters
+
+
+1
+cm
+centimeters
+
+
+
+Not Used
+Pixhawk AUXOUT1
+Pixhawk AUXOUT2
+Pixhawk AUXOUT3
+Pixhawk AUXOUT4
+Pixhawk AUXOUT5
+Pixhawk AUXOUT6
+PX4 FMU Relay1
+PX4 FMU Relay2
+PX4IO Relay1
+PX4IO Relay2
+PX4IO ACC1
+PX4IO ACC2
+
+
+
+1
+ms
+milliseconds
+
+
+
+No
+Yes
+
+
+
+0 32767
+m
+meters
+
+
+5 127
+1
+cm
+centimeters
+
+
+0 127
+1
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Forward-Right
+Right
+Back-Right
+Back
+Back-Left
+Left
+Forward-Left
+Up
+Down
+
+
+
+
+
+0 255
+
+
+0 255
+
+
+0 10000
+
+
+0 255
+
+
+-1 255
+
+
+
+Low Speed
+High Speed
+
+
+
+
+
+
+None
+PX4-PWM
+AUXPIN
+
+
+
+0.001
+
+
+1
+
+
+1
+
+
+0.1
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+None
+PX4-PWM
+AUXPIN
+
+
+
+0.001
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+
+
+Disabled
+AnalogPin
+RCChannelPwmValue
+ReceiverProtocol
+PWMInputPin
+
+
+
+
+V5 Nano
+Pixracer
+Pixhawk ADC4
+Pixhawk ADC3
+Pixhawk ADC6
+Pixhawk2 ADC
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+Pixhawk SBUS
+
+
+
+0 5.0
+0.01
+V
+volt
+
+
+0 5.0
+0.01
+V
+volt
+
+
+0 16
+
+
+0 2000
+PWM
+PWM in microseconds
+
+
+0 2000
+PWM
+PWM in microseconds
+
+
+
+
+
+Disabled
+ShowSlips
+ShowOverruns
+
+
+
+
+50Hz
+100Hz
+200Hz
+250Hz
+300Hz
+400Hz
+
+True
+
+
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+460800
+500000
+921600
+1500000
+
+
+
+
+MAVlink1
+MAVLink2
+
+True
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+
+None
+MAVLink1
+MAVLink2
+Frsky D
+Frsky SPort
+GPS
+Alexmos Gimbal Serial
+SToRM32 Gimbal Serial
+Rangefinder
+FrSky SPort Passthrough (OpenTX)
+Lidar360
+Beacon
+Volz servo out
+SBus servo out
+ESC Telemetry
+Devo Telemetry
+OpticalFlow
+RobotisServo
+
+True
+
+
+
+1200
+2400
+4800
+9600
+19200
+38400
+57600
+111100
+115200
+256000
+500000
+921600
+1500000
+
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+0:InvertRX, 1:InvertTX, 2:HalfDuplex, 4:Swap
+True
+
+
+
+Disabled
+Serial0
+Serial1
+Serial2
+Serial3
+Serial4
+Serial5
+Serial6
+
+
+
+
+Disabled
+Serial0
+Serial1
+Serial2
+Serial3
+Serial4
+Serial5
+Serial6
+
+
+
+0 120
+s
+seconds
+
+
+
+
+
+Disable
+Enable
+
+
+
+25 400
+Hz
+hertz
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+500 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+800 2200
+1
+PWM
+PWM in microseconds
+
+
+
+Normal
+Reversed
+
+
+
+
+Disabled
+RCPassThru
+Flap
+Flap_auto
+Aileron
+mount_pan
+mount_tilt
+mount_roll
+mount_open
+camera_trigger
+release
+mount2_pan
+mount2_tilt
+mount2_roll
+mount2_open
+DifferentialSpoilerLeft1
+DifferentialSpoilerRight1
+Elevator
+Rudder
+FlaperonLeft
+FlaperonRight
+GroundSteering
+Parachute
+EPM
+LandingGear
+EngineRunEnable
+HeliRSC
+HeliTailRSC
+Motor1
+Motor2
+Motor3
+Motor4
+Motor5
+Motor6
+Motor7
+Motor8
+MotorTilt
+RCIN1
+RCIN2
+RCIN3
+RCIN4
+RCIN5
+RCIN6
+RCIN7
+RCIN8
+RCIN9
+RCIN10
+RCIN11
+RCIN12
+RCIN13
+RCIN14
+RCIN15
+RCIN16
+Ignition
+Choke
+Starter
+Throttle
+TrackerYaw
+TrackerPitch
+ThrottleLeft
+ThrottleRight
+tiltMotorLeft
+tiltMotorRight
+ElevonLeft
+ElevonRight
+VTailLeft
+VTailRight
+BoostThrottle
+Motor9
+Motor10
+Motor11
+Motor12
+DifferentialSpoilerLeft2
+DifferentialSpoilerRight2
+Winch
+Main Sail
+Camera ISO
+Camera Focus
+Camera Shutter Speed
+Script 1
+Script 2
+Script 3
+Script 4
+Script 5
+Script 6
+Script 7
+Script 8
+Script 9
+Script 10
+Script 11
+Script 12
+Script 13
+Script 14
+Script 15
+Script 16
+
+
+
+
+
+0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
+
+
+
+Disabled
+Enabled
+
+
+
+
+Disabled
+TestMotor1
+TestMotor2
+TestMotor3
+TestMotor4
+TestMotor5
+TestMotor6
+TestMotor7
+TestMotor8
+
+
+
+0 300
+s
+seconds
+
+
+0 500
+Hz
+hertz
+
+
+
+Disabled
+Enabled
+
+
+
+
+None
+OneShot
+OneShot125
+Brushed
+DShot150
+DShot300
+DShot600
+DShot1200
+
+
+
+
+Console
+Telem1
+Telem2
+Telem3
+Telem4
+Telem5
+
+
+
+1 127
+
+
+0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
+
+
+
+
+0 4095
+
+
+0 4095
+
+
+
+
+25 250
+Hz
+hertz
+
+
+
+
+0:Channel1,1:Channel2,2:Channel3,3:Channel4,4:Channel5,5:Channel6,6:Channel7,7:Channel8,8:Channel9,9:Channel10,10:Channel11,11:Channel12,12:Channel13,13:Channel14,14:Channel15,15:Channel16
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+0 100
+%
+percent
+
+
+1000 2000
+ms
+milliseconds
+
+
+0 1000
+cm/s
+centimeters per second
+
+
+0 100
+%
+percent
+
+
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 50
+1
+Hz
+hertz
+
+
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 50
+1
+Hz
+hertz
+
+
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 50
+1
+Hz
+hertz
+
+
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 10
+1
+Hz
+hertz
+
+
+0 50
+1
+Hz
+hertz
+
+
+
+
+0 10
+m
+meters
+
+
+0 500
+True
+
+
+
+
+True
+
+
+True
+s
+seconds
+
+
+True
+s
+seconds
+
+
+True
+s
+seconds
+
+
+
+
+
+Disabled
+Enabled
+EnableAndLearn
+
+
+
+True
+True
+degC
+degrees Celsius
+
+
+True
+True
+degC
+degrees Celsius
+
+
+True
+True
+
+
+
+
+
+Disable
+Enable
+
+
+
+1
+m
+meters
+
+
+
+
+
+Disabled
+EnableVersion1
+EnableVersion2
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+FlowHold
+
+
+
+
+Stabilize
+Acro
+AltHold
+Auto
+Guided
+Loiter
+RTL
+Circle
+Land
+Drift
+Sport
+Flip
+AutoTune
+PosHold
+Brake
+Throw
+Avoid_ADSB
+Guided_NoGPS
+FlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+ModeFlowHold
+
+
+
+0 100
+
+
+
+None
+TakePhoto
+ToggleVideo
+ModeAcro
+ModeAltHold
+ModeAuto
+ModeLoiter
+ModeRTL
+ModeCircle
+ModeLand
+ModeDrift
+ModeSport
+ModeAutoTune
+ModePosHold
+ModeBrake
+ModeThrow
+Flip
+ModeStabilize
+Disarm
+ToggleMode
+Arm-Land-RTL
+ToggleSimpleMode
+ToggleSuperSimpleMode
+MotorLoadTest
+
+
+
+0:DisarmOnLowThrottle,1:ArmOnHighThrottle,2:UpgradeToLoiter,3:RTLStickCancel
+
+
+0 5
+0.01
+
+
+0 5
+0.01
+
+
+0 1
+0.01
+
+
+0 1
+0.01
+
+
+0 1
+0.01
+
+
+0 100
+
+
+
+ConstantThrust
+LogReplay1
+LogReplay2
+
+
+
+
+
+
+None
+MAV
+
+
+
+m
+meters
+
+
+m
+meters
+
+
+m
+meters
+
+
+
+Forward
+Right
+Back
+Left
+Up
+Down
+
+
+
+
+
+
+None
+Quadrature
+
+
+
+1
+
+
+0.001
+m
+meters
+
+
+0.01
+m
+meters
+
+
+0.01
+m
+meters
+
+
+0.01
+m
+meters
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+None
+Quadrature
+
+
+
+1
+
+
+0.001
+m
+meters
+
+
+0.01
+m
+meters
+
+
+0.01
+m
+meters
+
+
+0.01
+m
+meters
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+Disabled
+PixhawkAUX1
+PixhawkAUX2
+PixhawkAUX3
+PixhawkAUX4
+PixhawkAUX5
+PixhawkAUX6
+
+
+
+
+
+
+Disabled
+Enabled
+
+
+
+
+Servo with encoder
+
+
+
+0 10
+m/s
+meters per second
+
+
+0.01 10.0
+
+
+0.100 2.000
+
+
+0.000 2.000
+
+
+0.000 1.000
+
+
+0.000 0.400
+
+
+1.000 100.000
+Hz
+hertz
+
+
+
+
+20 2000
+50
+cm/s
+centimeters per second
+
+
+10 1000
+1
+cm
+centimeters
+
+
+10 1000
+50
+cm/s
+centimeters per second
+
+
+10 500
+10
+cm/s
+centimeters per second
+
+
+50 500
+10
+cm/s/s
+centimeters per square second
+
+
+50 500
+10
+cm/s/s
+centimeters per square second
+
+
+
+Disable
+Enable
+
+
+
+
diff --git a/src/FirmwarePlugin/APM/APMResources.qrc b/src/FirmwarePlugin/APM/APMResources.qrc
index aa54a0be1d9229a45a855b6c50b92707510194b8..5c147c4684495db4df3d45c542af7110648b9e8b 100644
--- a/src/FirmwarePlugin/APM/APMResources.qrc
+++ b/src/FirmwarePlugin/APM/APMResources.qrc
@@ -49,6 +49,7 @@
APMParameterFactMetaData.Copter.3.4.xml
APMParameterFactMetaData.Copter.3.5.xml
APMParameterFactMetaData.Copter.3.6.xml
+ APMParameterFactMetaData.Copter.3.7.xml
APMParameterFactMetaData.Rover.3.0.xml
APMParameterFactMetaData.Rover.3.2.xml
APMParameterFactMetaData.Rover.3.4.xml
diff --git a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
index 511d03408cac29066f9685ce1133781355f608eb..93d653b9ce7171bc7fbecfcd4f5106725c022fc6 100644
--- a/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
+++ b/src/FirmwarePlugin/APM/ArduCopterFirmwarePlugin.cc
@@ -162,6 +162,12 @@ ArduCopterFirmwarePlugin::ArduCopterFirmwarePlugin(void)
remapV3_7["BATT_ARM_VOLT"] = QStringLiteral("ARMING_VOLT_MIN");
remapV3_7["BATT2_ARM_VOLT"] = QStringLiteral("ARMING_VOLT2_MIN");
+ remapV3_7["RC7_OPTION"] = QStringLiteral("CH7_OPT");
+ remapV3_7["RC8_OPTION"] = QStringLiteral("CH8_OPT");
+ remapV3_7["RC9_OPTION"] = QStringLiteral("CH9_OPT");
+ remapV3_7["RC10_OPTION"] = QStringLiteral("CH10_OPT");
+ remapV3_7["RC11_OPTION"] = QStringLiteral("CH11_OPT");
+ remapV3_7["RC12_OPTION"] = QStringLiteral("CH12_OPT");
_remapParamNameIntialized = true;
}
diff --git a/src/FirmwarePlugin/APM/BuildParamMetaData.sh b/src/FirmwarePlugin/APM/BuildParamMetaData.sh
new file mode 100644
index 0000000000000000000000000000000000000000..1a0acf8fe0c41b3d52c363cc0ea5b15f7c44bdab
--- /dev/null
+++ b/src/FirmwarePlugin/APM/BuildParamMetaData.sh
@@ -0,0 +1,6 @@
+cd ~/repos/ardupilot
+rm apm.pdef.xml
+./Tools/autotest/param_metadata/param_parse.py --vehicle ArduCopter
+cp apm.pdef.xml ~/repos/qgroundcontrol/src/FirmwarePlugin/APM/APMParameterFactMetaData.Copter.3.7.xml
+rm apm.pdef.xml
+cd ~/repos/qgroundcontrol/src/FirmwarePlugin/APM