This is a complete list of the parameters which can be set via the MAVLink protocol in the EEPROM of your autopilot to control vehicle behaviour. This list is automatically generated from the latest ardupilot source code, and so may contain parameters which are not yet in the stable released versions of the code.
[toc exclude="Complete Parameter List"]This value is incremented when changes are made to the eeprom format
Allows setting an individual MAVLink system id for this vehicle to distinguish it from others on the same network
Allows restricting radio overrides to only come from my ground station
Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable
Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.
Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.
Value | Meaning |
---|---|
0 | None |
1 | Feedback from mid stick |
2 | High throttle cancels landing |
4 | Disarm on land detection |
The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up
bitmask of PIDs to send MAVLink PID_TUNING messages for
Value | Meaning |
---|---|
0 | None |
1 | Roll |
2 | Pitch |
4 | Yaw |
8 | AccelZ |
The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.
Defines a cone above home which determines maximum climb
Value | Meaning |
---|---|
0 | Disabled |
1 | Shallow |
3 | Steep |
Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.
This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.
The vehicle will climb this many cm during the initial climb portion of the RTL
Time (in milliseconds) to loiter above home before beginning final descent
RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database
Value | Meaning |
---|---|
0 | Relative to Home |
1 | Terrain |
Used to adjust the speed with which the target altitude is changed when objects are sensed below the copter
Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.
Value | Meaning |
---|---|
0 | Disabled/NoAction |
1 | RTL |
2 | RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS) |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Land (4.0+ Only) |
GPS Hdop value at or below this value represent a good position. Used for pre-arm checks
Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Mode1 |
2 | Mode2 |
3 | Mode1+2 |
4 | Mode3 |
5 | Mode1+3 |
6 | Mode2+3 |
7 | Mode1+2+3 |
8 | Mode4 |
9 | Mode1+4 |
10 | Mode2+4 |
11 | Mode1+2+4 |
12 | Mode3+4 |
13 | Mode1+3+4 |
14 | Mode2+3+4 |
15 | Mode1+2+3+4 |
16 | Mode5 |
17 | Mode1+5 |
18 | Mode2+5 |
19 | Mode1+2+5 |
20 | Mode3+5 |
21 | Mode1+3+5 |
22 | Mode2+3+5 |
23 | Mode1+2+3+5 |
24 | Mode4+5 |
25 | Mode1+4+5 |
26 | Mode2+4+5 |
27 | Mode1+2+4+5 |
28 | Mode3+4+5 |
29 | Mode1+3+4+5 |
30 | Mode2+3+4+5 |
31 | Mode1+2+3+4+5 |
32 | Mode6 |
33 | Mode1+6 |
34 | Mode2+6 |
35 | Mode1+2+6 |
36 | Mode3+6 |
37 | Mode1+3+6 |
38 | Mode2+3+6 |
39 | Mode1+2+3+6 |
40 | Mode4+6 |
41 | Mode1+4+6 |
42 | Mode2+4+6 |
43 | Mode1+2+4+6 |
44 | Mode3+4+6 |
45 | Mode1+3+4+6 |
46 | Mode2+3+4+6 |
47 | Mode1+2+3+4+6 |
48 | Mode5+6 |
49 | Mode1+5+6 |
50 | Mode2+5+6 |
51 | Mode1+2+5+6 |
52 | Mode3+5+6 |
53 | Mode1+3+5+6 |
54 | Mode2+3+5+6 |
55 | Mode1+2+3+5+6 |
56 | Mode4+5+6 |
57 | Mode1+4+5+6 |
58 | Mode2+4+5+6 |
59 | Mode1+2+4+5+6 |
60 | Mode3+4+5+6 |
61 | Mode1+3+4+5+6 |
62 | Mode2+3+4+5+6 |
63 | Mode1+2+3+4+5+6 |
Determines how the autopilot controls the yaw during missions and RTL
Value | Meaning |
---|---|
0 | Never change yaw |
1 | Face next waypoint |
2 | Face next waypoint except RTL |
3 | Face along GPS course |
The descent speed for the final stage of landing in cm/s
The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used
The maximum vertical ascending velocity the pilot may request in cm/s
The vertical acceleration used when pilot is controlling the altitude
The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled always RTL |
2 | Enabled Continue with Mission in Auto Mode (Removed in 4.0+) |
3 | Enabled always Land |
4 | Enabled always SmartRTL or RTL |
5 | Enabled always SmartRTL or Land |
The PWM level in microseconds on channel 3 below which throttle failsafe triggers
The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes
Flight mode when Channel 5 pwm is <= 1230
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Flight mode when Channel 5 pwm is >1230, <= 1360
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Flight mode when Channel 5 pwm is >1360, <= 1490
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Flight mode when Channel 5 pwm is >1490, <= 1620
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Flight mode when Channel 5 pwm is >1620, <= 1749
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Flight mode when Channel 5 pwm is >=1750
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
RC Channel to use for flight mode control
Value | Meaning |
---|---|
0 | Disabled |
5 | Channel5 |
6 | Channel6 |
7 | Channel7 |
8 | Channel8 |
9 | Channel9 |
10 | Channel 10 |
11 | Channel 11 |
12 | Channel 12 |
13 | Channel 13 |
14 | Channel 14 |
15 | Channel 15 |
This selects the mode to start in on boot. This is useful for when you want to start in AUTO mode on boot without a receiver.
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | Smart_RTL |
22 | FlowHold |
23 | Follow |
24 | ZigZag |
25 | SystemID |
26 | Heli_Autorotate |
Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode)
4 byte bitmap of log types to enable
Value | Meaning |
---|---|
830 | Default |
894 | Default+RCIN |
958 | Default+IMU |
1854 | Default+Motors |
-6146 | NearlyAll-AC315 |
45054 | NearlyAll |
131071 | All+FastATT |
262142 | All+MotBatt |
393214 | All+FastIMU |
397310 | All+FastIMU+PID |
655358 | All+FullIMU |
0 | Disabled |
Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.
Value | Meaning |
---|---|
0 | Normal Start-up |
1 | Start-up in ESC Calibration mode if throttle high |
2 | Start-up in ESC Calibration mode regardless of throttle |
3 | Start-up and automatically calibrate ESCs |
9 | Disabled |
Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob
Value | Meaning |
---|---|
0 | None |
1 | Stab Roll/Pitch kP |
4 | Rate Roll/Pitch kP |
5 | Rate Roll/Pitch kI |
21 | Rate Roll/Pitch kD |
3 | Stab Yaw kP |
6 | Rate Yaw kP |
26 | Rate Yaw kD |
56 | Rate Yaw Filter |
55 | Motor Yaw Headroom |
14 | AltHold kP |
7 | Throttle Rate kP |
34 | Throttle Accel kP |
35 | Throttle Accel kI |
36 | Throttle Accel kD |
12 | Loiter Pos kP |
22 | Velocity XY kP |
28 | Velocity XY kI |
10 | WP Speed |
25 | Acro RollPitch kP |
40 | Acro Yaw kP |
45 | RC Feel |
13 | Heli Ext Gyro |
38 | Declination |
39 | Circle Rate |
41 | RangeFinder Gain |
46 | Rate Pitch kP |
47 | Rate Pitch kI |
48 | Rate Pitch kD |
49 | Rate Roll kP |
50 | Rate Roll kI |
51 | Rate Roll kD |
52 | Rate Pitch FF |
53 | Rate Roll FF |
54 | Rate Yaw FF |
58 | SysID Magnitude |
Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.
Value | Meaning |
---|---|
0 | Plus |
1 | X |
2 | V |
3 | H |
4 | V-Tail |
5 | A-Tail |
10 | Y6B |
11 | Y6F |
12 | BetaFlightX |
13 | DJIX |
14 | ClockwiseX |
15 | I |
18 | BetaFlightXReversed |
Delay before automatic disarm in seconds. A value of zero disables auto disarm.
Maximum lean angle in all flight modes
PosHold flight mode's rotation rate during braking in deg/sec
PosHold flight mode's max lean angle during braking in centi-degrees
Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.
Value | Meaning |
---|---|
0 | No repositioning |
1 | Repositioning |
Controls the action that will be taken when an EKF failsafe is invoked
Value | Meaning |
---|---|
1 | Land |
2 | AltHold |
3 | Land even in Stabilize |
Allows setting the maximum acceptable compass and velocity variance
This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This is the speed in Hertz that your ESCs will receive updates
Converts pilot roll and pitch into a desired rate of rotation in ACRO and SPORT mode. Higher values mean faster rate of rotation.
Converts pilot yaw input into a desired rate of rotation. Higher values mean faster rate of rotation.
rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.
rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.
Type of trainer used in acro mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Leveling |
2 | Leveling and Limited |
Acro roll/pitch Expo to allow faster rotation when stick at edges
Value | Meaning |
---|---|
0 | Disabled |
0.1 | Very Low |
0.2 | Low |
0.3 | Medium |
0.4 | High |
0.5 | Very High |
Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.
Value | Meaning |
---|---|
0 | Stopped |
1 | Running |
This is the altitude in meters above which for navigation can begin. This applies in auto takeoff and auto landing.
Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)
Value | Meaning |
---|---|
3 | Auto |
4 | Guided |
5 | LOITER |
6 | RTL |
9 | Land |
17 | Brake |
18 | Throw |
Used by Throw mode. Specifies whether Copter is thrown upward or dropped.
Value | Meaning |
---|---|
0 | Upward Throw |
1 | Drop |
Ground Effect Compensation Enable/Disable
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning
Acro yaw expo to allow faster rotation when stick at edges
Value | Meaning |
---|---|
0 | Disabled |
0.1 | Very Low |
0.2 | Low |
0.3 | Medium |
0.4 | High |
0.5 | Very High |
Acro Throttle Mid
This controls whether packets from other than the expected GCS system ID will be accepted
Value | Meaning |
---|---|
0 | NotEnforced |
1 | Enforced |
Controls major frame class for multicopter component
Value | Meaning |
---|---|
0 | Undefined |
1 | Quad |
2 | Hexa |
3 | Octa |
4 | OctaQuad |
5 | Y6 |
6 | Heli |
7 | Tri |
8 | SingleCopter |
9 | CoaxCopter |
10 | BiCopter |
11 | Heli_Dual |
12 | DodecaHexa |
13 | HeliQuad |
14 | Deca |
15 | Scripting Matrix |
16 | 6DoF Scripting |
The maximum vertical descending velocity the pilot may request in cm/s
Altitude during Landing at which vehicle slows to LAND_SPEED
Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to
Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to
This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.
Value | Meaning |
---|---|
0 | Disabled |
1 | Continue if in Auto on RC failsafe only |
2 | Continue if in Auto on GCS failsafe only |
3 | Continue if in Auto on RC and/or GCS failsafe |
4 | Continue if in Guided on RC failsafe only |
8 | Continue if landing on any failsafe |
16 | Continue if in pilot controlled modes on GCS failsafe |
19 | Continue if in Auto on RC and/or GCS failsafe and continue if in pilot controlled modes on GCS failsafe |
A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.
A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.
Options that can be applied to change guided mode behaviour
Timeout before triggering the GCS failsafe
Options that can be applied to change RTL mode behaviour
Flight mode specific options
Type of ADS-B hardware for ADSB-in and ADSB-out configuration and operation. If any type is selected then MAVLink based ADSB-in messages will always be enabled
Value | Meaning |
---|---|
0 | Disabled |
1 | uAvionix-MAVLink |
2 | Sagetech |
ADSB list size of nearest vehicles. Longer lists take longer to refresh with lower SRx_ADSB values.
ADSB vehicle list radius filter. Vehicles detected outside this radius will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.
ICAO_ID unique vehicle identification number of this aircraft. This is a integer limited to 24bits. If set to 0 then one will be randomly generated. If set to -1 then static information is not sent, transceiver is assumed pre-programmed.
ADSB classification for the type of vehicle emitting the transponder signal. Default value is 14 (UAV).
Value | Meaning |
---|---|
0 | NoInfo |
1 | Light |
2 | Small |
3 | Large |
4 | HighVortexlarge |
5 | Heavy |
6 | HighlyManuv |
7 | Rotocraft |
8 | RESERVED |
9 | Glider |
10 | LightAir |
11 | Parachute |
12 | UltraLight |
13 | RESERVED |
14 | UAV |
15 | Space |
16 | RESERVED |
17 | EmergencySurface |
18 | ServiceSurface |
19 | PointObstacle |
Aircraft length and width dimension options in Length and Width in meters. In most cases, use a value of 1 for smallest size.
Value | Meaning |
---|---|
0 | NO_DATA |
1 | L15W23 |
2 | L25W28P5 |
3 | L25W34 |
4 | L35W33 |
5 | L35W38 |
6 | L45W39P5 |
7 | L45W45 |
8 | L55W45 |
9 | L55W52 |
10 | L65W59P5 |
11 | L65W67 |
12 | L75W72P5 |
13 | L75W80 |
14 | L85W80 |
15 | L85W90 |
GPS antenna lateral offset. This describes the physical location offest from center of the GPS antenna on the aircraft.
Value | Meaning |
---|---|
0 | NoData |
1 | Left2m |
2 | Left4m |
3 | Left6m |
4 | Center |
5 | Right2m |
6 | Right4m |
7 | Right6m |
GPS antenna longitudinal offset. This is usually set to 1, Applied By Sensor
Value | Meaning |
---|---|
0 | NO_DATA |
1 | AppliedBySensor |
Transceiver RF selection for Rx enable and/or Tx enable. This only effects devices that can Tx and/or Rx. Rx-only devices should override this to always be Rx-only.
VFR squawk (Mode 3/A) code is a pre-programmed default code when the pilot is flying VFR and not in contact with ATC. In the USA, the VFR squawk code is octal 1200 (hex 0x280, decimal 640) and in most parts of Europe the VFR squawk code is octal 7000. If an invalid octal number is set then it will be reset to 1200.
Describes your hardware RF In/Out capabilities.
Value | Meaning |
---|---|
0 | Unknown |
1 | Rx UAT only |
3 | Rx UAT and 1090ES |
7 | Rx&Tx UAT and 1090ES |
ADSB vehicle list altitude filter. Vehicles detected above this altitude will be completely ignored. They will not show up in the SRx_ADSB stream to the GCS and will not be considered in any avoidance calculations. A value of 0 will disable this filter.
ICAO_ID of special vehicle that ignores ADSB_LIST_RADIUS and ADSB_LIST_ALT. The vehicle is always tracked. Use 0 to disable.
0: no logging, 1: log only special ID, 2:log all
Value | Meaning |
---|---|
0 | no logging |
1 | log only special ID |
2 | log all |
This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect
This sets a digital output pin to set high when in manual mode
This sets a digital output pin which is cycled at 10Hz when termination is not activated. Note that if a FS_TERM_PIN is set then the heartbeat pin will continue to cycle at 10Hz when termination is activated, to allow the termination board to distinguish between autopilot crash and termination.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
Waypoint number to navigate to on comms loss
Waypoint number to navigate to on GPS lock loss
Can be set in flight to force termination of the heartbeat signal
This can be used to force an action on flight termination. Normally this is handled by an external failsafe board, but you can setup ArduPilot to handle it here. Please consult the wiki for more information on the possible values of the parameter
This sets a digital output pin to set high on flight termination
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
This sets the AMSL (above mean sea level) altitude limit. If the pressure altitude determined by QNH exceeds this limit then flight termination will be forced. Note that this limit is in meters, whereas pressure altitude limits are often quoted in feet. A value of zero disables the pressure altitude limit.
This sets margin for error in GPS derived altitude limit. This error margin is only used if the barometer has failed. If the barometer fails then the GPS will be used to enforce the AMSL_LIMIT, but this margin will be subtracted from the AMSL_LIMIT first, to ensure that even with the given amount of GPS altitude error the pressure altitude is not breached. OBC users should set this to comply with their D2 safety case. A value of -1 will mean that barometer failure will lead to immediate termination.
This sets the QNH pressure in millibars to be used for pressure altitude in the altitude limit. A value of zero disables the altitude limit.
Maximum number of GPS loss events before the aircraft stops returning to mission on GPS recovery. Use zero to allow for any number of GPS loss events.
Maximum number of comms loss events before the aircraft stops returning to mission on comms recovery. Use zero to allow for any number of comms loss events.
This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1
This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1
If this parameter is set to 1, then an RC loss will only cause the plane to terminate in manual control modes. If it is 0, then the plane will terminate in any flight mode.
This enables the dual loss termination part of the AFS system. If this parameter is 1 and both GPS and the ground control station fail simultaneously, this will be considered a "dual loss" and cause termination.
This is the time in seconds in manual mode that failsafe termination will activate if RC input is lost. For the OBC rules this should be (1.5). Use 0 to disable.
This is the maximum range of the vehicle in kilometers from first arming. If the vehicle goes beyond this range then the TERM_ACTION is performed. A value of zero disables this feature.
This controls how much to use the GPS to correct the attitude. This should never be set to zero for a plane as it would result in the plane losing control in turns. For a plane please use the default value of 1.0.
This controls whether to use dead-reckoning or GPS based navigation. If set to 0 then the GPS won't be used for navigation, and only dead reckoning will be used. A value of zero should never be used for normal flight. Currently this affects only the DCM-based AHRS: the EKF uses GPS whenever it is available.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This controls the weight the compass or GPS has on the heading. A higher value means the heading will track the yaw source (GPS or compass) more rapidly.
This controls how fast the accelerometers correct the attitude
This sets the maximum allowable difference between ground speed and airspeed. This allows the plane to cope with a failing airspeed sensor. A value of zero means to use the airspeed as is. See ARSPD_OPTIONS and ARSPD_MAX_WIND to disable airspeed sensors.
Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.
Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.
Not Used
Overall board orientation relative to the standard orientation for the board type. This rotates the IMU and compass readings to allow the board to be oriented in your vehicle at any 90 or 45 degree angle. This option takes affect on next boot. After changing you will need to re-level your vehicle.
Value | Meaning |
---|---|
0 | None |
1 | Yaw45 |
2 | Yaw90 |
3 | Yaw135 |
4 | Yaw180 |
5 | Yaw225 |
6 | Yaw270 |
7 | Yaw315 |
8 | Roll180 |
9 | Roll180Yaw45 |
10 | Roll180Yaw90 |
11 | Roll180Yaw135 |
12 | Pitch180 |
13 | Roll180Yaw225 |
14 | Roll180Yaw270 |
15 | Roll180Yaw315 |
16 | Roll90 |
17 | Roll90Yaw45 |
18 | Roll90Yaw90 |
19 | Roll90Yaw135 |
20 | Roll270 |
21 | Roll270Yaw45 |
22 | Roll270Yaw90 |
23 | Roll270Yaw135 |
24 | Pitch90 |
25 | Pitch270 |
26 | Pitch180Yaw90 |
27 | Pitch180Yaw270 |
28 | Roll90Pitch90 |
29 | Roll180Pitch90 |
30 | Roll270Pitch90 |
31 | Roll90Pitch180 |
32 | Roll270Pitch180 |
33 | Roll90Pitch270 |
34 | Roll180Pitch270 |
35 | Roll270Pitch270 |
36 | Roll90Pitch180Yaw90 |
37 | Roll90Yaw270 |
38 | Yaw293Pitch68Roll180 |
39 | Pitch315 |
40 | Roll90Pitch315 |
100 | Custom |
This controls the time constant for the cross-over frequency used to fuse AHRS (airspeed and heading) and GPS data to estimate ground velocity. Time constant is 0.1/beta. A larger time constant will use GPS data less and a small time constant will use air data less.
Minimum number of satellites visible to use GPS for velocity based corrections attitude correction. This defaults to 6, which is about the point at which the velocity numbers from a GPS become too unreliable for accurate correction of the accelerometers.
This controls which NavEKF Kalman filter version is used for attitude and position estimation
Value | Meaning |
---|---|
0 | Disabled |
2 | Enable EKF2 |
3 | Enable EKF3 |
11 | ExternalAHRS |
Autopilot mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Autopilot mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Autopilot mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when AHRS_ORIENTATION is set to CUSTOM.
Accelerometer error threshold used to determine inconsistent accelerometers. Compares this error range to other accelerometers to detect a hardware or calibration error. Lower value means tighter check and harder to pass arming check. Not all accelerometers are created equal.
Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works in manual throttle modes with throttle at zero +- deadzone (RCx_DZ)
Value | Meaning |
---|---|
0 | Disabled |
1 | ArmingOnly |
2 | ArmOrDisarm |
Bitmask of mission items that are required to be planned in order to arm the aircraft
Checks prior to arming motor. This is a bitmask of checks that will be performed before allowing arming. For most users it is recommended to leave this at the default of 1 (all checks enabled). You can select whatever checks you prefer by adding together the values of each check type to set this parameter. For example, to only allow arming when you have GPS lock and no RC failsafe you would set ARMING_CHECK to 72.
Value | Meaning |
---|---|
0 | None |
1 | All |
2 | Barometer |
4 | Compass |
8 | GPS Lock |
16 | INS(INertial Sensors - accels & gyros) |
32 | Parameters |
64 | RC Channels |
128 | Board voltage |
256 | Battery Level |
1024 | LoggingAvailable |
2048 | Hardware safety switch |
4096 | GPS configuration |
8192 | System |
16384 | Mission |
32768 | RangeFinder |
65536 | Camera |
131072 | AuxAuth |
524288 | FFT |
Allows you to enable (1) or disable (0) the autonomous autorotation capability.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Increase value to increase sensitivity of head speed controller during autonomous autorotation.
The target head speed in RPM during autorotation. Start by setting to desired hover speed and tune from there as necessary.
Target ground speed in cm/s for the autorotation controller to try and achieve/ maintain during the glide phase.
Cut-off frequency for collective low pass filter. For the entry phase. Acts as a following trim. Must be higher than AROT_COL_FILT_G.
Cut-off frequency for collective low pass filter. For the glide phase. Acts as a following trim. Must be lower than AROT_COL_FILT_E.
Maximum forward acceleration to apply in speed controller.
Time in seconds from bail out initiated to the exit of autorotation flight mode.
Allocate the RPM sensor instance to use for measuring head speed. RPM1 = 0. RPM2 = 1.
Velocity (horizontal) P gain. Determines the propotion of the target acceleration based on the velocity error.
Velocity (horizontal) input filter. Corrects the target acceleration proportionally to the desired velocity.
Maximum rate the yaw target can be updated in Loiter, RTL, Auto flight modes
Maximum acceleration in yaw axis
Value | Meaning |
---|---|
0 | Disabled |
9000 | VerySlow |
18000 | Slow |
36000 | Medium |
54000 | Fast |
Controls whether body-frame rate feedfoward is enabled or disabled
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Maximum acceleration in roll axis
Value | Meaning |
---|---|
0 | Disabled |
30000 | VerySlow |
72000 | Slow |
108000 | Medium |
162000 | Fast |
Maximum acceleration in pitch axis
Value | Meaning |
---|---|
0 | Disabled |
30000 | VerySlow |
72000 | Slow |
108000 | Medium |
162000 | Fast |
Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate
Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate
Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate
Angle Limit (to maintain altitude) Time Constant
Maximum angular velocity in roll axis
Value | Meaning |
---|---|
0 | Disabled |
360 | Slow |
720 | Medium |
1080 | Fast |
Maximum angular velocity in pitch axis
Value | Meaning |
---|---|
0 | Disabled |
360 | Slow |
720 | Medium |
1080 | Fast |
Maximum angular velocity in yaw axis
Value | Meaning |
---|---|
0 | Disabled |
360 | Slow |
720 | Medium |
1080 | Fast |
Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response
Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
Roll axis rate controller feed forward
Roll axis rate controller target frequency in Hz
Roll axis rate controller error frequency in Hz
Roll axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
Pitch axis rate controller feed forward
Pitch axis rate controller target frequency in Hz
Pitch axis rate controller error frequency in Hz
Pitch axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
Yaw axis rate controller feed forward
Yaw axis rate controller target frequency in Hz
Yaw axis rate controller error frequency in Hz
Yaw axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)
Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)
Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)
Trim the hover roll angle to counter tail rotor thrust in a hover
Roll axis rate controller P gain. Converts the difference between desired roll rate and actual roll rate into a motor speed output
Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate
Roll axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Point below which I-term will not leak down
Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate
Roll axis rate controller feed forward
Roll axis rate controller target frequency in Hz
Roll axis rate controller error frequency in Hz
Roll axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Pitch axis rate controller P gain. Converts the difference between desired pitch rate and actual pitch rate into a motor speed output
Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate
Pitch axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Point below which I-term will not leak down
Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate
Pitch axis rate controller feed forward
Pitch axis rate controller target frequency in Hz
Pitch axis rate controller error frequency in Hz
Pitch axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Yaw axis rate controller P gain. Converts the difference between desired yaw rate and actual yaw rate into a motor speed output
Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate
Yaw axis rate controller I gain maximum. Constrains the maximum motor output that the I gain will output
Point below which I-term will not leak down
Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate
Yaw axis rate controller feed forward
Yaw axis rate controller target frequency in Hz
Yaw axis rate controller error frequency in Hz
Yaw axis rate controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Pirouette compensation enabled
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
1-byte bitmap of axes to autotune
Value | Meaning |
---|---|
7 | All |
1 | Roll Only |
2 | Pitch Only |
4 | Yaw Only |
3 | Roll and Pitch |
5 | Roll and Yaw |
6 | Pitch and Yaw |
Autotune aggressiveness. Defines the bounce back used to detect size of the D term.
Defines the minimum D gain
Enable Avoidance using ADSB
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Specifies aircraft behaviour when a collision is imminent
Value | Meaning |
---|---|
0 | None |
1 | Report |
2 | Climb Or Descend |
3 | Move Horizontally |
4 | Move Perpendicularly in 3D |
5 | RTL |
6 | Hover |
Specifies aircraft behaviour when a collision may occur
Value | Meaning |
---|---|
0 | None |
1 | Report |
Determines what the aircraft will do after a fail event is resolved
Value | Meaning |
---|---|
0 | Remain in AVOID_ADSB |
1 | Resume previous flight mode |
2 | RTL |
3 | Resume if AUTO else Loiter |
Maximum number of obstacles to track
Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than W_DIST_XY or W_DIST_Z then W_ACTION is undertaken (assuming F_ACTION is not undertaken)
Aircraft velocity vectors are multiplied by this time to determine closest approach. If this results in an approach closer than F_DIST_XY or F_DIST_Z then F_ACTION is undertaken
Closest allowed projected distance before W_ACTION is undertaken
Closest allowed projected distance before F_ACTION is undertaken
Closest allowed projected distance before BEHAVIOUR_W is undertaken
Closest allowed projected distance before BEHAVIOUR_F is undertaken
Minimum AMSL (above mean sea level) altitude for ADS-B avoidance. If the vehicle is below this altitude, no avoidance action will take place. Useful to prevent ADS-B avoidance from activating while below the tree line or around structures. Default of 0 is no minimum.
Enabled/disable avoidance input sources
Value | Meaning |
---|---|
0 | None |
1 | UseFence |
2 | UseProximitySensor |
3 | UseFence and UseProximitySensor |
4 | UseBeaconFence |
7 | All |
Max lean angle used to avoid obstacles while in non-GPS modes
Distance from object at which obstacle avoidance will begin in non-GPS modes
Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes
Avoidance behaviour (slide or stop)
Value | Meaning |
---|---|
0 | Slide |
1 | Stop |
Maximum speed that will be used to back away from obstacles in GPS modes (m/s). Set zero to disable
Minimum altitude above which proximity based avoidance will start working. This requires a valid downward facing rangefinder reading to work. Set zero to disable
Maximum acceleration with which obstacles will be avoided with. Set zero to disable acceleration limits
calibrated ground pressure in Pascals
User provided ambient ground temperature in degrees Celsius. This is used to improve the calculation of the altitude the vehicle is at. This parameter is not persistent and will be reset to 0 every time the vehicle is rebooted. A value of 0 means use the internal measurement ambient temperature.
altitude offset in meters added to barometric altitude. This is used to allow for automatic adjustment of the base barometric altitude by a ground station equipped with a barometer. The value is added to the barometric altitude read by the aircraft. It is automatically reset to 0 when the barometer is calibrated on each reboot or when a preflight calibration is performed.
This selects which barometer will be the primary if multiple barometers are found
Value | Meaning |
---|---|
0 | FirstBaro |
1 | 2ndBaro |
2 | 3rdBaro |
This selects the bus number for looking for an I2C barometer. When set to -1 it will probe all external i2c buses based on the GND_PROBE_EXT parameter.
Value | Meaning |
---|---|
-1 | Disabled |
0 | Bus0 |
1 | Bus1 |
This sets the specific gravity of the fluid when flying an underwater ROV.
calibrated ground pressure in Pascals
calibrated ground pressure in Pascals
This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
This sets which types of external i2c barometer to look for. It is a bitmask of barometer types. The I2C buses to probe is based on GND_EXT_BUS. If BARO_EXT_BUS is -1 then it will probe all external buses, otherwise it will probe just the bus number given in GND_EXT_BUS.
Value | Meaning |
---|---|
1 | BMP085 |
2 | BMP280 |
4 | MS5611 |
8 | MS5607 |
16 | MS5637 |
32 | FBM320 |
64 | DPS280 |
128 | LPS25H |
256 | Keller |
512 | MS5837 |
1024 | BMP388 |
2048 | SPL06 |
4096 | MSP |
Barometer sensor ID, taking into account its type, bus and instance
Barometer2 sensor ID, taking into account its type, bus and instance
Barometer3 sensor ID, taking into account its type, bus and instance
This enables the use of wind coefficients for barometer compensation
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This enables the use of wind coefficients for barometer compensation
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This enables the use of wind coefficients for barometer compensation
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the X body axis. If the baro height estimate rises during forwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the X body axis. If the baro height estimate rises during backwards flight, then this will be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the right, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Y body axis. If the baro height estimate rises during sideways flight to the left, then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_BCOEF_X and EK3_BCOEF_Y parameters have been tuned.
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT2_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT2_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT2_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT2_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT2_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT2_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT2__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT2__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT3_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT3_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT3_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT3_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT3_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT3_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT3__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT3__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT4_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT4_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT4_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT4_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT4_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT4_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT4__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT4__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT5_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT5_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT5_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT5_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT5_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT5_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT5__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT5__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT6_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT6_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT6_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT6__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT6__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT7_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT7_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT7_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT7__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT7__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT8_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT8_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT8_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT8__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT8__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT9_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT9_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT9_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT9__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT9__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
Controls enabling monitoring of the battery's voltage and current
Value | Meaning |
---|---|
0 | Disabled |
3 | Analog Voltage Only |
4 | Analog Voltage and Current |
5 | Solo |
6 | Bebop |
7 | SMBus-Generic |
8 | UAVCAN-BatteryInfo |
9 | ESC |
10 | SumOfFollowing |
11 | FuelFlow |
12 | FuelLevelPWM |
13 | SMBUS-SUI3 |
14 | SMBUS-SUI6 |
15 | NeoDesign |
16 | SMBus-Maxell |
17 | Generator-Elec |
18 | Generator-Fuel |
19 | Rotoye |
Sets the analog input pin that should be used for voltage monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
2 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
13 | Pixhawk2_PM2/CubeOrange_PM2 |
14 | CubeOrange |
16 | Durandal |
100 | PX4-v1 |
Sets the analog input pin that should be used for current monitoring.
Value | Meaning |
---|---|
-1 | Disabled |
3 | Pixhawk/Pixracer/Navio2/Pixhawk2_PM1 |
4 | CubeOrange_PM2 |
14 | Pixhawk2_PM2 |
15 | CubeOrange |
17 | Durandal |
101 | PX4-v1 |
Used to convert the voltage of the voltage sensing pin (BATT_VOLT_PIN) to the actual battery's voltage (pin_voltage * VOLT_MULT). For the 3DR Power brick with a Pixhawk, this should be set to 10.1. For the Pixhawk with the 3DR 4in1 ESC this should be 12.02. For the PX using the PX4IO power supply this should be set to 1.
Number of amps that a 1V reading on the current sensor corresponds to. With a Pixhawk using the 3DR Power brick this should be set to 17. For the Pixhawk with the 3DR 4in1 ESC this should be 17.
Voltage offset at zero current on current sensor
Capacity of the battery in mAh when full
Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With UAVCAN it is the battery_id.
This is the timeout in seconds before a low voltage event will be triggered. For aircraft with low C batteries it may be necessary to raise this in order to cope with low voltage on long takeoffs. A value of zero disables low voltage errors.
Voltage type used for detection of low voltage event
Value | Meaning |
---|---|
0 | Raw Voltage |
1 | Sag Compensated Voltage |
Battery voltage that triggers a low battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
Battery capacity at which the low battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT_FS_LOW_ACT parameter.
Battery voltage that triggers a critical battery failsafe. Set to 0 to disable. If the battery voltage drops below this voltage continuously for more then the period specified by the BATT_LOW_TIMER parameter then the vehicle will perform the failsafe specified by the BATT_FS_CRT_ACT parameter.
Battery capacity at which the critical battery failsafe is triggered. Set to 0 to disable battery remaining failsafe. If the battery capacity drops below this level the vehicle will perform the failsafe specified by the BATT__FS_CRT_ACT parameter.
What action the vehicle should perform if it hits a low battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
What action the vehicle should perform if it hits a critical battery failsafe
Value | Meaning |
---|---|
0 | None |
1 | Land |
2 | RTL |
3 | SmartRTL or RTL |
4 | SmartRTL or Land |
5 | Terminate |
Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.
Battery capacity remaining which is required to arm the aircraft. Set to 0 to allow arming at any capacity. Note that execept for smart batteries rebooting the vehicle will always reset the remaining capacity estimate, which can lead to this check not providing sufficent protection, it is recommended to always use this in conjunction with the BATT__ARM_VOLT parameter.
Battery monitor I2C bus number
This sets options to change the behaviour of the battery monitor
What type of beacon based position estimation device is connected
Value | Meaning |
---|---|
0 | None |
1 | Pozyx |
2 | Marvelmind |
3 | Nooploop |
10 | SITL |
Beacon origin's latitude
Beacon origin's longitude
Beacon origin's altitude above sealevel in meters
Beacon systems rotation from north in degrees
Controls number of FMU outputs which are setup for PWM. All unassigned pins can be used for GPIO
Value | Meaning |
---|---|
0 | No PWMs |
1 | One PWMs |
2 | Two PWMs |
3 | Three PWMs |
4 | Four PWMs |
5 | Five PWMs |
6 | Six PWMs |
7 | Seven PWMs |
8 | Eight PWMs |
Enable flow control on serial 1 (telemetry 1) on Pixhawk. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup. Note that the PX4v1 does not have hardware flow control pins on this port, so you should leave this disabled.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | Auto |
Enable flow control on serial 2 (telemetry 2) on Pixhawk and STATE. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | Auto |
Enable flow control on serial 3. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | Auto |
Enable flow control on serial 4. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | Auto |
Enable flow control on serial 5. You must have the RTS and CTS pins connected to your radio. The standard DF13 6 pin connector for a 3DR radio does have those pins connected. If this is set to 2 then flow control will be auto-detected by checking for the output buffer filling on startup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | Auto |
This controls the default state of the safety switch at startup. When set to 1 the safety switch will start in the safe state (flashing) at boot. When set to zero the safety switch will start in the unsafe state (solid) at startup. Note that if a safety switch is fitted the user can still control the safety state after startup using the switch. The safety state can also be controlled in software using a MAVLink message.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the SBUS output frame rate in Hz
Value | Meaning |
---|---|
0 | Disabled |
1 | 50Hz |
2 | 75Hz |
3 | 100Hz |
4 | 150Hz |
5 | 200Hz |
6 | 250Hz |
7 | 300Hz |
User-defined serial number of this vehicle, it can be any arbitrary number you want and has no effect on the autopilot
A bitmask which controls what outputs can move while the safety switch has not been pressed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the target IMU temperature for boards with controllable IMU heating units. DO NOT SET -1 on The Cube. A value of -1 sets PH1 behaviour
This allows selection of a PX4 or VRBRAIN board type. If set to zero then the board type is auto-detected (PX4)
Value | Meaning |
---|---|
0 | AUTO |
1 | PX4V1 |
2 | Pixhawk |
3 | Cube/Pixhawk2 |
4 | Pixracer |
5 | PixhawkMini |
6 | Pixhawk2Slim |
13 | Intel Aero FC |
14 | Pixhawk Pro |
20 | AUAV2.1 |
21 | PCNC1 |
22 | MINDPXV2 |
23 | SP01 |
24 | CUAVv5/FMUV5 |
30 | VRX BRAIN51 |
32 | VRX BRAIN52 |
33 | VRX BRAIN52E |
34 | VRX UBRAIN51 |
35 | VRX UBRAIN52 |
36 | VRX CORE10 |
38 | VRX BRAIN54 |
39 | PX4 FMUV6 |
100 | PX4 OLDDRIVERS |
This allows for the IO co-processor on FMUv1 and FMUv2 to be disabled
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This controls the activation of the safety button. It allows you to control if the safety button can be used for safety enable and/or disable, and whether the button is only active when disarmed
Minimum voltage on the autopilot power rail to allow the aircraft to arm. 0 to disable the check.
Minimum voltage on the servo rail to allow the aircraft to arm. 0 to disable the check.
This is a scaling factor to slow down microSD operation. It can be used on flight board and microSD card combinations where full speed is not reliable. For normal full speed operation a value of 0 should be used.
This sets the voltage max for PWM output pulses. 0 for 3.3V and 1 for 5V output.
Value | Meaning |
---|---|
0 | 3.3V |
1 | 5V |
Board specific option flags
This adds a delay in milliseconds to boot to ensure peripherals initialise fully
IMU Heater P gain
IMU Heater integrator gain
IMU Heater integrator maximum
Select an alternative hardware configuration. A value of zero selects the default configuration for this board. Other values are board specific. Please see the documentation for your board for details on any alternative configuration values that may be available.
This enables support for direct attached radio receivers
Value | Meaning |
---|---|
0 | None |
1 | CYRF6936 |
2 | CC2500 |
3 | BK2425 |
Select air protocol
Value | Meaning |
---|---|
0 | Auto |
1 | DSM2 |
2 | DSMX |
radio debug level
disable receive CRC (for debug)
Value | Meaning |
---|---|
0 | NotDisabled |
1 | Disabled |
Channel to show receive RSSI signal strength, or zero for disabled
Channel to show received packet-per-second rate, or zero for disabled
If this is non-zero then telemetry packets will be sent over DSM
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Set telemetry transmit power. This is the power level (from 1 to 8) for telemetry packets sent from the RX to the TX
If this is enabled then the radio will continuously transmit as required for FCC testing. The transmit channel is set by the value of the parameter. The radio will not work for RC input while this is enabled
Value | Meaning |
---|---|
0 | Disabled |
1 | MinChannel |
2 | MidChannel |
3 | MaxChannel |
4 | MinChannelCW |
5 | MidChannelCW |
6 | MaxChannelCW |
This selects between different stick input modes. The default is mode2, which has throttle on the left stick and pitch on the right stick. You can instead set mode1, which has throttle on the right stick and pitch on the left stick.
Value | Meaning |
---|---|
1 | Mode1 |
2 | Mode2 |
This sets the radio to a fixed test channel for factory testing. Using a fixed channel avoids the need for binding in factory testing.
Value | Meaning |
---|---|
0 | Disabled |
1 | TestChan1 |
2 | TestChan2 |
3 | TestChan3 |
4 | TestChan4 |
5 | TestChan5 |
6 | TestChan6 |
7 | TestChan7 |
8 | TestChan8 |
Channel to show telemetry RSSI value as received by TX
Channel to show telemetry packets-per-second value, as received at TX
Set transmitter maximum transmit power (from 1 to 8)
Set transmitter buzzer note adjustment (adjust frequency up)
When non-zero this sets the time with no transmitter packets before we start looking for auto-bind packets.
This sets the minimum RSSI of an auto-bind packet for it to be accepted. This should be set so that auto-bind will only happen at short range to minimise the change of an auto-bind happening accidentially
Specifies which sources of UTC time will be accepted
Adds offset in +- minutes from UTC to calculate local time
This enables the button checking module. When this is disabled the parameters for setting button inputs are not visible
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Digital pin number for first button input.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
Digital pin number for second button input.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
Digital pin number for third button input.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
Digital pin number for fourth button input.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
The duration in seconds that a BUTTON_CHANGE report is repeatedly sent to the GCS regarding a button changing state. Note that the BUTTON_CHANGE message is MAVLink2 only.
Options for Pin 1. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
Options for Pin 2. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
Options for Pin 3. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
Options for Pin 4. PWM input detects PWM above or below 1800/1200us instead of logic level. Invert changes HIGH state to be logic low voltage on pin, or below 1200us, if PWM input.
Auxiliary RC Options function executed on pin change
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 |
67 | Relay6 |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
Auxiliary RC Options function executed on pin change
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 |
67 | Relay6 |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
Auxiliary RC Options function executed on pin change
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 |
67 | Relay6 |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
Auxiliary RC Options function executed on pin change
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 |
67 | Relay6 |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
how to trigger the camera to take a picture
Value | Meaning |
---|---|
0 | Servo |
1 | Relay |
2 | GoPro in Solo Gimbal |
How long the shutter will be held open in 10ths of a second (i.e. enter 10 for 1second, 50 for 5seconds)
PWM value in microseconds to move servo to when shutter is activated
PWM value in microseconds to move servo to when shutter is deactivated
Distance in meters between camera triggers. If this value is non-zero then the camera will trigger whenever the position changes by this number of meters regardless of what mode the APM is in. Note that this parameter can also be set in an auto mission using the DO_SET_CAM_TRIGG_DIST command, allowing you to enable/disable the triggering of the camera during the flight.
This sets whether the relay goes high or low when it triggers. Note that you should also set RELAY_DEFAULT appropriately for your camera
Value | Meaning |
---|---|
0 | Low |
1 | High |
Postpone shooting if previous picture was taken less than preset time(ms) ago.
Postpone shooting if roll is greater than limit. (0=Disable, will shoot regardless of roll).
pin number to use for save accurate camera feedback messages. If set to -1 then don't use a pin flag for this, otherwise this is a pin number which if held high after a picture trigger order, will save camera messages when camera really takes a picture. A universal camera hot shoe is needed. The pin should be held high for at least 2 milliseconds for reliable trigger detection. See also the CAM_FEEDBACK_POL option.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUX1 |
51 | AUX2 |
52 | AUX3 |
53 | AUX4 |
54 | AUX5 |
55 | AUX6 |
Polarity for feedback pin. If this is 1 then the feedback pin should go high on trigger. If set to 0 then it should go low
Value | Meaning |
---|---|
0 | TriggerLow |
1 | TriggerHigh |
When enabled, trigging by distance is done in AUTO mode only.
Value | Meaning |
---|---|
0 | Always |
1 | Only when in AUTO |
Set the camera type that is being used, certain cameras have custom functions that need further configuration, this enables that.
Value | Meaning |
---|---|
0 | Default |
1 | BMMCC |
RunCam deviee type used to determine OSD menu structure and shutter options.
Value | Meaning |
---|---|
0 | Disabled |
1 | RunCam Split Micro/RunCam with UART |
2 | RunCam Split |
3 | RunCam Split4 4k |
The available features of the attached RunCam device. If 0 then the RunCam device will be queried for the features it supports, otherwise this setting is used.
Time it takes for the RunCam to become fully ready in ms. If this is too short then commands can get out of sync.
Time it takes for the a RunCam button press to be actived in ms. If this is too short then commands can get out of sync.
Time it takes for the a RunCam mode button press to be actived in ms. If a mode change first requires a video recording change then double this value is used. If this is too short then commands can get out of sync.
Specifies the allowed actions required to enter the OSD menu
Loglevel for recording initialisation and debug information from CAN Interface
Value | Meaning |
---|---|
0 | Log None |
1 | Log Error |
2 | Log Warning and below |
3 | Log Info and below |
4 | Log Everything |
Enabling this option starts selected protocol that will use this virtual driver
Value | Meaning |
---|---|
0 | Disabled |
1 | UAVCAN |
3 | ToshibaCAN |
4 | PiccoloCAN |
5 | CANTester |
8 | KDECAN |
9 | PacketDigitalCAN |
Sets the number of motor poles to calculate the correct RPM value
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Output rate of ESC command messages
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Value | Meaning |
---|---|
0 | TEST_NONE |
1 | TEST_LOOPBACK |
2 | TEST_BUSOFF_RECOVERY |
3 | TEST_UAVCAN_DNA |
4 | TEST_TOSHIBA_CAN |
5 | TEST_KDE_CAN |
6 | TEST_UAVCAN_ESC |
Selects the Looprate of Test methods
UAVCAN node should be set implicitly
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Maximum transmit rate for servo outputs
Enabling this option starts selected protocol that will use this virtual driver
Value | Meaning |
---|---|
0 | Disabled |
1 | UAVCAN |
3 | ToshibaCAN |
4 | PiccoloCAN |
5 | CANTester |
8 | KDECAN |
9 | PacketDigitalCAN |
Sets the number of motor poles to calculate the correct RPM value
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Output rate of ESC command messages
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Value | Meaning |
---|---|
0 | TEST_NONE |
1 | TEST_LOOPBACK |
2 | TEST_BUSOFF_RECOVERY |
3 | TEST_UAVCAN_DNA |
4 | TEST_TOSHIBA_CAN |
5 | TEST_KDE_CAN |
6 | TEST_UAVCAN_ESC |
Selects the Looprate of Test methods
UAVCAN node should be set implicitly
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Maximum transmit rate for servo outputs
Enabling this option starts selected protocol that will use this virtual driver
Value | Meaning |
---|---|
0 | Disabled |
1 | UAVCAN |
3 | ToshibaCAN |
4 | PiccoloCAN |
5 | CANTester |
8 | KDECAN |
9 | PacketDigitalCAN |
Sets the number of motor poles to calculate the correct RPM value
Bitmask defining which ESC (motor) channels are to be transmitted over Piccolo CAN
Output rate of ESC command messages
Selects the Index of Test that needs to be run recursively, this value gets reset to 0 at boot.
Value | Meaning |
---|---|
0 | TEST_NONE |
1 | TEST_LOOPBACK |
2 | TEST_BUSOFF_RECOVERY |
3 | TEST_UAVCAN_DNA |
4 | TEST_TOSHIBA_CAN |
5 | TEST_KDE_CAN |
6 | TEST_UAVCAN_ESC |
Selects the Looprate of Test methods
UAVCAN node should be set implicitly
Bitmask with one set for channel to be transmitted as a servo command over UAVCAN
Bitmask with one set for channel to be transmitted as a ESC command over UAVCAN
Maximum transmit rate for servo outputs
Enabling this option enables use of CAN buses.
Value | Meaning |
---|---|
0 | Disabled |
1 | First driver |
2 | Second driver |
Bit rate can be set up to from 10000 to 1000000
Enabling this option enables use of CAN buses.
Value | Meaning |
---|---|
0 | Disabled |
1 | First driver |
2 | Second driver |
Bit rate can be set up to from 10000 to 1000000
Enabling this option enables use of CAN buses.
Value | Meaning |
---|---|
0 | Disabled |
1 | First driver |
2 | Second driver |
Bit rate can be set up to from 10000 to 1000000
CAN Interface ID to be routed to SLCAN, 0 means no routing
Value | Meaning |
---|---|
0 | Disabled |
1 | First interface |
2 | Second interface |
Serial Port ID to be used for temporary SLCAN iface, -1 means no temporary serial. This parameter is automatically reset on reboot or on timeout. See CAN_SLCAN_TIMOUT for timeout details
Value | Meaning |
---|---|
-1 | Disabled |
0 | Serial0 |
1 | Serial1 |
2 | Serial2 |
3 | Serial3 |
4 | Serial4 |
5 | Serial5 |
6 | Serial6 |
Duration of inactivity after which SLCAN is switched back to original driver in seconds.
Duration after which slcan starts after setting SERNUM in seconds.
Parachute release enabled or disabled
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Parachute release mechanism type (relay or servo)
Value | Meaning |
---|---|
0 | First Relay |
1 | Second Relay |
2 | Third Relay |
3 | Fourth Relay |
10 | Servo |
Parachute Servo PWM value in microseconds when parachute is released
Parachute Servo PWM value in microseconds when parachute is not released
Parachute min altitude above home. Parachute will not be released below this altitude. 0 to disable alt check.
Delay in millseconds between motor stop and chute release
Release parachute when critical sink rate is reached
Defines the radius of the circle the vehicle will fly when in Circle flight mode
Circle mode's turn rate in deg/sec. Positive to turn clockwise, negative for counter clockwise
0:Enable or disable using the pitch/roll stick control circle mode's radius and rate
Offset to be added to the compass x-axis values to compensate for metal in the frame
Offset to be added to the compass y-axis values to compensate for metal in the frame
Offset to be added to the compass z-axis values to compensate for metal in the frame
An angle to compensate between the true north and magnetic north
Enable or disable the automatic learning of compass offsets. You can enable learning either using a compass-only method that is suitable only for fixed wing aircraft or using the offsets learnt by the active EKF state estimator. If this option is enabled then the learnt offsets are saved when you disarm the vehicle. If InFlight learning is enabled then the compass with automatically start learning once a flight starts (must be armed). While InFlight learning is running you cannot use position control modes.
Value | Meaning |
---|---|
0 | Disabled |
1 | Internal-Learning |
2 | EKF-Learning |
3 | InFlight-Learning |
Enable or disable the use of the compass (instead of the GPS) for determining heading
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Enable or disable the automatic calculation of the declination based on gps location
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Set motor interference compensation type to disabled, throttle or current. Do not change manually.
Value | Meaning |
---|---|
0 | Disabled |
1 | Use Throttle |
2 | Use Current |
Multiplied by the current throttle and added to the compass's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to the compass's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to the compass's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
The orientation of the first external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Value | Meaning |
---|---|
0 | None |
1 | Yaw45 |
2 | Yaw90 |
3 | Yaw135 |
4 | Yaw180 |
5 | Yaw225 |
6 | Yaw270 |
7 | Yaw315 |
8 | Roll180 |
9 | Roll180Yaw45 |
10 | Roll180Yaw90 |
11 | Roll180Yaw135 |
12 | Pitch180 |
13 | Roll180Yaw225 |
14 | Roll180Yaw270 |
15 | Roll180Yaw315 |
16 | Roll90 |
17 | Roll90Yaw45 |
18 | Roll90Yaw90 |
19 | Roll90Yaw135 |
20 | Roll270 |
21 | Roll270Yaw45 |
22 | Roll270Yaw90 |
23 | Roll270Yaw135 |
24 | Pitch90 |
25 | Pitch270 |
26 | Pitch180Yaw90 |
27 | Pitch180Yaw270 |
28 | Roll90Pitch90 |
29 | Roll180Pitch90 |
30 | Roll270Pitch90 |
31 | Roll90Pitch180 |
32 | Roll270Pitch180 |
33 | Roll90Pitch270 |
34 | Roll180Pitch270 |
35 | Roll270Pitch270 |
36 | Roll90Pitch180Yaw90 |
37 | Roll90Yaw270 |
38 | Yaw293Pitch68Roll180 |
39 | Pitch315 |
40 | Roll90Pitch315 |
100 | Custom |
Configure compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. Set to 1 if the compass is externally connected. When externally connected the COMPASS_ORIENT option operates independently of the AHRS_ORIENTATION board orientation option. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Value | Meaning |
---|---|
0 | Internal |
1 | External |
2 | ForcedExternal |
Offset to be added to compass2's x-axis values to compensate for metal in the frame
Offset to be added to compass2's y-axis values to compensate for metal in the frame
Offset to be added to compass2's z-axis values to compensate for metal in the frame
Multiplied by the current throttle and added to compass2's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to compass2's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to compass2's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Offset to be added to compass3's x-axis values to compensate for metal in the frame
Offset to be added to compass3's y-axis values to compensate for metal in the frame
Offset to be added to compass3's z-axis values to compensate for metal in the frame
Multiplied by the current throttle and added to compass3's x-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to compass3's y-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Multiplied by the current throttle and added to compass3's z-axis values to compensate for motor interference (Offset per Amp or at Full Throttle)
Compass device id. Automatically detected, do not set manually
Second compass's device id. Automatically detected, do not set manually
Third compass's device id. Automatically detected, do not set manually
Enable or disable the secondary compass for determining heading.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
The orientation of a second external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Value | Meaning |
---|---|
0 | None |
1 | Yaw45 |
2 | Yaw90 |
3 | Yaw135 |
4 | Yaw180 |
5 | Yaw225 |
6 | Yaw270 |
7 | Yaw315 |
8 | Roll180 |
9 | Roll180Yaw45 |
10 | Roll180Yaw90 |
11 | Roll180Yaw135 |
12 | Pitch180 |
13 | Roll180Yaw225 |
14 | Roll180Yaw270 |
15 | Roll180Yaw315 |
16 | Roll90 |
17 | Roll90Yaw45 |
18 | Roll90Yaw90 |
19 | Roll90Yaw135 |
20 | Roll270 |
21 | Roll270Yaw45 |
22 | Roll270Yaw90 |
23 | Roll270Yaw135 |
24 | Pitch90 |
25 | Pitch270 |
26 | Pitch180Yaw90 |
27 | Pitch180Yaw270 |
28 | Roll90Pitch90 |
29 | Roll180Pitch90 |
30 | Roll270Pitch90 |
31 | Roll90Pitch180 |
32 | Roll270Pitch180 |
33 | Roll90Pitch270 |
34 | Roll180Pitch270 |
35 | Roll270Pitch270 |
36 | Roll90Pitch180Yaw90 |
37 | Roll90Yaw270 |
38 | Yaw293Pitch68Roll180 |
39 | Pitch315 |
40 | Roll90Pitch315 |
100 | Custom |
Configure second compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Value | Meaning |
---|---|
0 | Internal |
1 | External |
2 | ForcedExternal |
Enable or disable the tertiary compass for determining heading.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
The orientation of a third external compass relative to the vehicle frame. This value will be ignored unless this compass is set as an external compass. When set correctly in the northern hemisphere, pointing the nose and right side down should increase the MagX and MagY values respectively. Rolling the vehicle upside down should decrease the MagZ value. For southern hemisphere, switch increase and decrease. NOTE: For internal compasses, AHRS_ORIENT is used.
Value | Meaning |
---|---|
0 | None |
1 | Yaw45 |
2 | Yaw90 |
3 | Yaw135 |
4 | Yaw180 |
5 | Yaw225 |
6 | Yaw270 |
7 | Yaw315 |
8 | Roll180 |
9 | Roll180Yaw45 |
10 | Roll180Yaw90 |
11 | Roll180Yaw135 |
12 | Pitch180 |
13 | Roll180Yaw225 |
14 | Roll180Yaw270 |
15 | Roll180Yaw315 |
16 | Roll90 |
17 | Roll90Yaw45 |
18 | Roll90Yaw90 |
19 | Roll90Yaw135 |
20 | Roll270 |
21 | Roll270Yaw45 |
22 | Roll270Yaw90 |
23 | Roll270Yaw135 |
24 | Pitch90 |
25 | Pitch270 |
26 | Pitch180Yaw90 |
27 | Pitch180Yaw270 |
28 | Roll90Pitch90 |
29 | Roll180Pitch90 |
30 | Roll270Pitch90 |
31 | Roll90Pitch180 |
32 | Roll270Pitch180 |
33 | Roll90Pitch270 |
34 | Roll180Pitch270 |
35 | Roll270Pitch270 |
36 | Roll90Pitch180Yaw90 |
37 | Roll90Yaw270 |
38 | Yaw293Pitch68Roll180 |
39 | Pitch315 |
40 | Roll90Pitch315 |
100 | Custom |
Configure third compass so it is attached externally. This is auto-detected on PX4 and Pixhawk. If set to 0 or 1 then auto-detection by bus connection can override the value. If set to 2 then auto-detection will be disabled.
Value | Meaning |
---|---|
0 | Internal |
1 | External |
2 | ForcedExternal |
DIA_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_X in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Y in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Z in the compass soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_X in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Y in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Z in the compass2 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
DIA_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_X in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Y in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
ODI_Z in the compass3 soft-iron calibration matrix: [[DIA_X, ODI_X, ODI_Y], [ODI_X, DIA_Y, ODI_Z], [ODI_Y, ODI_Z, DIA_Z]]
This controls the fitness level required for a successful compass calibration. A lower value makes for a stricter fit (less likely to pass). This is the value used for the primary magnetometer. Other magnetometers get double the value.
Value | Meaning |
---|---|
4 | Very Strict |
8 | Strict |
16 | Default |
32 | Relaxed |
This sets the maximum allowed compass offset in calibration and arming checks
This is a bitmask of driver types to disable. If a driver type is set in this mask then that driver will not try to find a sensor at startup
This sets the range around the average value that new samples must be within to be accepted. This can help reduce the impact of noise on sensors that are on long I2C cables. The value is a percentage from the average value. A value of zero disables this filter.
When enabled this will automatically check the orientation of compasses on successful completion of compass calibration. If set to 2 then external compasses will have their orientation automatically corrected.
Value | Meaning |
---|---|
0 | Disabled |
1 | CheckOnly |
2 | CheckAndFix |
Compass device id with 1st order priority, set automatically if 0. Reboot required after change.
Compass device id with 2nd order priority, set automatically if 0. Reboot required after change.
Compass device id with 3rd order priority, set automatically if 0. Reboot required after change.
Setting this to Enabled(1) will enable the compass. Setting this to Disabled(0) will disable the compass. Note that this is separate from COMPASS_USE. This will enable the low level senor, and will enable logging of magnetometer data. To use the compass for navigation you must also set COMPASS_USE to 1.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Scaling factor for first compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
Scaling factor for 2nd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
Scaling factor for 3rd compass to compensate for sensor scaling errors. If this is 0 then no scaling is done
This sets options to change the behaviour of the compass
Extra 4th compass's device id. Automatically detected, do not set manually
Extra 5th compass's device id. Automatically detected, do not set manually
Extra 6th compass's device id. Automatically detected, do not set manually
Extra 7th compass's device id. Automatically detected, do not set manually
Extra 8th compass's device id. Automatically detected, do not set manually
Compass mounting position roll offset. Positive values = roll right, negative values = roll left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
Compass mounting position pitch offset. Positive values = pitch up, negative values = pitch down. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
Compass mounting position yaw offset. Positive values = yaw right, negative values = yaw left. This parameter is only used when COMPASS_ORIENT/2/3 is set to CUSTOM.
This enables per-motor compass corrections
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This is the exponential correction for the power output of the motor for per-motor compass correction
Compensation for X axis of motor1
Compensation for Y axis of motor1
Compensation for Z axis of motor1
Compensation for X axis of motor2
Compensation for Y axis of motor2
Compensation for Z axis of motor2
Compensation for X axis of motor3
Compensation for Y axis of motor3
Compensation for Z axis of motor3
Compensation for X axis of motor4
Compensation for Y axis of motor4
Compensation for Z axis of motor4
Type of AHRS device
Value | Meaning |
---|---|
0 | None |
1 | VectorNav |
Requested rate for AHRS device
This enables EKF2. Enabling EKF2 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=2. A reboot or restart will need to be performed after changing the value of EK2_ENABLE for it to take effect.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This controls use of GPS measurements : 0 = use 3D velocity & 2D position, 1 = use 2D velocity and 2D position, 2 = use 2D position, 3 = Inhibit GPS use - this can be useful when flying with an optical flow sensor in an environment where GPS quality is poor and subject to large multipath errors.
Value | Meaning |
---|---|
0 | GPS 3D Vel and 2D Pos |
1 | GPS 2D vel and 2D pos |
2 | GPS 2D pos |
3 | No GPS |
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
This sets the GPS horizontal position observation noise. Increasing it reduces the weighting of GPS horizontal position measurements.
This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position.
Primary height sensor used by the EKF. If a sensor other than Baro is selected and becomes unavailable, then the Baro sensor will be used as a fallback. NOTE: The EK2_RNG_USE_HGT parameter can be used to switch to range-finder when close to the ground in conjunction with EK2_ALT_SOURCE = 0 or 2 (Baro or GPS).
Value | Meaning |
---|---|
0 | Use Baro |
1 | Use Range Finder |
2 | Use GPS |
3 | Use Range Beacon |
This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors.
This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the Height measurements lag behind the inertial measurements.
This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states, when it will use a simpler magnetic heading fusion model that does not use magnetic field states and when it will use an alternative method of yaw determination to the magnetometer. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK2_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK2_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK2_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK2_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK2_MAG_CAL = 4 uses 3-axis fusion at all times. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK2_MAG_MASK parameter. NOTE: limited operation without a magnetometer or any other yaw sensor is possible by setting all COMPASS_USE, COMPASS_USE2, COMPASS_USE3, etc parameters to 0 with COMPASS_ENABLE set to 1. If this is done, the EK2_GSF_RUN and EK2_GSF_USE masks must be set to the same as EK2_IMU_MASK.
Value | Meaning |
---|---|
0 | When flying |
1 | When manoeuvring |
2 | Never |
3 | After first climb yaw reset |
4 | Always |
This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
This noise controls the rate of gyro scale factor learning. Increasing it makes rate gyro scale factor estimation faster and noisier.
This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
1 byte bitmap of IMUs to use in EKF2. A separate instance of EKF2 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF2 will fail to start.
This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Sets the time constant of the output complementary filter/predictor in centi-seconds.
This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
Range finder can be used as the primary height source when below this percentage of its maximum range (see RNGFND_MAX_CM). This will not work unless Baro or GPS height is selected as the primary height source vis EK2_ALT_SOURCE = 0 or 2 respectively. This feature should not be used for terrain following as it is designed for vertical takeoff and landing with climb above the range finder use height before commencing the mission, and with horizontal position changes below that height being limited to a flat region around the takeoff and landing point.
Specifies the maximum gradient of the terrain below the vehicle assumed when it is fusing range finder or optical flow to estimate terrain height.
This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the range beacon measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
Value | Meaning |
---|---|
0 | None |
1 | Navigation |
2 | Terrain |
This limits the difference between the learned earth magnetic field and the earth field from the world magnetic model tables. A value of zero means to disable the use of the WMM tables.
Specifies the crossover frequency of the complementary filter used to calculate the output predictor height rate derivative.
1 byte bitmap of which EKF2 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF2 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK2_GSF_USE, EK2_GSF_DELAY and EK2_GSF_MAXCOUNT parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK2_GSF_USE to 0.
1 byte bitmap of which EKF2 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK2_GSF_RUN parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF2 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF2 instance. Additionally the EKF2 will initiate a reset internally if navigation is lost for more than EK2_GSF_DELAY milli seconds.
If the inertial navigation calculation stops following the GPS and other positioning sensors for longer than EK2_GSF_DELAY milli-seconds, then the EKF2 code will generate a reset request internally and reset the yaw to the estimate from the EKF-GSF filter and reset the horizontal velocity and position to the GPS. This reset will not be performed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE parameter.
Sets the maximum number of times the EKF2 will be allowed to reset it's yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK2_GSF_USE parameter.
This enables EKF3. Enabling EKF3 only makes the maths run, it does not mean it will be used for flight control. To use it for flight control set AHRS_EKF_TYPE=3. A reboot or restart will need to be performed after changing the value of EK3_ENABLE for it to take effect.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set horizontal velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS horizontal velocity measurements.
This sets a lower limit on the speed accuracy reported by the GPS receiver that is used to set vertical velocity observation noise. If the model of receiver used does not provide a speed accurcy estimate, then the parameter value will be used. Increasing it reduces the weighting of the GPS vertical velocity measurements.
This sets the percentage number of standard deviations applied to the GPS velocity measurement innovation consistency check. Decreasing it makes it more likely that good measurements willbe rejected. Increasing it makes it more likely that bad measurements will be accepted.
This sets the GPS horizontal position observation noise. Increasing it reduces the weighting of GPS horizontal position measurements.
This sets the percentage number of standard deviations applied to the GPS position measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This controls the maximum radial uncertainty in position between the value predicted by the filter and the value measured by the GPS before the filter position and velocity states are reset to the GPS. Making this value larger allows the filter to ignore larger GPS glitches but also means that non-GPS errors such as IMU and compass can create a larger error in position before the filter is forced back to the GPS position.
This is the RMS value of noise in the altitude measurement. Increasing it reduces the weighting of the baro measurement and will make the filter respond more slowly to baro measurement errors, but will make it more sensitive to GPS and accelerometer errors.
This sets the percentage number of standard deviations applied to the height measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the Height measurements lag behind the inertial measurements.
This is the RMS value of noise in magnetometer measurements. Increasing it reduces the weighting on these measurements.
This determines when the filter will use the 3-axis magnetometer fusion model that estimates both earth and body fixed magnetic field states and when it will use a simpler magnetic heading fusion model that does not use magnetic field states. The 3-axis magnetometer fusion is only suitable for use when the external magnetic field environment is stable. EK3_MAG_CAL = 0 uses heading fusion on ground, 3-axis fusion in-flight, and is the default setting for Plane users. EK3_MAG_CAL = 1 uses 3-axis fusion only when manoeuvring. EK3_MAG_CAL = 2 uses heading fusion at all times, is recommended if the external magnetic field is varying and is the default for rovers. EK3_MAG_CAL = 3 uses heading fusion on the ground and 3-axis fusion after the first in-air field and yaw reset has completed, and is the default for copters. EK3_MAG_CAL = 4 uses 3-axis fusion at all times. EK3_MAG_CAL = 5 uses an external yaw sensor with simple heading fusion. NOTE : Use of simple heading magnetometer fusion makes vehicle compass calibration and alignment errors harder for the EKF to detect which reduces the sensitivity of the Copter EKF failsafe algorithm. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK3_MAG_MASK parameter. EK3_MAG_CAL = 6 uses an external yaw sensor with fallback to compass when the external sensor is not available if we are flying. NOTE: The fusion mode can be forced to 2 for specific EKF cores using the EK3_MAG_MASK parameter. NOTE: limited operation without a magnetometer or any other yaw sensor is possible by setting all COMPASS_USE, COMPASS_USE2, COMPASS_USE3, etc parameters to 0 and setting COMPASS_ENABLE to 0. If this is done, the EK3_GSF_RUN and EK3_GSF_USE masks must be set to the same as EK3_IMU_MASK. A yaw angle derived from IMU and GPS velocity data using a Gaussian Sum Filter (GSF) will then be used to align the yaw when flight commences and there is sufficient movement.
Value | Meaning |
---|---|
0 | When flying |
1 | When manoeuvring |
2 | Never |
3 | After first climb yaw reset |
4 | Always |
5 | Use external yaw sensor (Deprecated in 4.1+ see EK3_SRCn_YAW) |
6 | External yaw sensor with compass fallback (Deprecated in 4.1+ see EK3_SRCn_YAW) |
This sets the percentage number of standard deviations applied to the magnetometer measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the RMS value of noise in equivalent airspeed measurements used by planes. Increasing it reduces the weighting of airspeed measurements and will make wind speed estimates less noisy and slower to converge. Increasing also increases navigation errors when dead-reckoning without GPS measurements.
This sets the percentage number of standard deviations applied to the airspeed measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the RMS value of noise in the range finder measurement. Increasing it reduces the weighting on this measurement.
This sets the percentage number of standard deviations applied to the range finder innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This sets the magnitude maximum optical flow rate in rad/sec that will be accepted by the filter
This is the RMS value of noise and errors in optical flow measurements. Increasing it reduces the weighting on these measurements.
This sets the percentage number of standard deviations applied to the optical flow innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the optical flow measurements lag behind the inertial measurements. It is the time from the end of the optical flow averaging period and does not include the time delay due to the 100msec of averaging within the flow sensor.
This control disturbance noise controls the growth of estimated error due to gyro measurement errors excluding bias. Increasing it makes the flter trust the gyro measurements less and other measurements more.
This control disturbance noise controls the growth of estimated error due to accelerometer measurement errors excluding bias. Increasing it makes the flter trust the accelerometer measurements less and other measurements more.
This state process noise controls growth of the gyro delta angle bias state error estimate. Increasing it makes rate gyro bias estimation faster and noisier.
This noise controls the growth of the vertical accelerometer delta velocity bias state error estimate. Increasing it makes accelerometer bias estimation faster and noisier.
This state process noise controls the growth of wind state error estimates. Increasing it makes wind estimation faster and noisier.
This controls how much the process noise on the wind states is increased when gaining or losing altitude to take into account changes in wind speed and direction with altitude. Increasing this parameter increases how rapidly the wind states adapt when changing altitude, but does make wind velocity estimation noiser.
This is a 1 byte bitmap controlling which GPS preflight checks are performed. Set to 0 to bypass all checks. Set to 255 perform all checks. Set to 3 to check just the number of satellites and HDoP. Set to 31 for the most rigorous checks that will still allow checks to pass when the copter is moving, eg launch from a boat.
1 byte bitmap of IMUs to use in EKF3. A separate instance of EKF3 will be started for each IMU selected. Set to 1 to use the first IMU only (default), set to 2 to use the second IMU only, set to 3 to use the first and second IMU. Additional IMU's can be used up to a maximum of 6 if memory and processing resources permit. There may be insufficient memory and processing resources to run multiple instances. If this occurs EKF3 will fail to start.
This scales the thresholds that are used to check GPS accuracy before it is used by the EKF. A value of 100 is the default. Values greater than 100 increase and values less than 100 reduce the maximum GPS error the EKF will accept. A value of 200 will double the allowable GPS error.
This sets the amount of position variation that the EKF allows for when operating without external measurements (eg GPS or optical flow). Increasing this parameter makes the EKF attitude estimate less sensitive to vehicle manoeuvres but more sensitive to IMU errors.
1 byte bitmap controlling use of sideslip angle fusion for estimation of non wind states during operation of 'fly forward' vehicle types such as fixed wing planes. By assuming that the angle of sideslip is small, the wind velocity state estimates are corrected whenever the EKF is not dead reckoning (e.g. has an independent velocity or position sensor such as GPS). This behaviour is on by default and cannot be disabled. When the EKF is dead reckoning, the wind states are used as a reference, enabling use of the small angle of sideslip assumption to correct non wind velocity states (eg attitude, velocity, position, etc) and improve navigation accuracy. This behaviour is on by default and cannot be disabled. The behaviour controlled by this parameter is the use of the small angle of sideslip assumption to correct non wind velocity states when the EKF is NOT dead reckoning. This is primarily of benefit to reduce the buildup of yaw angle errors during straight and level flight without a yaw sensor (e.g. magnetometer or dual antenna GPS yaw) provided aerobatic flight maneuvers with large sideslip angles are not performed. The 'always' option might be used where the yaw sensor is intentionally not fitted or disabled. The 'WhenNoYawSensor' option might be used if a yaw sensor is fitted, but protection against in-flight failure and continual rejection by the EKF is desired. For vehicles operated within visual range of the operator performing frequent turning maneuvers, setting this parameter is unnecessary.
This is the RMS value of noise in yaw measurements from the magnetometer. Increasing it reduces the weighting on these measurements.
This sets the percentage number of standard deviations applied to the magnetometer yaw measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
Sets the time constant of the output complementary filter/predictor in centi-seconds.
This state process noise controls the growth of earth magnetic field state error estimates. Increasing it makes earth magnetic field estimation faster and noisier.
This state process noise controls the growth of body magnetic field state error estimates. Increasing it makes magnetometer bias error estimation faster and noisier.
Range finder can be used as the primary height source when below this percentage of its maximum range (see RNGFND_MAX_CM). This will not work unless Baro or GPS height is selected as the primary height source vis EK3_ALT_SOURCE = 0 or 2 respectively. This feature should not be used for terrain following as it is designed for vertical takeoff and landing with climb above the range finder use height before commencing the mission, and with horizontal position changes below that height being limited to a flat region around the takeoff and landing point.
Specifies the maximum gradient of the terrain below the vehicle when it is using range finder as a height reference
This is the RMS value of noise in the range beacon measurement. Increasing it reduces the weighting on this measurement.
This sets the percentage number of standard deviations applied to the range beacon measurement innovation consistency check. Decreasing it makes it more likely that good measurements will be rejected. Increasing it makes it more likely that bad measurements will be accepted.
This is the number of msec that the range beacon measurements lag behind the inertial measurements.
The range finder will not be used as the primary height source when the horizontal ground speed is greater than this value.
The accelerometer bias state will be limited to +- this value
1 byte bitmap of EKF cores that will disable magnetic field states and use simple magnetic heading fusion at all times. This parameter enables specified cores to be used as a backup for flight into an environment with high levels of external magnetic interference which may degrade the EKF attitude estimate when using 3-axis magnetometer fusion. NOTE : Use of a different magnetometer fusion algorithm on different cores makes unwanted EKF core switches due to magnetometer errors more likely.
When a height sensor other than GPS is used as the primary height source by the EKF, the position of the zero height datum is defined by that sensor and its frame of reference. If a GPS height measurement is also available, then the height of the WGS-84 height datum used by the EKF can be corrected so that the height returned by the getLLH() function is compensated for primary height sensor drift and change in datum over time. The first two bit positions control when the height datum will be corrected. Correction is performed using a Bayes filter and only operates when GPS quality permits. The third bit position controls where the corrections to the GPS reference datum are applied. Corrections can be applied to the local vertical position or to the reported EKF origin height (default).
This is the 1-STD odometry velocity observation error that will be assumed when maximum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
This is the 1-STD odometry velocity observation error that will be assumed when minimum quality is reported by the sensor. When quality is between max and min, the error will be calculated using linear interpolation between VIS_VERR_MIN and VIS_VERR_MAX.
This is the 1-STD odometry velocity observation error that will be assumed when wheel encoder data is being fused.
Controls if the optical flow data is fused into the 24-state navigation estimator OR the 1-state terrain height estimator.
Value | Meaning |
---|---|
0 | None |
1 | Navigation |
2 | Terrain |
Specifies the crossover frequency of the complementary filter used to calculate the output predictor height rate derivative.
This limits the difference between the learned earth magnetic field and the earth field from the world magnetic model tables. A value of zero means to disable the use of the WMM tables.
1 byte bitmap of which EKF3 instances run an independant EKF-GSF yaw estimator to provide a backup yaw estimate that doesn't rely on magnetometer data. This estimator uses IMU, GPS and, if available, airspeed data. EKF-GSF yaw estimator data for the primary EKF3 instance will be logged as GSF0 and GSF1 messages. Use of the yaw estimate generated by this algorithm is controlled by the EK3_GSF_USE, EK3_GSF_DELAY and EK3_GSF_MAXCOUNT parameters. To run the EKF-GSF yaw estimator in ride-along and logging only, set EK3_GSF_USE to 0.
1 byte bitmap of which EKF3 instances will use the output from the EKF-GSF yaw estimator that has been turned on by the EK3_GSF_RUN parameter. If the inertial navigation calculation stops following the GPS, then the vehicle code can request EKF3 to attempt to resolve the issue, either by performing a yaw reset if enabled by this parameter by switching to another EKF3 instance. Additionally the EKF3 will initiate a reset internally if navigation is lost for more than EK3_GSF_DELAY milli seconds.
If the inertial navigation calculation stops following the GPS and other positioning sensors for longer than EK3_GSF_DELAY milli-seconds, then the EKF3 code will generate a reset request internally and reset the yaw to the estimate from the EKF-GSF filter and reset the horizontal velocity and position to the GPS. This reset will not be performed unless the use of the EKF-GSF yaw estimate is enabled via the EK3_GSF_USE parameter.
Sets the maximum number of times the EKF3 will be allowed to reset it's yaw to the estimate from the EKF-GSF yaw estimator. No resets will be allowed unless the use of the EKF-GSF yaw estimate is enabled via the EK3_GSF_USE parameter.
lanes have to be consistently better than the primary by at least this threshold to reduce their overall relativeCoreError, lowering this makes lane switching more sensitive to smaller error differences
These options control the affinity between sensor instances and EKF cores
Ratio of mass to drag coefficient measured along the X body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the frontal area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter.
Ratio of mass to drag coefficient measured along the Y body axis. This parameter enables estimation of wind drift for vehicles with bluff bodies and without propulsion forces in the X and Y direction (eg multicopters). The drag produced by this effect scales with speed squared. Set to a postive value > 1.0 to enable. A starting value is the mass in Kg divided by the side area. The predicted drag from the rotors is specified separately by the EK3_MCOEF parameter.
This sets the amount of noise used when fusing X and Y acceleration as an observation that enables esitmation of wind velocity for multi-rotor vehicles. This feature is enabled by the EK3_BCOEF_X and EK3_BCOEF_Y parameters
This parameter is used to predict the drag produced by the rotors when flying a multi-copter, enabling estimation of wind drift. The drag produced by this effect scales with speed not speed squared and is produced because some of the air velocity normal to the rotors axis of rotation is lost when passing through the rotor disc which changes the momentum of the airflow causing drag. For unducted rotors the effect is roughly proportional to the area of the propeller blades when viewed side on and changes with different propellers. It is higher for ducted rotors. For example if flying at 15 m/s at sea level conditions produces a rotor induced drag acceleration of 1.5 m/s/s, then EK3_MCOEF would be set to 0.1 = (1.5/15.0). Set EK3_MCOEF to a postive value to enable wind estimation using this drag effect. To account for the drag produced by the body which scales with speed squared, see documentation for the EK3_BCOEF_X and EK3_BCOEF_Y parameters.
This parameter is adjust the sensitivity of the on ground not moving test which is used to assist with learning the yaw gyro bias and stopping yaw drift before flight when operating without a yaw sensor. Bigger values allow the detection of a not moving condition with noiser IMU data. Check the XKFM data logged when the vehicle is on ground not moving and adjust the value of OGNM_TEST_SF to be slightly higher than the maximum value of the XKFM.ADR, XKFM.ALR, XKFM.GDR and XKFM.GLR test levels.
Position Horizontal Source (Primary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Horizontal Source
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
5 | OpticalFlow |
6 | ExternalNav |
7 | WheelEncoder |
Position Vertical Source
Value | Meaning |
---|---|
0 | None |
1 | Baro |
2 | RangeFinder |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Vertical Source
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Yaw Source
Value | Meaning |
---|---|
0 | None |
1 | Compass |
2 | GPS |
3 | GPS with Compass Fallback |
6 | ExternalNav |
8 | GSF |
Position Horizontal Source (Secondary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Horizontal Source (Secondary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
5 | OpticalFlow |
6 | ExternalNav |
7 | WheelEncoder |
Position Vertical Source (Secondary)
Value | Meaning |
---|---|
0 | None |
1 | Baro |
2 | RangeFinder |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Vertical Source (Secondary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Yaw Source (Secondary)
Value | Meaning |
---|---|
0 | None |
1 | Compass |
2 | GPS |
3 | GPS with Compass Fallback |
6 | ExternalNav |
8 | GSF |
Position Horizontal Source (Tertiary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Horizontal Source (Tertiary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
5 | OpticalFlow |
6 | ExternalNav |
7 | WheelEncoder |
Position Vertical Source (Tertiary)
Value | Meaning |
---|---|
0 | None |
1 | Baro |
2 | RangeFinder |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Velocity Vertical Source (Tertiary)
Value | Meaning |
---|---|
0 | None |
3 | GPS |
4 | Beacon |
6 | ExternalNav |
Yaw Source (Tertiary)
Value | Meaning |
---|---|
0 | None |
1 | Compass |
2 | GPS |
3 | GPS with Compass Fallback |
6 | ExternalNav |
8 | GSF |
EKF Source Options
Allows you to enable (1) or disable (0) the fence functionality
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Enabled fence types held as bitmask
Value | Meaning |
---|---|
0 | None |
1 | Max altitude |
2 | Circle |
3 | Max altitude and Circle |
4 | Polygon |
5 | Max altitude and Polygon |
6 | Circle and Polygon |
7 | Max altitude circle and Polygon |
8 | Min altitude |
What action should be taken when fence is breached
Value | Meaning |
---|---|
0 | Report Only |
1 | RTL or Land |
2 | Always Land |
3 | SmartRTL or RTL or Land |
4 | Brake or Land |
5 | SmartRTL or Land |
Maximum altitude allowed before geofence triggers
Circle fence radius which when breached will cause an RTL
Distance that autopilot's should maintain from the fence to avoid a breach
Number of polygon points saved in eeprom (do not update manually)
Minimum altitude allowed before geofence triggers
Enable Gyro FFT analyser
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Lower bound of FFT frequency detection in Hz. On larger vehicles the minimum motor frequency is likely to be significantly lower than for smaller vehicles.
Upper bound of FFT frequency detection in Hz. On smaller vehicles the maximum motor frequency is likely to be significantly higher than for larger vehicles.
Sampling mode (and therefore rate). 0: Gyro rate sampling, 1: Fast loop rate sampling, 2: Fast loop rate / 2 sampling, 3: Fast loop rate / 3 sampling. Takes effect on reboot.
Size of window to be used in FFT calculations. Takes effect on reboot. Must be a power of 2 and between 32 and 512. Larger windows give greater frequency resolution but poorer time resolution, consume more CPU time and may not be appropriate for all vehicles. Time and frequency resolution are given by the sample-rate / window-size. Windows of 256 are only really recommended for F7 class boards, windows of 512 or more H7 class.
Percentage of window to be overlapped before another frame is process. Takes effect on reboot. A good default is 50% overlap. Higher overlap results in more processed frames but not necessarily more temporal resolution. Lower overlap results in lost information at the frame edges.
The learned hover noise frequency
FFT learned thrust reference for the hover frequency and FFT minimum frequency.
FFT SNR reference threshold in dB at which a signal is determined to be present.
FFT attenuation level in dB for bandwidth calculation and peak detection. The bandwidth is calculated by comparing peak power output with the attenuated version. The default of 15 has shown to be a good compromise in both simulations and real flight.
FFT learned bandwidth at hover for the attenuation frequencies.
FFT harmonic fit frequency threshold percentage at which a signal of the appropriate frequency is determined to be the harmonic of another. Signals that have a harmonic relationship that varies at most by this percentage are considered harmonics of each other for the purpose of selecting the harmonic notch frequency. If a match is found then the lower frequency harmonic is always used as the basis for the dynamic harmonic notch. A value of zero completely disables harmonic matching.
The FFT harmonic peak target that should be returned by FTN1.PkAvg. The resulting value will be used by the harmonic notch if configured to track the FFT frequency. By default the appropriate peak is auto-detected based on the harmonic fit between peaks and the energy-weighted average frequency on roll on pitch is used. Setting this to 1 will always target the highest energy peak. Setting this to 2 will target the highest energy peak that is lower in frequency than the highest energy peak. Setting this to 3 will target the highest energy peak that is higher in frequency than the highest energy peak. Setting this to 4 will target the highest energy peak on the roll axis only and only the roll frequency will be used (some vehicles have a much more pronounced peak on roll). Setting this to 5 will target the highest energy peak on the pitch axis only and only the pitch frequency will be used (some vehicles have a much more pronounced peak on roll).
Value | Meaning |
---|---|
0 | Auto |
1 | Center Frequency |
2 | Lower-Shoulder Frequency |
3 | Upper-Shoulder Frequency |
4 | Roll-Axis |
5 | Pitch-Axis |
FlowHold (horizontal) P gain.
FlowHold (horizontal) I gain
FlowHold (horizontal) integrator maximum
FlowHold (horizontal) filter on input to control
Controls maximum apparent flow rate in flowhold
Filter frequency for flow data
Minimum flow quality to use flow position hold
Controls deceleration rate on stick release
Optical flow sensor type
Value | Meaning |
---|---|
0 | None |
1 | PX4Flow |
2 | Pixart |
3 | Bebop |
4 | CXOF |
5 | MAVLink |
6 | UAVCAN |
7 | MSP |
8 | UPFLOW |
This sets the parts per thousand scale factor correction applied to the flow sensor X axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the X axis optical flow reading by 0.1%. Negative values reduce the scale factor.
This sets the parts per thousand scale factor correction applied to the flow sensor Y axis optical rate. It can be used to correct for variations in effective focal length. Each positive increment of 1 increases the scale factor applied to the Y axis optical flow reading by 0.1%. Negative values reduce the scale factor.
Specifies the number of centi-degrees that the flow sensor is yawed relative to the vehicle. A sensor with its X-axis pointing to the right of the vehicle X axis has a positive yaw angle.
X position of the optical flow sensor focal point in body frame. Positive X is forward of the origin.
Y position of the optical flow sensor focal point in body frame. Positive Y is to the right of the origin.
Z position of the optical flow sensor focal point in body frame. Positive Z is down from the origin.
This is used to select between multiple possible I2C addresses for some sensor types. For PX4Flow you can choose 0 to 7 for the 8 possible addresses on the I2C bus.
Enabled/disable following a target
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Follow target's mavlink system id
Follow distance maximum. targets further than this will be ignored
Follow offset type
Value | Meaning |
---|---|
0 | North-East-Down |
1 | Relative to lead vehicle heading |
Follow offsets in meters north/forward. If positive, this vehicle fly ahead or north of lead vehicle. Depends on FOLL_OFS_TYPE
Follow offsets in meters east/right. If positive, this vehicle will fly to the right or east of lead vehicle. Depends on FOLL_OFS_TYPE
Follow offsets in meters down. If positive, this vehicle will fly below the lead vehicle
Follow yaw behaviour
Value | Meaning |
---|---|
0 | None |
1 | Face Lead Vehicle |
2 | Same as Lead vehicle |
3 | Direction of Flight |
Follow position error P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
Follow altitude type
Value | Meaning |
---|---|
0 | absolute |
1 | relative |
Change the uplink sensor id (SPort only)
Value | Meaning |
---|---|
-1 | Disable |
7 | 7 |
8 | 8 |
9 | 9 |
10 | 10 |
11 | 11 |
12 | 12 |
13 | 13 |
14 | 14 |
15 | 15 |
16 | 16 |
17 | 17 |
18 | 18 |
19 | 19 |
20 | 20 |
21 | 21 |
22 | 22 |
23 | 23 |
24 | 24 |
25 | 25 |
26 | 26 |
Change the first extra downlink sensor id (SPort only)
Value | Meaning |
---|---|
-1 | Disable |
7 | 7 |
8 | 8 |
9 | 9 |
10 | 10 |
11 | 11 |
12 | 12 |
13 | 13 |
14 | 14 |
15 | 15 |
16 | 16 |
17 | 17 |
18 | 18 |
19 | 19 |
20 | 20 |
21 | 21 |
22 | 22 |
23 | 23 |
24 | 24 |
25 | 25 |
26 | 26 |
Change the second extra downlink sensor id (SPort only)
Value | Meaning |
---|---|
-1 | Disable |
7 | 7 |
8 | 8 |
9 | 9 |
10 | 10 |
11 | 11 |
12 | 12 |
13 | 13 |
14 | 14 |
15 | 15 |
16 | 16 |
17 | 17 |
18 | 18 |
19 | 19 |
20 | 20 |
21 | 21 |
22 | 22 |
23 | 23 |
24 | 24 |
25 | 25 |
26 | 26 |
Generator type
Value | Meaning |
---|---|
0 | Disabled |
1 | IE 650w 800w Fuel Cell |
2 | IE 2.4kW Fuel Cell |
3 | Richenpower |
GPS type of 1st GPS
Value | Meaning |
---|---|
0 | None |
1 | AUTO |
2 | uBlox |
3 | MTK |
4 | MTK19 |
5 | NMEA |
6 | SiRF |
7 | HIL |
8 | SwiftNav |
9 | UAVCAN |
10 | SBF |
11 | GSOF |
13 | ERB |
14 | MAV |
15 | NOVA |
16 | HemisphereNMEA |
17 | uBlox-MovingBaseline-Base |
18 | uBlox-MovingBaseline-Rover |
19 | MSP |
20 | AllyStar |
21 | ExternalAHRS |
GPS type of 2nd GPS
Value | Meaning |
---|---|
0 | None |
1 | AUTO |
2 | uBlox |
3 | MTK |
4 | MTK19 |
5 | NMEA |
6 | SiRF |
7 | HIL |
8 | SwiftNav |
9 | UAVCAN |
10 | SBF |
11 | GSOF |
13 | ERB |
14 | MAV |
15 | NOVA |
16 | HemisphereNMEA |
17 | uBlox-MovingBaseline-Base |
18 | uBlox-MovingBaseline-Rover |
19 | MSP |
20 | AllyStar |
21 | ExternalAHRS |
Navigation filter engine setting
Value | Meaning |
---|---|
0 | Portable |
2 | Stationary |
3 | Pedestrian |
4 | Automotive |
5 | Sea |
6 | Airborne1G |
7 | Airborne2G |
8 | Airborne4G |
Automatic switchover to GPS reporting best lock, 1:UseBest selects the GPS with highest status, if both are equal the GPS with highest satellite count is used 4:Use primary if 3D fix or better, will revert to 'UseBest' behaviour if 3D fix is lost on primary
Value | Meaning |
---|---|
0 | Use primary |
1 | UseBest |
2 | Blend |
4 | Use primary if 3D fix or better |
Sets the minimum type of differential GPS corrections required before allowing to switch into DGPS mode.
Value | Meaning |
---|---|
0 | Any |
50 | FloatRTK |
100 | IntegerRTK |
This sets the SBAS (satellite based augmentation system) mode if available on this GPS. If set to 2 then the SBAS mode is not changed in the GPS. Otherwise the GPS will be reconfigured to enable/disable SBAS. Disabling SBAS may be worthwhile in some parts of the world where an SBAS signal is available but the baseline is too long to be useful.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | NoChange |
This sets the minimum elevation of satellites above the horizon for them to be used for navigation. Setting this to -100 leaves the minimum elevation set to the GPS modules default.
The GGS can send raw serial packets to inject data to multiple GPSes.
Value | Meaning |
---|---|
0 | send to first GPS |
1 | send to 2nd GPS |
127 | send to all |
Masked with the SBP msg_type field to determine whether SBR1/SBR2 data is logged
Value | Meaning |
---|---|
0 | None (0x0000) |
-1 | All (0xFFFF) |
-256 | External only (0xFF00) |
Handles logging raw data; on uBlox chips that support raw data this will log RXM messages into logger; on Septentrio this will log on the equipment's SD card and when set to 2, the autopilot will try to stop logging after disarming and restart after arming
Value | Meaning |
---|---|
0 | Ignore |
1 | Always log |
2 | Stop logging when disarmed (SBF only) |
5 | Only log every five samples (uBlox only) |
Bitmask for what GNSS system to use on the first GPS (all unchecked or zero to leave GPS as configured)
Value | Meaning |
---|---|
0 | Leave as currently configured |
1 | GPS-NoSBAS |
3 | GPS+SBAS |
4 | Galileo-NoSBAS |
6 | Galileo+SBAS |
8 | Beidou |
51 | GPS+IMES+QZSS+SBAS (Japan Only) |
64 | GLONASS |
66 | GLONASS+SBAS |
67 | GPS+GLONASS+SBAS |
Determines whether the configuration for this GPS should be written to non-volatile memory on the GPS. Currently working for UBlox 6 series and above.
Value | Meaning |
---|---|
0 | Do not save config |
1 | Save config |
2 | Save only when needed |
Bitmask for what GNSS system to use on the second GPS (all unchecked or zero to leave GPS as configured)
Value | Meaning |
---|---|
0 | Leave as currently configured |
1 | GPS-NoSBAS |
3 | GPS+SBAS |
4 | Galileo-NoSBAS |
6 | Galileo+SBAS |
8 | Beidou |
51 | GPS+IMES+QZSS+SBAS (Japan Only) |
64 | GLONASS |
66 | GLONASS+SBAS |
67 | GPS+GLONASS+SBAS |
Controls if the autopilot should automatically configure the GPS based on the parameters and default settings
Value | Meaning |
---|---|
0 | Disables automatic configuration |
1 | Enable automatic configuration |
Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.
Value | Meaning |
---|---|
100 | 10Hz |
125 | 8Hz |
200 | 5Hz |
Controls how often the GPS should provide a position update. Lowering below 5Hz(default) is not allowed. Raising the rate above 5Hz usually provides little benefit and for some GPS (eg Ublox M9N) can severely impact performance.
Value | Meaning |
---|---|
100 | 10Hz |
125 | 8Hz |
200 | 5Hz |
X position of the first GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Y position of the first GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Z position of the first GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
X position of the second GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Y position of the second GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Z position of the second GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
Controls the amount of GPS measurement delay that the autopilot compensates for. Set to zero to use the default delay for the detected GPS type.
Determines which of the accuracy measures Horizontal position, Vertical Position and Speed are used to calculate the weighting on each GPS receiver when soft switching has been selected by setting GPS_AUTO_SWITCH to 2(Blend)
Controls the slowest time constant applied to the calculation of GPS position and height offsets used to adjust different GPS receivers for steady state position differences.
Additional backend specific options
The physical COM port on the connected device, currently only applies to SBF GPS
The physical COM port on the connected device, currently only applies to SBF GPS
This GPS will be used when GPS_AUTO_SWITCH is 0 and used preferentially with GPS_AUTO_SWITCH = 4.
Value | Meaning |
---|---|
0 | FirstGPS |
1 | SecondGPS |
GPS Node id for discovered first.
GPS Node id for discovered second.
GPS Node id for first GPS. If 0 the gps will be automatically selected on first come basis.
GPS Node id for second GPS. If 0 the gps will be automatically selected on first come basis.
Controls the type of moving base used if using moving base.
Value | Meaning |
---|---|
0 | Relative to alternate GPS instance |
1 | RelativeToCustomBase |
X position of the base GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Y position of the base GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Z position of the base GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
Controls the type of moving base used if using moving base.
Value | Meaning |
---|---|
0 | Relative to alternate GPS instance |
1 | RelativeToCustomBase |
X position of the base GPS antenna in body frame. Positive X is forward of the origin. Use antenna phase centroid location if provided by the manufacturer.
Y position of the base GPS antenna in body frame. Positive Y is to the right of the origin. Use antenna phase centroid location if provided by the manufacturer.
Z position of the base GPS antenna in body frame. Positive Z is down from the origin. Use antenna phase centroid location if provided by the manufacturer.
Gripper enable/disable
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Gripper enable/disable
Value | Meaning |
---|---|
0 | None |
1 | Servo |
2 | EPM |
PWM value in microseconds sent to Gripper to initiate grabbing the cargo
PWM value in microseconds sent to Gripper to release the cargo
PWM value in microseconds sent to grabber when not grabbing or releasing
Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable
Refer to https://docs.zubax.com/opengrab_epm_v3#UAVCAN_interface
Tail type selection. Simpler yaw controller used if external gyro is selected. Direct Drive Variable Pitch is used for tails that have a motor that is governed at constant speed by an ESC. Tail pitch is still accomplished with a servo. Direct Drive Fixed Pitch (DDFP) CW is used for helicopters with a rotor that spins clockwise when viewed from above. Direct Drive Fixed Pitch (DDFP) CCW is used for helicopters with a rotor that spins counter clockwise when viewed from above. In both DDFP cases, no servo is used for the tail and the tail motor esc is controlled by the yaw axis.
Value | Meaning |
---|---|
0 | Servo only |
1 | Servo with ExtGyro |
2 | DirectDrive VarPitch |
3 | DirectDrive FixedPitch CW |
4 | DirectDrive FixedPitch CCW |
5 | DDVP with external governor |
PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro
Feed-forward compensation to automatically add rudder input when collective pitch is increased. Can be positive or negative depending on mechanics.
Flybar present or not. Affects attitude controller used during ACRO flight mode
Value | Meaning |
---|---|
0 | NoFlybar |
1 | Flybar |
Direct drive, variable pitch tail ESC speed in percent output to the tail motor esc (HeliTailRSC Servo) when motor interlock enabled (throttle hold off).
PWM in microseconds sent to external gyro on ch7 when tail type is Servo w/ ExtGyro. A value of zero means to use H_GYR_GAIN
H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
Value | Meaning |
---|---|
0 | H3 Generic |
1 | H1 non-CPPM |
2 | H3_140 |
3 | H3_120 |
4 | H4_90 |
5 | H4_45 |
Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
This linearizes the swashplate servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Automatically set when H3 generic swash type is selected for swashplate. Do not set manually.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
Azimuth position on swashplate for servo 2 with the front of the heli being 0 deg
Azimuth position on swashplate for servo 3 with the front of the heli being 0 deg
Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
Sets the dual mode of the heli, either as tandem or as transverse.
Value | Meaning |
---|---|
0 | Longitudinal |
1 | Transverse |
2 | Intermeshing |
Scaling factor applied to the differential-collective-pitch
Feed-forward compensation to automatically add yaw input when differential collective pitch is applied. Disabled for intermeshing mode.
Scaler for mixing yaw into roll or pitch.
Lowest possible servo position in PWM microseconds for swashplate 2
Highest possible servo position in PWM microseconds for swashplate 2
Swash servo position in PWM microseconds corresponding to zero collective pitch for the rear swashplate (or zero lift for Asymmetrical blades)
H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
Value | Meaning |
---|---|
0 | H3 Generic |
1 | H1 non-CPPM |
2 | H3_140 |
3 | H3_120 |
4 | H4_90 |
5 | H4_45 |
Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
This linearizes the swashplate 1 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Automatically set when H3 generic swash type is selected for swashplate 1. Do not set manually.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
Azimuth position on swashplate 1 for servo 2 with the front of the heli being 0 deg
Azimuth position on swashplate 1 for servo 3 with the front of the heli being 0 deg
Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
H3 is generic, three-servo only. H3_120/H3_140 plates have Motor1 left side, Motor2 right side, Motor3 elevator in rear. HR3_120/HR3_140 have Motor1 right side, Motor2 left side, Motor3 elevator in front - use H3_120/H3_140 and reverse servo and collective directions as necessary. For all H3_90 swashplates use H4_90 and don't use servo output for the missing servo. For H4-90 Motors1&2 are left/right respectively, Motors3&4 are rear/front respectively. For H4-45 Motors1&2 are LF/RF, Motors3&4 are LR/RR
Value | Meaning |
---|---|
0 | H3 Generic |
1 | H1 non-CPPM |
2 | H3_140 |
3 | H3_120 |
4 | H4_90 |
5 | H4_45 |
Direction collective moves for positive pitch. 0 for Normal, 1 for Reversed
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
This linearizes the swashplate 2 servo's mechanical output to account for nonlinear output due to arm rotation. This requires a specific setup procedure to work properly. The servo arm must be centered on the mechanical throw at the servo trim position and the servo trim position kept as close to 1500 as possible. Leveling the swashplate can only be done through the pitch links. See the ardupilot wiki for more details on setup.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Automatically set when H3 generic swash type is selected for swashplate 2. Do not set manually.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Azimuth position on swashplate for servo 1 with the front of the heli being 0 deg
Azimuth position on swashplate 2 for servo 2 with the front of the heli being 0 deg
Azimuth position on swashplate 2 for servo 3 with the front of the heli being 0 deg
Only for H3 swashplate. If pitching the swash forward induces a roll, this can be correct the problem
Removes I term bias due to center of gravity offsets or discrepancies between rotors in swashplate setup. If DCP axis has I term bias while hovering in calm winds, use value of bias in DCP_TRIM to re-center I term.
For intermeshing mode only. Yaw revereser smoothing exponent, smoothen transition near zero collective region. Increase this parameter to shink smoothing range. Set to -1 to disable reverser.
Lowest possible servo position in PWM microseconds for the swashplate
Highest possible servo position in PWM microseconds for the swashplate
Swash servo position in PWM microseconds corresponding to zero collective pitch (or zero lift for Asymmetrical blades)
Manual servo override for swash set-up. Do not set this manually!
Value | Meaning |
---|---|
0 | Disabled |
1 | Passthrough |
2 | Max collective |
3 | Mid collective |
4 | Min collective |
Maximum cyclic pitch angle of the swash plate. There are no units to this parameter. This should be adjusted to get the desired cyclic blade pitch for the pitch and roll axes. Typically this should be 6-7 deg (measured blade pitch angle difference between stick centered and stick max deflection.
Number of cycles to run servo test on boot-up
Collective needed to hover expressed as a number from 0 to 1 where 0 is H_COL_MIN and 1 is H_COL_MAX
Enable/Disable automatic learning of hover collective
Value | Meaning |
---|---|
0 | Disabled |
1 | Learn |
2 | Learn and Save |
Bitmask of heli options. Bit 0 changes how the pitch, roll, and yaw axis integrator term is managed for low speed and takeoff/landing. In AC 4.0 and earlier, scheme uses a leaky integrator for ground speeds less than 5 m/s and won't let the steady state integrator build above ILMI. The integrator is allowed to build to the ILMI value when it is landed. The other integrator management scheme bases integrator limiting on takeoff and landing. Whenever the aircraft is landed the integrator is set to zero. When the aicraft is airborne, the integrator is only limited by IMAX.
Value | Meaning |
---|---|
0 | I term management based landed state |
1 | Leaky I(4.0 and earlier) |
Throttle (HeliRSC Servo) output in percent to the external motor governor when motor interlock enabled (throttle hold off).
Selects the type of rotor speed control used to determine throttle output to the HeliRSC servo channel when motor interlock is enabled (throttle hold off). RC Passthrough sends the input from the RC Motor Interlock channel as throttle output. External Gov SetPoint sends the RSC SetPoint parameter value as throttle output. Throttle Curve uses the 5 point throttle curve to determine throttle output based on the collective output. Governor is ArduCopter's built-in governor that uses the throttle curve for a feed forward throttle command to determine throttle output.
Value | Meaning |
---|---|
1 | RC Passthrough |
2 | External Gov SetPoint |
3 | Throttle Curve |
4 | Governor |
Time in seconds for throttle output (HeliRSC servo) to ramp from ground idle (RSC_IDLE) to flight idle throttle setting when motor interlock is enabled (throttle hold off).
Actual time in seconds for the main rotor to reach full speed after motor interlock is enabled (throttle hold off). Must be at least one second longer than the Throttle Ramp Time that is set with RSC_RAMP_TIME.
Percentage of normal rotor speed where flight is no longer possible. However currently the rotor runup/rundown is estimated using the RSC_RUNUP_TIME parameter. Estimated rotor speed increases/decreases between 0 (rotor stopped) to 1 (rotor at normal speed) in the RSC_RUNUP_TIME in seconds. This parameter should be set so that the estimated rotor speed goes below critical in approximately 3 seconds. So if you had a 10 second runup time then set RSC_CRITICAL to 70%.
Throttle output (HeliRSC Servo) in percent while armed but motor interlock is disabled (throttle hold on). FOR COMBUSTION ENGINES. Sets the engine ground idle throttle percentage with clutch disengaged. This must be set to zero for electric helicopters under most situations. If the ESC has an autorotation window this can be set to keep the autorotation window open in the ESC. Consult the operating manual for your ESC to set it properly for this purpose
This controls the maximum rate at which the throttle output (HeliRSC servo) can change, as a percentage per second. A value of 100 means the throttle can change over its full range in one second. A value of zero gives unlimited slew rate.
Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 0 percent collective is defined by H_COL_MIN. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to -2 degree of pitch.
Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 25% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 25% of 12 degrees is 3 degrees, so this setting would correspond to +1 degree of pitch.
Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 50% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 50% of 12 degrees is 6 degrees, so this setting would correspond to +4 degree of pitch.
Sets the throttle output (HeliRSC servo) in percent for the throttle curve at 75% of full collective travel where he 0 percent collective is defined by H_COL_MIN and 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, the total range is 12 degrees. 75% of 12 degrees is 9 degrees, so this setting would correspond to +7 degree of pitch.
Sets the throttle output (HeliRSC servo) in percent for the throttle curve at the minimum collective pitch position. The 100 percent collective is defined by H_COL_MAX. Example: if the setup has -2 degree to +10 degree collective pitch setup, this setting would correspond to +10 degree of pitch.
Main rotor rpm setting that governor maintains when engaged. Set to the rotor rpm your helicopter runs in flight. When a speed sensor is installed the rotor governor maintains this speed. For governor operation this should be set 10 rpm higher than the actual desired headspeed to allow for governor droop
Percentage of throttle where the governor will disengage to allow return to flight idle power. Typically should be set to the same value as flight idle throttle (the very lowest throttle setting on the throttle curve). The governor disengage can be disabled by setting this value to zero and using the pull-down from the governor TCGAIN to reduce power to flight idle with the collective at it's lowest throttle setting on the throttle curve.
Governor droop response under load, normal settings of 0-100%. Higher value is quicker response but may cause surging. Setting to zero disables the governor. Adjust this to be as aggressive as possible without getting surging or over-run on headspeed when the governor engages. Setting over 100% is allowable for some two-stage turbine engines to provide scheduling of the gas generator for proper torque response of the N2 spool
Percentage of throttle curve gain in governor output. This provides a type of feedforward response to sudden loading or unloading of the engine. If headspeed drops excessively during sudden heavy load, increase the throttle curve gain. If the governor runs with excessive droop more than 15 rpm lower than the speed setting, increase this setting until the governor runs at 8-10 rpm droop from the speed setting. The throttle curve must be properly tuned to fly the helicopter without the governor for this setting to work properly.
RPM range +/- governor rpm reference setting where governor is operational. If speed sensor fails or rpm falls outside of this range, the governor will disengage and return to throttle curve. Recommended range is 100
The throttle percentage sent to external governors, signaling to enable fast spool-up, when bailing out of an autorotation. Set 0 to disable. If also using a tail rotor of type DDVP with external governor then this value must lie within the autorotation window of both governors.
Used to soften collective pitch inputs near center point in Acro mode.
Value | Meaning |
---|---|
0 | Disabled |
0.1 | Very Low |
0.2 | Low |
0.3 | Medium |
0.4 | High |
0.5 | Very High |
Helicopter's minimum collective pitch setting at zero collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
Helicopter's collective pitch setting at mid-low (40%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
Helicopter's collective pitch setting at mid-high (60%) collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
Helicopter's maximum collective pitch setting at full collective stick input in Stabilize mode. Set this as a percent of collective range given by H_COL_MAX minus H_COL_MIN.
Gyro sensor offsets of X axis. This is setup on each boot during gyro calibrations
Gyro sensor offsets of Y axis. This is setup on each boot during gyro calibrations
Gyro sensor offsets of Z axis. This is setup on each boot during gyro calibrations
Gyro2 sensor offsets of X axis. This is setup on each boot during gyro calibrations
Gyro2 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
Gyro2 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
Gyro3 sensor offsets of X axis. This is setup on each boot during gyro calibrations
Gyro3 sensor offsets of Y axis. This is setup on each boot during gyro calibrations
Gyro3 sensor offsets of Z axis. This is setup on each boot during gyro calibrations
Accelerometer scaling of X axis. Calculated during acceleration calibration routine
Accelerometer scaling of Y axis Calculated during acceleration calibration routine
Accelerometer scaling of Z axis Calculated during acceleration calibration routine
Accelerometer offsets of X axis. This is setup using the acceleration calibration or level operations
Accelerometer offsets of Y axis. This is setup using the acceleration calibration or level operations
Accelerometer offsets of Z axis. This is setup using the acceleration calibration or level operations
Accelerometer2 scaling of X axis. Calculated during acceleration calibration routine
Accelerometer2 scaling of Y axis Calculated during acceleration calibration routine
Accelerometer2 scaling of Z axis Calculated during acceleration calibration routine
Accelerometer2 offsets of X axis. This is setup using the acceleration calibration or level operations
Accelerometer2 offsets of Y axis. This is setup using the acceleration calibration or level operations
Accelerometer2 offsets of Z axis. This is setup using the acceleration calibration or level operations
Accelerometer3 scaling of X axis. Calculated during acceleration calibration routine
Accelerometer3 scaling of Y axis Calculated during acceleration calibration routine
Accelerometer3 scaling of Z axis Calculated during acceleration calibration routine
Accelerometer3 offsets of X axis. This is setup using the acceleration calibration or level operations
Accelerometer3 offsets of Y axis. This is setup using the acceleration calibration or level operations
Accelerometer3 offsets of Z axis. This is setup using the acceleration calibration or level operations
Filter cutoff frequency for gyroscopes. This can be set to a lower value to try to cope with very high vibration levels in aircraft. A value of zero means no filtering (not recommended!)
Filter cutoff frequency for accelerometers. This can be set to a lower value to try to cope with very high vibration levels in aircraft. A value of zero means no filtering (not recommended!)
Use first IMU for attitude, velocity and position estimates
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Use second IMU for attitude, velocity and position estimates
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Use third IMU for attitude, velocity and position estimates
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Threshold to tolerate vibration to determine if vehicle is motionless. This depends on the frame type and if there is a constant vibration due to motors before launch or after landing. Total motionless is about 0.05. Suggested values: Planes/rover use 0.1, multirotors use 1, tradHeli uses 5
Conrols when automatic gyro calibration is performed
Value | Meaning |
---|---|
0 | Never |
1 | Start-up only |
Specifies how the accel cal routine determines the trims
Value | Meaning |
---|---|
0 | Don't adjust the trims |
1 | Assume first orientation was level |
2 | Assume ACC_BODYFIX is perfectly aligned to the vehicle |
The body-fixed accelerometer to be used for trim calculation
Value | Meaning |
---|---|
1 | IMU 1 |
2 | IMU 2 |
3 | IMU 3 |
X position of the first IMU Accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Y position of the first IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Z position of the first IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
X position of the second IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Y position of the second IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Z position of the second IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
X position of the third IMU accelerometer in body frame. Positive X is forward of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Y position of the third IMU accelerometer in body frame. Positive Y is to the right of the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Z position of the third IMU accelerometer in body frame. Positive Z is down from the origin. Attention: The IMU should be located as close to the vehicle c.g. as practical so that the value of this parameter is minimised. Failure to do so can result in noisy navigation velocity measurements due to vibration and IMU gyro noise. If the IMU cannot be moved and velocity noise is a problem, a location closer to the IMU can be used as the body frame origin.
Gyro sensor ID, taking into account its type, bus and instance
Gyro2 sensor ID, taking into account its type, bus and instance
Gyro3 sensor ID, taking into account its type, bus and instance
Accelerometer sensor ID, taking into account its type, bus and instance
Accelerometer2 sensor ID, taking into account its type, bus and instance
Accelerometer3 sensor ID, taking into account its type, bus and instance
Mask of IMUs to enable fast sampling on, if available
Value | Meaning |
---|---|
1 | FirstIMUOnly |
3 | FirstAndSecondIMU |
Bitmask of IMUs to enable. It can be used to prevent startup of specific detected IMUs
Value | Meaning |
---|---|
1 | FirstIMUOnly |
3 | FirstAndSecondIMU |
7 | FirstSecondAndThirdIMU |
127 | AllIMUs |
Gyro rate for IMUs with fast sampling enabled. The gyro rate is the sample rate at which the IMU filters operate and needs to be at least double the maximum filter frequency. If the sensor does not support the selected rate the next highest supported rate will be used. For IMUs which do not support fast sampling this setting is ignored and the default gyro rate of 1Khz is used.
Value | Meaning |
---|---|
0 | 1kHz |
1 | 2kHz |
2 | 4kHz |
3 | 8kHz |
Temperature that the 1st accelerometer was calibrated at
Temperature that the 1st gyroscope was calibrated at
Temperature that the 2nd accelerometer was calibrated at
Temperature that the 2nd gyroscope was calibrated at
Temperature that the 3rd accelerometer was calibrated at
Temperature that the 3rd gyroscope was calibrated at
This enables optional temperature calibration features. Setting PersistParams will save the accelerometer and temperature calibration parameters in the bootloader sector on the next update of the bootloader.
Harmonic Notch Filter enable
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Harmonic Notch Filter base center frequency in Hz. This should be set at most half the backend gyro rate (which is typically 1Khz). For helicopters using RPM sensor to dynamically set the notch frequency, use this parameter to provide a lower limit to the dynamic notch filter. Recommend setting it to half the operating rotor speed in Hz.
Harmonic Notch Filter bandwidth in Hz. This is typically set to half the base frequency. The ratio of base frequency to bandwidth determines the notch quality factor and is fixed across harmonics.
Harmonic Notch Filter attenuation in dB. Values greater than 40dB will typically produce a hard notch rather than a modest attenuation of motor noise.
Bitmask of harmonic frequencies to apply Harmonic Notch Filter to. This option takes effect on the next reboot. A maximum of 3 harmonics can be used at any one time.
A reference value of zero disables dynamic updates on the Harmonic Notch Filter and a positive value enables dynamic updates on the Harmonic Notch Filter. For throttle-based scaling, this parameter is the reference value associated with the specified frequency to facilitate frequency scaling of the Harmonic Notch Filter. For RPM and ESC telemetry based tracking, this parameter is set to 1 to enable the Harmonic Notch Filter using the RPM sensor or ESC telemetry set to measure rotor speed. The sensor data is converted to Hz automatically for use in the Harmonic Notch Filter. This reference value may also be used to scale the sensor data, if required. For example, rpm sensor data is required to measure heli motor RPM. Therefore the reference value can be used to scale the RPM sensor to the rotor RPM.
Harmonic Notch Filter dynamic frequency tracking mode. Dynamic updates can be throttle, RPM sensor, ESC telemetry or dynamic FFT based. Throttle-based updates should only be used with multicopters.
Value | Meaning |
---|---|
0 | Disabled |
1 | Throttle |
2 | RPM Sensor |
3 | ESC Telemetry |
4 | Dynamic FFT |
Harmonic Notch Filter options. Double-notches can provide deeper attenuation across a wider bandwidth than single notches and are suitable for larger aircraft. Dynamic harmonics attaches a harmonic notch to each detected noise frequency instead of simply being multiples of the base frequency, in the case of FFT it will attach notches to each of three detected noise peaks, in the case of ESC it will attach notches to each of four motor RPM values.
Number of samples to take when logging streams of IMU sensor readings. Will be rounded down to a multiple of 32. This option takes effect on the next reboot.
Bitmap of which IMUs to log batch data for. This option takes effect on the next reboot.
Value | Meaning |
---|---|
0 | None |
1 | First IMU |
255 | All |
Options for the BatchSampler. Post-filter and sensor-rate logging cannot be used at the same time.
Interval between pushing samples to the AP_Logger log
Number of samples to push to count every INS_LOG_BAT_LGIN
Enable notch filter
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Notch attenuation in dB
Notch center frequency in Hz
Notch bandwidth in Hz
Enable the use of temperature calibration parameters for this IMU. For automatic learning set to 2 and also set the INS_TCALn_TMAX to the target temperature, then reboot
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | LearnCalibration |
The minimum temperature that the calibration is valid for
The maximum temperature that the calibration is valid for. This must be at least 10 degrees above TMIN for calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
Enable the use of temperature calibration parameters for this IMU. For automatic learning set to 2 and also set the INS_TCALn_TMAX to the target temperature, then reboot
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | LearnCalibration |
The minimum temperature that the calibration is valid for
The maximum temperature that the calibration is valid for. This must be at least 10 degrees above TMIN for calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
Enable the use of temperature calibration parameters for this IMU. For automatic learning set to 2 and also set the INS_TCALn_TMAX to the target temperature, then reboot
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | LearnCalibration |
The minimum temperature that the calibration is valid for
The maximum temperature that the calibration is valid for. This must be at least 10 degrees above TMIN for calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 1st order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 2nd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
This is the 3rd order temperature coefficient from a temperature calibration
Landing Gear Startup behaviour control
Value | Meaning |
---|---|
0 | WaitForPilotInput |
1 | Retract |
2 | Deploy |
Pin number to use for detection of gear deployment. If set to -1 feedback is disabled.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUX1 |
51 | AUX2 |
52 | AUX3 |
53 | AUX4 |
54 | AUX5 |
55 | AUX6 |
Polarity for feedback pin. If this is 1 then the pin should be high when gear are deployed. If set to 0 then then deployed gear level is low.
Value | Meaning |
---|---|
0 | Low |
1 | High |
Pin number to use for feedback of weight on wheels condition. If set to -1 feedback is disabled.
Value | Meaning |
---|---|
-1 | Disabled |
50 | AUX1 |
51 | AUX2 |
52 | AUX3 |
53 | AUX4 |
54 | AUX5 |
55 | AUX6 |
Polarity for feedback pin. If this is 1 then the pin should be high when there is weight on wheels. If set to 0 then then weight on wheels level is low.
Value | Meaning |
---|---|
0 | Low |
1 | High |
Altitude where the landing gear will be deployed. This should be lower than the RETRACT_ALT. If zero then altitude is not used for deploying landing gear. Only applies when vehicle is armed.
Altitude where the landing gear will be retracted. This should be higher than the DEPLOY_ALT. If zero then altitude is not used for retracting landing gear. Only applies when vehicle is armed.
Options to retract or deploy landing gear in Auto or Guided mode
Value | Meaning |
---|---|
1 | Retract after Takeoff |
2 | Deploy during Land |
3 | Retract after Takeoff AND deploy during Land |
Bitmap of what Logger backend types to enable. Block-based logging is available on SITL and boards with dataflash chips. Multiple backends can be selected.
Value | Meaning |
---|---|
0 | None |
1 | File |
2 | MAVLink |
3 | File and MAVLink |
4 | Block |
6 | Block and MAVLink |
The File and Block backends use a buffer to store data before writing to the block device. Raising this value may reduce "gaps" in your SD card logging. This buffer size may be reduced depending on available memory. PixHawk requires at least 4 kilobytes. Maximum value available here is 64 kilobytes.
If LOG_DISARMED is set to 1 then logging will be enabled while disarmed. This can make for very large logfiles but can help a lot when tracking down startup issues
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
If LOG_REPLAY is set to 1 then the EKF2 state estimator will log detailed information needed for diagnosing problems with the Kalman filter. It is suggested that you also raise LOG_FILE_BUFSIZE to give more buffer space for logging and use a high quality microSD card to ensure no sensor data is lost
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
When set, the current log file is closed when the vehicle is disarmed. If LOG_DISARMED is set then a fresh log will be opened. Applies to the File and Block logging backends.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Maximum amount of memory to allocate to AP_Logger-over-mavlink
This controls the amount of time before failing writes to a log file cause the file to be closed and logging stopped.
Set this such that the free space is larger than your largest typical flight log
Loiter maximum lean angle. Set to zero for 2/3 of PSC_ANGLE_MAX or ANGLE_MAX
Defines the maximum speed in cm/s which the aircraft will travel horizontally while in loiter mode
Loiter maximum correction acceleration in cm/s/s. Higher values cause the copter to correct position errors more aggressively.
Loiter braking acceleration in cm/s/s. Higher values stop the copter more quickly when the stick is centered.
Loiter braking jerk in cm/s/s/s. Higher values will remove braking faster if the pilot moves the sticks during a braking maneuver.
Loiter brake start delay (in seconds)
The number of mission mission items that has been loaded by the ground station. Do not change this manually.
Controls mission starting point when entering Auto mode (either restart from beginning of mission or resume from last command run)
Value | Meaning |
---|---|
0 | Resume Mission |
1 | Restart Mission |
Bitmask of what options to use in missions.
Mount Type (None, Servo or MAVLink)
Value | Meaning |
---|---|
0 | None |
1 | Servo |
2 | 3DR Solo |
3 | Alexmos Serial |
4 | SToRM32 MAVLink |
5 | SToRM32 Serial |
Mount default operating mode on startup and after control is returned from autopilot
Value | Meaning |
---|---|
0 | Retracted |
1 | Neutral |
2 | MavLink Targeting |
3 | RC Targeting |
4 | GPS Point |
Mount roll angle when in retracted position
Mount tilt/pitch angle when in retracted position
Mount yaw/pan angle when in retracted position
Mount roll angle when in neutral position
Mount tilt/pitch angle when in neutral position
Mount pan/yaw angle when in neutral position
enable roll stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
enable tilt/pitch stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
enable pan/yaw stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
0 for none, any other for the RC channel to be used to control roll movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Minimum physical roll angular position of mount.
Maximum physical roll angular position of the mount
0 for none, any other for the RC channel to be used to control tilt (pitch) movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Minimum physical tilt (pitch) angular position of mount.
Maximum physical tilt (pitch) angular position of the mount
0 for none, any other for the RC channel to be used to control pan (yaw) movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Minimum physical pan (yaw) angular position of mount.
Maximum physical pan (yaw) angular position of the mount
0 for position control, small for low speeds, 100 for max speed. A good general value is 10 which gives a movement speed of 3 degrees per second.
Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
Mount default operating mode on startup and after control is returned from autopilot
Value | Meaning |
---|---|
0 | Retracted |
1 | Neutral |
2 | MavLink Targeting |
3 | RC Targeting |
4 | GPS Point |
Mount2 roll angle when in retracted position
Mount2 tilt/pitch angle when in retracted position
Mount2 yaw/pan angle when in retracted position
Mount2 roll angle when in neutral position
Mount2 tilt/pitch angle when in neutral position
Mount2 pan/yaw angle when in neutral position
enable roll stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
enable tilt/pitch stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
enable pan/yaw stabilisation relative to Earth
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
0 for none, any other for the RC channel to be used to control roll movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Mount2's minimum physical roll angular position
Mount2's maximum physical roll angular position
0 for none, any other for the RC channel to be used to control tilt (pitch) movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Mount2's minimum physical tilt (pitch) angular position
Mount2's maximum physical tilt (pitch) angular position
0 for none, any other for the RC channel to be used to control pan (yaw) movements
Value | Meaning |
---|---|
0 | Disabled |
5 | RC5 |
6 | RC6 |
7 | RC7 |
8 | RC8 |
9 | RC9 |
10 | RC10 |
11 | RC11 |
12 | RC12 |
Mount2's minimum physical pan (yaw) angular position
MOunt2's maximum physical pan (yaw) angular position
Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate, compensating for servo delay. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
Causes the servo angle output to lead the current angle of the vehicle by some amount of time based on current angular rate. Increase until the servo is responsive but doesn't overshoot. Does nothing with pan stabilization enabled.
Mount Type (None, Servo or MAVLink)
Value | Meaning |
---|---|
0 | None |
1 | Servo |
2 | 3DR Solo |
3 | Alexmos Serial |
4 | SToRM32 MAVLink |
5 | SToRM32 Serial |
Yaw control is given at least this pwm in microseconds range
Motor thrust curve exponent (from 0 for linear to 1.0 for second order curve)
Point at which the thrust saturates expressed as a number from 0 to 1 in the entire output range
Battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.4 * cell count, 0 = Disabled
Battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.5 * cell count, 0 = Disabled
Maximum current over which maximum throttle is limited (0 = Disabled)
This selects the output PWM type, allowing for normal PWM continuous output, OneShot, brushed or DShot motor output
Value | Meaning |
---|---|
0 | Normal |
1 | OneShot |
2 | OneShot125 |
3 | Brushed |
4 | DShot150 |
5 | DShot300 |
6 | DShot600 |
7 | DShot1200 |
This sets the min PWM output value in microseconds that will ever be output to the motors, 0 = use input RC3_MIN
This sets the max PWM value in microseconds that will ever be output to the motors, 0 = use input RC3_MAX
Point at which the thrust starts expressed as a number from 0 to 1 in the entire output range. Should be higher than MOT_SPIN_ARM.
Point at which the motors start to spin expressed as a number from 0 to 1 in the entire output range. Should be lower than MOT_SPIN_MIN.
Time constant used to limit the maximum current
Motor thrust needed to hover expressed as a number from 0 to 1
Enable/Disable automatic learning of hover throttle
Value | Meaning |
---|---|
0 | Disabled |
1 | Learn |
2 | Learn and Save |
Disables motor PWM output when disarmed
Value | Meaning |
---|---|
0 | PWM enabled while disarmed |
1 | PWM disabled while disarmed |
Yaw servo's maximum lean angle
Time in seconds to spool up the motors from zero to min throttle.
Booster motor output scaling factor vs main throttle. The output to the BoostThrottle servo will be the main throttle times this scaling factor. A higher scaling factor will put more of the load on the booster motor. A value of 1 will set the BoostThrottle equal to the main throttle.
Which battery monitor should be used for doing compensation
Value | Meaning |
---|---|
0 | First battery |
1 | Second battery |
Time in seconds to slew output from zero to full. This is used to limit the rate at which output can change. Range is constrained between 0 and 0.5.
Time in seconds to slew output from full to zero. This is used to limit the rate at which output can change. Range is constrained between 0 and 0.5.
Time taken to disable and enable the motor PWM output when disarmed and armed.
Used for average cell voltage calculation
Value | Meaning |
---|---|
0 | Auto |
1 | 1 |
2 | 2 |
3 | 3 |
4 | 4 |
5 | 5 |
6 | 6 |
7 | 7 |
8 | 8 |
9 | 9 |
10 | 10 |
11 | 11 |
12 | 12 |
13 | 13 |
14 | 14 |
A bitmask to set some MSP specific options
Select the RGB LED brightness level. When USB is connected brightness will never be higher than low regardless of the setting.
Value | Meaning |
---|---|
0 | Off |
1 | Low |
2 | Medium |
3 | High |
Controls what types of Buzzer will be enabled
Specifies the source for the colours and brightness for the LED. OutbackChallenge conforms to the MedicalExpress (https://uavchallenge.org/medical-express/) rules, essentially "Green" is disarmed (safe-to-approach), "Red" is armed (not safe-to-approach). Traffic light is a simplified color set, red when armed, yellow when the safety switch is not surpressing outputs (but disarmed), and green when outputs are surpressed and disarmed, the LED will blink faster if disarmed and failing arming checks.
Value | Meaning |
---|---|
0 | Standard |
1 | MAVLink/Scripting/AP_Periph |
2 | OutbackChallenge |
3 | TrafficLight |
This sets up the type of on-board I2C display. Disabled by default.
Value | Meaning |
---|---|
0 | Disable |
1 | ssd1306 |
2 | sh1106 |
10 | SITL |
Enable/Disable Solo Oreo LED driver, 0 to disable, 1 for Aircraft theme, 2 for Rover theme
Value | Meaning |
---|---|
0 | Disabled |
1 | Aircraft |
2 | Rover |
Enables to connect active buzzer to arbitrary pin. Requires 3-pin buzzer or additional MOSFET!
Value | Meaning |
---|---|
0 | Disabled |
Controls what types of LEDs will be enabled
Specifies pin level that indicates buzzer should play
Value | Meaning |
---|---|
0 | LowIsOn |
1 | HighIsOn |
Control the volume of the buzzer
The number of Serial LED's to use for notifications (NeoPixel's and ProfiLED)
Enabled/disable path planning around obstacles
Value | Meaning |
---|---|
0 | Disabled |
1 | BendyRuler |
2 | Dijkstra |
3 | Dijkstra with BendyRuler |
Object Avoidance will ignore objects more than this many meters from vehicle
Object Avoidance will look this many meters ahead of vehicle
BendyRuler will avoid changing bearing unless ratio of previous margin from obstacle (or fence) to present calculated margin is atleast this much.
BendyRuler will resist changing current bearing if the change in bearing is over this angle
BendyRuler will search for clear path along the direction defined by this parameter
Value | Meaning |
---|---|
1 | Horizontal search |
2 | Vertical search |
OADatabase maximum number of points. Set to 0 to disable the OA Database. Larger means more points but is more cpu intensive to process
OADatabase item timeout. The time an item will linger without any updates before it expires. Zero means never expires which is useful for a sent-once static environment but terrible for dynamic ones.
OADatabase queue maximum number of points. This in an input buffer size. Larger means it can handle larger bursts of incoming data points to filter into the database. No impact on cpu, only RAM. Recommend larger for faster datalinks or for sensors that generate a lot of data.
OADatabase output level to configure which database objects are sent to the ground station. All data is always available internally for avoidance algorithms.
Value | Meaning |
---|---|
0 | Disabled |
1 | Send only HIGH importance items |
2 | Send HIGH and NORMAL importance items |
3 | Send all items |
Beam width of incoming lidar data
Minimum radius of objects held in database
Maximum distance of objects held in database. Set to zero to disable the limits
OADatabase will reject obstacle's if vehicle's altitude above home is below this parameter, in a 3 meter radius around home. Set 0 to disable this feature.
OSD type. TXONLY makes the OSD parameter selection available to other modules even if there is no native OSD support on the board, for instance CRSF.
Value | Meaning |
---|---|
0 | None |
1 | MAX7456 |
2 | SITL |
3 | MSP |
4 | TXONLY |
This sets the channel used to switch different OSD screens.
Value | Meaning |
---|---|
0 | Disable |
5 | Chan5 |
6 | Chan6 |
7 | Chan7 |
8 | Chan8 |
9 | Chan9 |
10 | Chan10 |
11 | Chan11 |
12 | Chan12 |
13 | Chan13 |
14 | Chan14 |
15 | Chan15 |
16 | Chan16 |
This sets the method used to switch different OSD screens.
Value | Meaning |
---|---|
0 | switch to next screen if channel value was changed |
1 | select screen based on pwm ranges specified for each screen |
2 | switch to next screen after low to high transition and every 1s while channel value is high |
This sets options that change the display
This sets which OSD font to use. It is an integer from 0 to the number of fonts available
Sets vertical offset of the osd inside image
Sets horizontal offset of the osd inside image
Set level at which RSSI item will flash
Set level at which NSAT item will flash
Set level at which BAT_VOLT item will flash
Sets the units to use in displaying items
Value | Meaning |
---|---|
0 | Metric |
1 | Imperial |
2 | SI |
3 | Aviation |
Sets message duration seconds
Screen to be shown on Arm event. Zero to disable the feature.
Screen to be shown on disarm event. Zero to disable the feature.
Screen to be shown on failsafe event. Zero to disable the feature.
Debounce time in ms for stick commanded parameter navigation.
Set level below which TER_HGT item will flash. -1 disables.
Set level at which AVGCELLV item will flash
Used for average cell voltage display. -1 disables, 0 uses cell count autodetection for well charged LIPO/LIION batteries at connection, other values manually select cell count used.
Set level at which RESTVOLT item will flash
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Enables display of altitude AGL
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays RC signal strength
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays primary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays number of acquired sattelites
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Mavlink messages
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS ground speed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays distance and relative direction to HOME
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays heading
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays actual throttle percentage being sent to motor(s)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enables display of compass rose
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays wind speed and relative direction, on Rover this is the apparent wind speed and direction from the windvane, if fitted
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed value being used by TECS (fused value)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb rate
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's temp
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's rpm
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS latitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS longitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of roll from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of pitch from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Horizontal Dilution Of Position
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays bearing and distance to next waypoint
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays crosstrack error
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total distance flown
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight stats
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total flight time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb efficiency (climb rate/current)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight efficiency (mAh/km or /mi)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by secondary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery2 voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays secondary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from secondary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays a clock panel based on AP_RTC local time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon side bars (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays artificial horizon crosshair (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays distance from HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays relative direction to HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays power (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery usage bar (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays arming status (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays pluscode (OLC) element
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays callsign from callsign.txt on microSD card
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays 2nd battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays VTX Power
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Height above terrain
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery resting voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays indication of fence enable and breach
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Enables display of altitude AGL
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays RC signal strength
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays primary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays number of acquired sattelites
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Mavlink messages
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS ground speed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays distance and relative direction to HOME
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays heading
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays actual throttle percentage being sent to motor(s)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enables display of compass rose
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays wind speed and relative direction, on Rover this is the apparent wind speed and direction from the windvane, if fitted
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed value being used by TECS (fused value)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb rate
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's temp
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's rpm
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS latitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS longitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of roll from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of pitch from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Horizontal Dilution Of Position
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays bearing and distance to next waypoint
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays crosstrack error
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total distance flown
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight stats
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total flight time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb efficiency (climb rate/current)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight efficiency (mAh/km or /mi)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by secondary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery2 voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays secondary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from secondary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays a clock panel based on AP_RTC local time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon side bars (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays artificial horizon crosshair (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays distance from HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays relative direction to HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays power (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery usage bar (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays arming status (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays pluscode (OLC) element
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays callsign from callsign.txt on microSD card
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays 2nd battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays VTX Power
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Height above terrain
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery resting voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays indication of fence enable and breach
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Enables display of altitude AGL
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays RC signal strength
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays primary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays number of acquired sattelites
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Mavlink messages
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS ground speed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays distance and relative direction to HOME
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays heading
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays actual throttle percentage being sent to motor(s)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enables display of compass rose
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays wind speed and relative direction, on Rover this is the apparent wind speed and direction from the windvane, if fitted
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed value being used by TECS (fused value)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb rate
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's temp
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's rpm
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS latitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS longitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of roll from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of pitch from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Horizontal Dilution Of Position
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays bearing and distance to next waypoint
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays crosstrack error
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total distance flown
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight stats
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total flight time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb efficiency (climb rate/current)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight efficiency (mAh/km or /mi)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by secondary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery2 voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays secondary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from secondary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays a clock panel based on AP_RTC local time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon side bars (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays artificial horizon crosshair (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays distance from HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays relative direction to HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays power (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery usage bar (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays arming status (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays pluscode (OLC) element
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays callsign from callsign.txt on microSD card
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays 2nd battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays VTX Power
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Height above terrain
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery resting voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays indication of fence enable and breach
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Enables display of altitude AGL
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays RC signal strength
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays primary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays number of acquired sattelites
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight mode
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Mavlink messages
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS ground speed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays distance and relative direction to HOME
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays heading
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays actual throttle percentage being sent to motor(s)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enables display of compass rose
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays wind speed and relative direction, on Rover this is the apparent wind speed and direction from the windvane, if fitted
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed value being used by TECS (fused value)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb rate
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's temp
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's rpm
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays first esc's current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS latitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays GPS longitude
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of roll from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays degrees of pitch from level
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Horizontal Dilution Of Position
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays bearing and distance to next waypoint
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays crosstrack error
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total distance flown
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight stats
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays total flight time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays climb efficiency (climb rate/current)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays flight efficiency (mAh/km or /mi)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by secondary barometer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays temperature reported by primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery2 voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays secondary battery mAh consumed
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from secondary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays airspeed reported directly from primary airspeed sensor
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays a clock panel based on AP_RTC local time
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays artificial horizon side bars (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays artificial horizon crosshair (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays distance from HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen (MSP OSD only)
Vertical position on screen (MSP OSD only)
Displays relative direction to HOME (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays power (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays battery usage bar (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays arming status (MSP OSD only)
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays pluscode (OLC) element
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays callsign from callsign.txt on microSD card
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays 2nd battery current
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays VTX Power
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays Height above terrain
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays average cell voltage. WARNING: this can be inaccurate if the cell count is not detected or set properly. If the the battery is far from fully charged the detected cell count might not be accurate if auto cell count detection is used (OSD_CELL_COUNT=0).
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays main battery resting voltage
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Displays indication of fence enable and breach
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Horizontal position of Save button on screen
Vertical position of Save button on screen
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable this screen
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
This sets the PWM lower limit for this screen
This sets the PWM upper limit for this screen
Horizontal position of Save button on screen
Vertical position of Save button on screen
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Enable setting
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Horizontal position on screen
Vertical position on screen
Key of the parameter to be displayed and modified
Index of the parameter to be displayed and modified
Group of the parameter to be displayed and modified
Minimum value of the parameter to be displayed and modified
Maximum of the parameter to be displayed and modified
Increment of the parameter to be displayed and modified
Type of the parameter to be displayed and modified
Precision Land enabled/disabled
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Precision Land Type
Value | Meaning |
---|---|
0 | None |
1 | CompanionComputer |
2 | IRLock |
3 | SITL_Gazebo |
4 | SITL |
Yaw angle from body x-axis to sensor x-axis.
Desired landing position of the camera forward of the target in vehicle body frame
desired landing position of the camera right of the target in vehicle body frame
Specifies the estimation method to be used
Value | Meaning |
---|---|
0 | RawSensor |
1 | KalmanFilter |
Kalman Filter Accelerometer Noise, higher values weight the input from the camera more, accels less
X position of the camera in body frame. Positive X is forward of the origin.
Y position of the camera in body frame. Positive Y is to the right of the origin.
Z position of the camera in body frame. Positive Z is down from the origin.
Precland sensor bus for I2C sensors.
Value | Meaning |
---|---|
-1 | DefaultBus |
0 | InternalI2C |
1 | ExternalI2C |
Precision Landing sensor lag, to cope with variable landing_target latency
What type of proximity sensor is connected
Value | Meaning |
---|---|
0 | None |
7 | LightwareSF40c |
1 | LightWareSF40C-legacy |
2 | MAVLink |
3 | TeraRangerTower |
4 | RangeFinder |
5 | RPLidarA2 |
6 | TeraRangerTowerEvo |
8 | LightwareSF45B |
10 | SITL |
12 | AirSimSITL |
Proximity sensor orientation
Value | Meaning |
---|---|
0 | Default |
1 | Upside Down |
Proximity sensor yaw correction
Proximity sensor ignore angle 1
Proximity sensor ignore width 1
Proximity sensor ignore angle 2
Proximity sensor ignore width 2
Proximity sensor ignore angle 3
Proximity sensor ignore width 3
Proximity sensor ignore angle 4
Proximity sensor ignore width 4
Proximity sensor ignore angle 5
Proximity sensor ignore width 5
Proximity sensor ignore angle 6
Proximity sensor ignore width 6
Ignore proximity data that is within 1 meter of the ground below the vehicle. This requires a downward facing rangefinder
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Set this parameter to one if logging unfiltered(raw) distances from sensor should be enabled
Value | Meaning |
---|---|
0 | Off |
1 | On |
Cutoff frequency for low pass filter applied to each face in the proximity boundary
Lower values will slow the response of the navigation controller and reduce twitchiness
Position (vertical) controller P gain. Converts the difference between the desired altitude and actual altitude into a climb or descent rate which is passed to the throttle rate controller
Velocity (vertical) controller P gain. Converts the difference between desired vertical speed and actual speed into a desired acceleration that is passed to the throttle acceleration controller
Velocity (vertical) controller I gain. Corrects long-term difference in desired velocity to a target acceleration
Velocity (vertical) controller I gain maximum. Constrains the target acceleration that the I gain will output
Velocity (vertical) controller D gain. Corrects short-term changes in velocity
Velocity (vertical) controller Feed Forward gain. Produces an output that is proportional to the magnitude of the target
Velocity (vertical) error filter. This filter (in Hz) is applied to the input for P and I terms
Velocity (vertical) input filter for D term. This filter (in Hz) is applied to the input for D terms
Acceleration (vertical) controller P gain. Converts the difference between desired vertical acceleration and actual acceleration into a motor output
Acceleration (vertical) controller I gain. Corrects long-term difference in desired vertical acceleration and actual acceleration
Acceleration (vertical) controller I gain maximum. Constrains the maximum pwm that the I term will generate
Acceleration (vertical) controller D gain. Compensates for short-term change in desired vertical acceleration vs actual acceleration
Acceleration (vertical) controller feed forward
Acceleration (vertical) controller target frequency in Hz
Acceleration (vertical) controller error frequency in Hz
Acceleration (vertical) controller derivative frequency in Hz
Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.
Position controller P gain. Converts the distance (in the latitude direction) to the target location into a desired speed which is then passed to the loiter latitude rate controller
Velocity (horizontal) P gain. Converts the difference between desired and actual velocity to a target acceleration
Velocity (horizontal) I gain. Corrects long-term difference between desired and actual velocity to a target acceleration
Velocity (horizontal) D gain. Corrects short-term changes in velocity
Velocity (horizontal) integrator maximum. Constrains the target acceleration that the I gain will output
Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for P and I terms
Velocity (horizontal) input filter. This filter (in Hz) is applied to the input for D term
Velocity (horizontal) feed forward gain. Converts the difference between desired velocity to a target acceleration
Maximum lean angle autopilot can request. Set to zero to use ANGLE_MAX parameter value
Number of rally points currently loaded
Maximum distance to rally point. If the closest rally point is more than this number of kilometers from the current position and the home location is closer than any of the rally points from the current position then do RTL to home rather than to the closest rally point. This prevents a leftover rally point from a different airfield being used accidentally. If this is set to 0 then the closest rally point is always used.
Controls if Home is included as a Rally point (i.e. as a safe landing place) for RTL
Value | Meaning |
---|---|
0 | DoNotIncludeHome |
1 | IncludeHome |
Timeout after which RC overrides will no longer be used, and RC input will resume, 0 will disable RC overrides, -1 will never timeout, and continue using overrides until they are disabled
RC input options
Bitmask of enabled RC protocols. Allows narrowing the protocol detection to only specific types of RC receivers which can avoid issues with incorrect detection. Set to 1 to enable all protocols.
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
RC minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC trim (neutral) PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
RC maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse channel input. Set to 0 for normal operation. Set to 1 to reverse this input channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
PWM dead zone in microseconds around trim or bottom
Function assigned to this RC channel
Value | Meaning |
---|---|
0 | Do Nothing |
2 | Flip |
3 | Simple Mode |
4 | RTL |
5 | Save Trim |
7 | Save WP |
9 | Camera Trigger |
10 | RangeFinder |
11 | Fence |
13 | Super Simple Mode |
14 | Acro Trainer |
15 | Sprayer |
16 | Auto |
17 | AutoTune |
18 | Land |
19 | Gripper |
21 | Parachute Enable |
22 | Parachute Release |
23 | Parachute 3pos |
24 | Auto Mission Reset |
25 | AttCon Feed Forward |
26 | AttCon Accel Limits |
27 | Retract Mount |
28 | Relay On/Off |
29 | Landing Gear |
30 | Lost Copter Sound |
31 | Motor Emergency Stop |
32 | Motor Interlock |
33 | Brake |
34 | Relay2 On/Off |
35 | Relay3 On/Off |
36 | Relay4 On/Off |
37 | Throw |
38 | ADSB Avoidance En |
39 | PrecLoiter |
40 | Proximity Avoidance |
41 | ArmDisarm |
42 | SmartRTL |
43 | InvertedFlight |
46 | RC Override Enable |
47 | User Function 1 |
48 | User Function 2 |
49 | User Function 3 |
52 | Acro |
55 | Guided |
56 | Loiter |
57 | Follow |
58 | Clear Waypoints |
60 | ZigZag |
61 | ZigZag SaveWP |
62 | Compass Learn |
65 | GPS Disable |
66 | Relay5 On/Off |
67 | Relay6 On/Off |
68 | Stabilize |
69 | PosHold |
70 | AltHold |
71 | FlowHold |
72 | Circle |
73 | Drift |
75 | SurfaceTrackingUpDown |
76 | Standby Mode |
78 | RunCam Control |
79 | RunCam OSD Control |
80 | Viso Align |
81 | Disarm |
83 | ZigZag Auto |
84 | Air Mode |
85 | Generator |
90 | EKF Pos Source |
94 | VTX Power |
100 | KillIMU1 |
101 | KillIMU2 |
102 | Camera Mode Toggle |
105 | GPS Disable Yaw |
300 | Scripting1 |
301 | Scripting2 |
302 | Scripting3 |
303 | Scripting4 |
304 | Scripting5 |
305 | Scripting6 |
306 | Scripting7 |
307 | Scripting8 |
Roll channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Roll is normally on channel 1, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
Pitch channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Pitch is normally on channel 2, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
Throttle channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Throttle is normally on channel 3, but you can move it to any channel with this parameter. Warning APM 2.X: Changing the throttle channel could produce unexpected fail-safe results if connection between receiver and on-board PPM Encoder is lost. Disabling on-board PPM Encoder is recommended. Reboot is required for changes to take effect.
Yaw channel number. This is useful when you have a RC transmitter that can't change the channel order easily. Yaw (also known as rudder) is normally on channel 4, but you can move it to any channel with this parameter. Reboot is required for changes to take effect.
Digital pin number for first relay control. This is the pin used for camera control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
27 | BBBMini Pin P8.17 |
Digital pin number for 2nd relay control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
65 | BBBMini Pin P8.18 |
Digital pin number for 3rd relay control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
22 | BBBMini Pin P8.19 |
Digital pin number for 4th relay control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
63 | BBBMini Pin P8.34 |
The state of the relay on boot.
Value | Meaning |
---|---|
0 | Off |
1 | On |
2 | NoChange |
Digital pin number for 5th relay control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
62 | BBBMini Pin P8.13 |
Digital pin number for 6th relay control.
Value | Meaning |
---|---|
-1 | Disabled |
49 | BB Blue GP0 pin 4 |
50 | AUXOUT1 |
51 | AUXOUT2 |
52 | AUXOUT3 |
53 | AUXOUT4 |
54 | AUXOUT5 |
55 | AUXOUT6 |
57 | BB Blue GP0 pin 3 |
113 | BB Blue GP0 pin 6 |
116 | BB Blue GP0 pin 5 |
37 | BBBMini Pin P8.14 |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of rangefinder device that is connected
Value | Meaning |
---|---|
0 | None |
1 | Analog |
2 | MaxbotixI2C |
3 | LidarLite-I2C |
5 | PWM |
6 | BBB-PRU |
7 | LightWareI2C |
8 | LightWareSerial |
9 | Bebop |
10 | MAVLink |
11 | uLanding |
12 | LeddarOne |
13 | MaxbotixSerial |
14 | TeraRangerI2C |
15 | LidarLiteV3-I2C |
16 | VL53L0X or VL53L1X |
17 | NMEA |
18 | WASP-LRF |
19 | BenewakeTF02 |
20 | Benewake-Serial |
21 | LidarLightV3HP |
22 | PWM |
23 | BlueRoboticsPing |
24 | UAVCAN |
25 | BenewakeTFminiPlus-I2C |
26 | LanbaoPSK-CM8JL65-CC5 |
27 | BenewakeTF03 |
28 | VL53L1X-ShortRange |
29 | LeddarVu8-Serial |
30 | HC-SR04 |
31 | GYUS42v2 |
32 | MSP |
33 | USD1_CAN |
100 | SITL |
Analog or PWM input pin that rangefinder is connected to. Airspeed ports can be used for Analog input, AUXOUT can be used for PWM input
Value | Meaning |
---|---|
-1 | Not Used |
11 | PX4-airspeed port |
15 | Pixhawk-airspeed port |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
Scaling factor between rangefinder reading and distance. For the linear and inverted functions this is in meters per volt. For the hyperbolic function the units are meterVolts.
Offset in volts for zero distance for analog rangefinders. Offset added to distance in centimeters for PWM lidars
Control over what function is used to calculate distance. For a linear function, the distance is (voltage-offset)*scaling. For a inverted function the distance is (offset-voltage)*scaling. For a hyperbolic function the distance is scaling/(voltage-offset). The functions return the distance in meters.
Value | Meaning |
---|---|
0 | Linear |
1 | Inverted |
2 | Hyperbolic |
Minimum distance in centimeters that rangefinder can reliably read
Maximum distance in centimeters that rangefinder can reliably read
Digital pin that enables/disables rangefinder measurement for the pwm rangefinder. A value of -1 means no pin. If this is set, then the pin is set to 1 to enable the rangefinder and set to 0 to disable it. This is used to enable powersaving when out of range.
Value | Meaning |
---|---|
-1 | Not Used |
50 | Pixhawk AUXOUT1 |
51 | Pixhawk AUXOUT2 |
52 | Pixhawk AUXOUT3 |
53 | Pixhawk AUXOUT4 |
54 | Pixhawk AUXOUT5 |
55 | Pixhawk AUXOUT6 |
111 | PX4 FMU Relay1 |
112 | PX4 FMU Relay2 |
113 | PX4IO Relay1 |
114 | PX4IO Relay2 |
115 | PX4IO ACC1 |
116 | PX4IO ACC2 |
This parameter sets whether an analog rangefinder is ratiometric. Most analog rangefinders are ratiometric, meaning that their output voltage is influenced by the supply voltage. Some analog rangefinders (such as the SF/02) have their own internal voltage regulators so they are not ratiometric.
Value | Meaning |
---|---|
0 | No |
1 | Yes |
This parameter sets the estimated terrain distance in meters above which the sensor will be put into a power saving mode (if available). A value of zero means power saving is not enabled
This parameter sets the expected range measurement(in cm) that the range finder should return when the vehicle is on the ground.
This sets the bus address of the sensor, where applicable. Used for the I2C and UAVCAN sensors to allow for multiple sensors on different addresses.
X position of the rangefinder in body frame. Positive X is forward of the origin. Use the zero range datum point if supplied.
Y position of the rangefinder in body frame. Positive Y is to the right of the origin. Use the zero range datum point if supplied.
Z position of the rangefinder in body frame. Positive Z is down from the origin. Use the zero range datum point if supplied.
Orientation of rangefinder
Value | Meaning |
---|---|
0 | Forward |
1 | Forward-Right |
2 | Right |
3 | Back-Right |
4 | Back |
5 | Back-Left |
6 | Left |
7 | Forward-Left |
24 | Up |
25 | Down |
Sets the number of historic range results to use for calculating the current range result. When MAVG is greater than 1, the current range result will be the current measured value averaged with the N-1 previous results
Sets the window size for the real-time median filter. When MEDF is greater than 0 the median filter is active
Sets the repetition frequency of the ranging operation in Hertz. Upon entering the desired frequency the system will calculate the nearest frequency that it can handle according to the resolution of internal timers.
Sets the number of pulses to be used in multi-pulse averaging mode. In this mode, a sequence of rapid fire ranges are taken and then averaged to improve the accuracy of the measurement
Sets the system sensitivity. Larger values of THR represent higher sensitivity. The system may limit the maximum value of THR to prevent excessive false alarm rates based on settings made at the factory. Set to -1 for automatic threshold adjustments
Desired baud rate
Value | Meaning |
---|---|
0 | Low Speed |
1 | High Speed |
What type of RPM sensor is connected
Value | Meaning |
---|---|
0 | None |
1 | PWM |
2 | AUXPIN |
3 | EFI |
4 | Harmonic Notch |
Scaling factor between sensor reading and RPM.
Maximum RPM to report
Minimum RPM to report
Minimum data quality to be used
Which pin to use
Value | Meaning |
---|---|
-1 | Disabled |
50 | PixhawkAUX1 |
51 | PixhawkAUX2 |
52 | PixhawkAUX3 |
53 | PixhawkAUX4 |
54 | PixhawkAUX5 |
55 | PixhawkAUX6 |
What type of RPM sensor is connected
Value | Meaning |
---|---|
0 | None |
1 | PWM |
2 | AUXPIN |
3 | EFI |
4 | Harmonic Notch |
Scaling factor between sensor reading and RPM.
Which pin to use
Value | Meaning |
---|---|
-1 | Disabled |
50 | PixhawkAUX1 |
51 | PixhawkAUX2 |
52 | PixhawkAUX3 |
53 | PixhawkAUX4 |
54 | PixhawkAUX5 |
55 | PixhawkAUX6 |
Radio Receiver RSSI type. If your radio receiver supports RSSI of some kind, set it here, then set its associated RSSI_XXXXX parameters, if any.
Value | Meaning |
---|---|
0 | Disabled |
1 | AnalogPin |
2 | RCChannelPwmValue |
3 | ReceiverProtocol |
4 | PWMInputPin |
5 | TelemetryRadioRSSI |
Pin used to read the RSSI voltage or PWM value
Value | Meaning |
---|---|
8 | V5 Nano |
11 | Pixracer |
13 | Pixhawk ADC4 |
14 | Pixhawk ADC3 |
15 | Pixhawk ADC6/Pixhawk2 ADC |
50 | PixhawkAUX1 |
51 | PixhawkAUX2 |
52 | PixhawkAUX3 |
53 | PixhawkAUX4 |
54 | PixhawkAUX5 |
55 | PixhawkAUX6 |
103 | Pixhawk SBUS |
RSSI pin's voltage received on the RSSI_ANA_PIN when the signal strength is the weakest. Some radio receivers put out inverted values so this value may be higher than RSSI_PIN_HIGH
RSSI pin's voltage received on the RSSI_ANA_PIN when the signal strength is the strongest. Some radio receivers put out inverted values so this value may be lower than RSSI_PIN_LOW
The channel number where RSSI will be output by the radio receiver (5 and above).
PWM value that the radio receiver will put on the RSSI_CHANNEL or RSSI_ANA_PIN when the signal strength is the weakest. Some radio receivers output inverted values so this value may be lower than RSSI_CHAN_HIGH
PWM value that the radio receiver will put on the RSSI_CHANNEL or RSSI_ANA_PIN when the signal strength is the strongest. Some radio receivers output inverted values so this value may be higher than RSSI_CHAN_LOW
Set to non-zero to enable scheduler debug messages. When set to show "Slips" the scheduler will display a message whenever a scheduled task is delayed due to too much CPU load. When set to ShowOverruns the scheduled will display a message whenever a task takes longer than the limit promised in the task table.
Value | Meaning |
---|---|
0 | Disabled |
2 | ShowSlips |
3 | ShowOverruns |
This controls the rate of the main control loop in Hz. This should only be changed by developers. This only takes effect on restart. Values over 400 are considered highly experimental.
Value | Meaning |
---|---|
50 | 50Hz |
100 | 100Hz |
200 | 200Hz |
250 | 250Hz |
300 | 300Hz |
400 | 400Hz |
This controls optional aspects of the scheduler.
Controls if scripting is enabled
Value | Meaning |
---|---|
0 | None |
1 | Lua Scripts |
The number virtual machine instructions that can be run before considering a script to have taken an excessive amount of time
Amount of memory available for scripting
The higher the number the more verbose builtin scripting debug will be.
General purpose user variable input for scripts
General purpose user variable input for scripts
General purpose user variable input for scripts
General purpose user variable input for scripts
This will stop scripts being loaded from the given locations
The baud rate used on the USB console. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol to use on the console.
Value | Meaning |
---|---|
1 | MAVlink1 |
2 | MAVLink2 |
Control what protocol to use on the Telem1 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate used on the Telem1 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol to use on the Telem2 port. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate of the Telem2 port. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol Serial 3 (GPS) should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate used for the Serial 3 (GPS). Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol Serial4 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate used for Serial4. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol Serial5 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate used for Serial5. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control what protocol Serial6 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
37 | SmartAudio |
The baud rate used for Serial6. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire. The Swap option allows the RX and TX pins to be swapped on STM32F7 based boards.
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
Value | Meaning |
---|---|
-1 | Disabled |
0 | Serial0 |
1 | Serial1 |
2 | Serial2 |
3 | Serial3 |
4 | Serial4 |
5 | Serial5 |
6 | Serial6 |
This sets one side of pass-through between two serial ports. Once both sides are set then all data received on either port will be passed to the other port
Value | Meaning |
---|---|
-1 | Disabled |
0 | Serial0 |
1 | Serial1 |
2 | Serial2 |
3 | Serial3 |
4 | Serial4 |
5 | Serial5 |
6 | Serial6 |
This sets a timeout for serial pass-through in seconds. When the pass-through is enabled by setting the SERIAL_PASS1 and SERIAL_PASS2 parameters then it remains in effect until no data comes from the first port for SERIAL_PASSTIMO seconds. This allows the port to revent to its normal usage (such as MAVLink connection to a GCS) when it is no longer needed. A value of 0 means no timeout.
Control what protocol Serial7 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
The baud rate used for Serial7. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
Control what protocol Serial8 port should be used for. Note that the Frsky options require external converter hardware. See the wiki for details.
Value | Meaning |
---|---|
-1 | None |
1 | MAVLink1 |
2 | MAVLink2 |
3 | Frsky D |
4 | Frsky SPort |
5 | GPS |
7 | Alexmos Gimbal Serial |
8 | SToRM32 Gimbal Serial |
9 | Rangefinder |
10 | FrSky SPort Passthrough (OpenTX) |
11 | Lidar360 |
13 | Beacon |
14 | Volz servo out |
15 | SBus servo out |
16 | ESC Telemetry |
17 | Devo Telemetry |
18 | OpticalFlow |
19 | RobotisServo |
20 | NMEA Output |
21 | WindVane |
22 | SLCAN |
23 | RCIN |
24 | MegaSquirt EFI |
25 | LTM |
26 | RunCam |
27 | HottTelem |
28 | Scripting |
29 | Crossfire |
30 | Generator |
31 | Winch |
32 | MSP |
33 | DJI FPV |
34 | AirSpeed |
35 | ADSB |
36 | AHRS |
The baud rate used for Serial7. Most stm32-based boards can support rates of up to 1500. If you setup a rate you cannot support and then can't connect to your board you should load a firmware from a different vehicle type. That will reset all your parameters to defaults.
Value | Meaning |
---|---|
1 | 1200 |
2 | 2400 |
4 | 4800 |
9 | 9600 |
19 | 19200 |
38 | 38400 |
57 | 57600 |
111 | 111100 |
115 | 115200 |
230 | 230400 |
256 | 256000 |
460 | 460800 |
500 | 500000 |
921 | 921600 |
1500 | 1500000 |
Control over UART options. The InvertRX option controls invert of the receive pin. The InvertTX option controls invert of the transmit pin. The HalfDuplex option controls half-duplex (onewire) mode, where both transmit and receive is done on the transmit wire.
This sets the default output rate in Hz for all outputs.
This sets the DShot output rate for all outputs as a multiple of the loop rate. 0 sets the output rate to be fixed at 1Khz for low loop rates. This value should never be set below 500Hz.
Value | Meaning |
---|---|
0 | 1Khz |
1 | loop-rate |
2 | double loop-rate |
3 | triple loop-rate |
4 | quadruple loop rate |
This sets the DShot ESC type for all outputs. The ESC type affects the range of DShot commands available. None means that no dshot commands will be executed.
Value | Meaning |
---|---|
0 | None |
1 | BLHeli32/BLHeli_S/Kiss |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
minimum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
maximum PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Trim PWM pulse width in microseconds. Typically 1000 is lower limit, 1500 is neutral and 2000 is upper limit.
Reverse servo operation. Set to 0 for normal operation. Set to 1 to reverse this output channel.
Value | Meaning |
---|---|
0 | Normal |
1 | Reversed |
Function assigned to this servo. Setting this to Disabled(0) will setup this output for control by auto missions or MAVLink servo set commands. any other value will enable the corresponding function
Value | Meaning |
---|---|
0 | Disabled |
1 | RCPassThru |
2 | Flap |
3 | Flap_auto |
4 | Aileron |
6 | mount_pan |
7 | mount_tilt |
8 | mount_roll |
9 | mount_open |
10 | camera_trigger |
12 | mount2_pan |
13 | mount2_tilt |
14 | mount2_roll |
15 | mount2_open |
16 | DifferentialSpoilerLeft1 |
17 | DifferentialSpoilerRight1 |
19 | Elevator |
21 | Rudder |
22 | SprayerPump |
23 | SprayerSpinner |
24 | FlaperonLeft |
25 | FlaperonRight |
26 | GroundSteering |
27 | Parachute |
28 | Gripper |
29 | LandingGear |
30 | EngineRunEnable |
31 | HeliRSC |
32 | HeliTailRSC |
33 | Motor1 |
34 | Motor2 |
35 | Motor3 |
36 | Motor4 |
37 | Motor5 |
38 | Motor6 |
39 | Motor7 |
40 | Motor8 |
41 | TiltMotorsFront |
45 | TiltMotorsRear |
46 | TiltMotorRearLeft |
47 | TiltMotorRearRight |
51 | RCIN1 |
52 | RCIN2 |
53 | RCIN3 |
54 | RCIN4 |
55 | RCIN5 |
56 | RCIN6 |
57 | RCIN7 |
58 | RCIN8 |
59 | RCIN9 |
60 | RCIN10 |
61 | RCIN11 |
62 | RCIN12 |
63 | RCIN13 |
64 | RCIN14 |
65 | RCIN15 |
66 | RCIN16 |
67 | Ignition |
69 | Starter |
70 | Throttle |
71 | TrackerYaw |
72 | TrackerPitch |
73 | ThrottleLeft |
74 | ThrottleRight |
75 | TiltMotorFrontLeft |
76 | TiltMotorFrontRight |
77 | ElevonLeft |
78 | ElevonRight |
79 | VTailLeft |
80 | VTailRight |
81 | BoostThrottle |
82 | Motor9 |
83 | Motor10 |
84 | Motor11 |
85 | Motor12 |
86 | DifferentialSpoilerLeft2 |
87 | DifferentialSpoilerRight2 |
88 | Winch |
89 | Main Sail |
90 | CameraISO |
91 | CameraAperture |
92 | CameraFocus |
93 | CameraShutterSpeed |
94 | Script 1 |
95 | Script 2 |
96 | Script 3 |
97 | Script 4 |
98 | Script 5 |
99 | Script 6 |
100 | Script 7 |
101 | Script 8 |
102 | Script 9 |
103 | Script 10 |
104 | Script 11 |
105 | Script 12 |
106 | Script 13 |
107 | Script 14 |
108 | Script 15 |
109 | Script 16 |
120 | NeoPixel1 |
121 | NeoPixel2 |
122 | NeoPixel3 |
123 | NeoPixel4 |
124 | RateRoll |
125 | RatePitch |
126 | RateThrust |
127 | RateYaw |
128 | Wing Sail Elevator |
129 | ProfiLED 1 |
130 | ProfiLED 2 |
131 | ProfiLED 3 |
132 | ProfiLED Clock |
133 | Winch Clutch |
134 | SERVOn_MIN |
135 | SERVOn_TRIM |
136 | SERVOn_MAX |
137 | Sail Mast Rotation |
Enable of BLHeli pass-thru servo protocol support to specific channels. This mask is in addition to motors enabled using SERVO_BLH_AUTO (if any)
If set to 1 this auto-enables BLHeli pass-thru support for all multicopter motors
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Setting SERVO_BLH_TEST to a motor number enables an internal test of the BLHeli ESC protocol to the corresponding ESC. The debug output is displayed on the USB console.
Value | Meaning |
---|---|
0 | Disabled |
1 | TestMotor1 |
2 | TestMotor2 |
3 | TestMotor3 |
4 | TestMotor4 |
5 | TestMotor5 |
6 | TestMotor6 |
7 | TestMotor7 |
8 | TestMotor8 |
This sets the inactivity timeout for the BLHeli protocol in seconds. If no packets are received in this time normal MAVLink operations are resumed. A value of 0 means no timeout
This sets the rate in Hz for requesting telemetry from ESCs. It is the rate per ESC. Setting to zero disables telemetry requests
When set to 1 this enabled verbose debugging output over MAVLink when the blheli protocol is active. This can be used to diagnose failures.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
When set to a non-zero value this overrides the output type for the output channels given by SERVO_BLH_MASK. This can be used to enable DShot on outputs that are not part of the multicopter motors group.
Value | Meaning |
---|---|
0 | None |
1 | OneShot |
2 | OneShot125 |
3 | Brushed |
4 | DShot150 |
5 | DShot300 |
6 | DShot600 |
7 | DShot1200 |
This sets the serial port to use for blheli pass-thru
Value | Meaning |
---|---|
0 | Console |
1 | Serial1 |
2 | Serial2 |
3 | Serial3 |
4 | Serial4 |
5 | Serial5 |
This allows calculation of true RPM from ESC's eRPM. The default is 14.
Mask of channels which are dynamically reversible. This is used to configure ESCs in '3D' mode, allowing for the motor to spin in either direction
Mask of channels which support bi-directional dshot. This is used for ESCs which have firmware that supports bi-directional dshot allowing fast rpm telemetry values to be returned for the harmonic notch.
Mask of channels which are reversed. This is used to configure ESCs in reversed mode
Position minimum at servo min value. This should be within the position control range of the servos, normally 0 to 4095
Position maximum at servo max value. This should be within the position control range of the servos, normally 0 to 4095
This sets the SBUS output frame rate in Hz.
Enable of volz servo protocol to specific channels
Controls which axis are being excited. Set to non-zero to see more parameters
Value | Meaning |
---|---|
0 | None |
1 | Input Roll Angle |
2 | Input Pitch Angle |
3 | Input Yaw Angle |
4 | Recovery Roll Angle |
5 | Recovery Pitch Angle |
6 | Recovery Yaw Angle |
7 | Rate Roll |
8 | Rate Pitch |
9 | Rate Yaw |
10 | Mixer Roll |
11 | Mixer Pitch |
12 | Mixer Yaw |
13 | Mixer Thrust |
Magnitude of sweep in deg, deg/s and 0-1 for mixer outputs.
Frequency at the start of the sweep
Frequency at the end of the sweep
Time to reach maximum amplitude of sweep
Time taken to complete the sweep
Time to reach zero amplitude at the end of the sweep
Allows you to enable (1) or disable (0) the sprayer
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Desired pump speed when traveling 1m/s expressed as a percentage
Spinner's rotation speed in PWM (a higher rate will disperse the spray over a wider area horizontally)
Speed minimum at which we will begin spraying
Minimum pump speed expressed as a percentage
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
Stream rate of RAW_IMU, SCALED_IMU2, SCALED_IMU3, SCALED_PRESSURE, SCALED_PRESSURE2, SCALED_PRESSURE3 and SENSOR_OFFSETS to ground station
Stream rate of SYS_STATUS, POWER_STATUS, MEMINFO, CURRENT_WAYPOINT, GPS_RAW_INT, GPS_RTK (if available), GPS2_RAW (if available), GPS2_RTK (if available), NAV_CONTROLLER_OUTPUT, and FENCE_STATUS to ground station
Stream rate of SERVO_OUTPUT_RAW and RC_CHANNELS to ground station
Stream rate of RC_CHANNELS_SCALED (HIL only) to ground station
Stream rate of GLOBAL_POSITION_INT and LOCAL_POSITION_NED to ground station
Stream rate of ATTITUDE, SIMSTATE (SITL only), AHRS2 and PID_TUNING to ground station
Stream rate of VFR_HUD to ground station
Stream rate of AHRS, HWSTATUS, SYSTEM_TIME, RANGEFINDER, DISTANCE_SENSOR, TERRAIN_REQUEST, BATTERY2, MOUNT_STATUS, OPTICAL_FLOW, GIMBAL_REPORT, MAG_CAL_REPORT, MAG_CAL_PROGRESS, EKF_STATUS_REPORT, VIBRATION and RPM to ground station
Stream rate of PARAM_VALUE to ground station
ADSB stream rate to ground station
SmartRTL accuracy. The minimum distance between points.
SmartRTL maximum number of points on path. Set to 0 to disable SmartRTL. 100 points consumes about 3k of memory.
Bitmask of SmartRTL options.
Number of times board has been booted
Total FlightTime (seconds)
Total time autopilot has run
Seconds since January 1st 2016 (Unix epoch+1451606400) since statistics reset (set to 0 to reset statistics)
Enable temperature calibration. Set to 0 to disable. Set to 1 to use learned values. Set to 2 to learn new values and use the values
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
2 | EnableAndLearn |
Minimum learned temperature. This is automatically set by the learning process
Maximum learned temperature. This is automatically set by the learning process
Learned exponent for barometer temperature correction
enable terrain data. This enables the vehicle storing a database of terrain data on the SD card. The terrain data is requested from the ground station as needed, and stored for later use on the SD card. To be useful the ground station must support TERRAIN_REQUEST messages and have access to a terrain database, such as the SRTM database.
Value | Meaning |
---|---|
0 | Disable |
1 | Enable |
Distance between terrain grid points in meters. This controls the horizontal resolution of the terrain data that is stored on te SD card and requested from the ground station. If your GCS is using the ArduPilot SRTM database like Mission Planner or MAVProxy, then a resolution of 100 meters is appropriate. Grid spacings lower than 100 meters waste SD card space if the GCS cannot provide that resolution. The grid spacing also controls how much data is kept in memory during flight. A larger grid spacing will allow for a larger amount of data in memory. A grid spacing of 100 meters results in the vehicle keeping 12 grid squares in memory with each grid square having a size of 2.7 kilometers by 3.2 kilometers. Any additional grid squares are stored on the SD once they are fetched from the GCS and will be loaded as needed.
Options to change behaviour of terrain system
tmode (or "toy" mode) gives a simplified user interface designed for mass market drones. Version1 is for the SkyViper V2450GPS. Version2 is for the F412 based boards
Value | Meaning |
---|---|
0 | Disabled |
1 | EnableVersion1 |
2 | EnableVersion2 |
This is the initial mode when the vehicle is first turned on. This mode is assumed to not require GPS
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | FlowHold |
This is the secondary mode. This mode is assumed to require GPS
Value | Meaning |
---|---|
0 | Stabilize |
1 | Acro |
2 | AltHold |
3 | Auto |
4 | Guided |
5 | Loiter |
6 | RTL |
7 | Circle |
9 | Land |
11 | Drift |
13 | Sport |
14 | Flip |
15 | AutoTune |
16 | PosHold |
17 | Brake |
18 | Throw |
19 | Avoid_ADSB |
20 | Guided_NoGPS |
21 | FlowHold |
This is the action taken when the left action button is pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the right action button is pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the power button is pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the left action button is pressed while the left (Mode) button is held down
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the right action is pressed while the left (Mode) button is held down
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the power button is pressed while the left (Mode) button is held down
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the left (Mode) button is pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the action taken when the left (Mode) button is long-pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
24 | ModeFlowHold |
This is the amount of automatic stick trim that can be applied when disarmed with sticks not moving. It is a PWM limit value away from 1500
This is the action taken when the right (Return) button is pressed
Value | Meaning |
---|---|
0 | None |
1 | TakePhoto |
2 | ToggleVideo |
3 | ModeAcro |
4 | ModeAltHold |
5 | ModeAuto |
6 | ModeLoiter |
7 | ModeRTL |
8 | ModeCircle |
9 | ModeLand |
10 | ModeDrift |
11 | ModeSport |
12 | ModeAutoTune |
13 | ModePosHold |
14 | ModeBrake |
15 | ModeThrow |
16 | Flip |
17 | ModeStabilize |
18 | Disarm |
19 | ToggleMode |
20 | Arm-Land-RTL |
21 | ToggleSimpleMode |
22 | ToggleSuperSimpleMode |
23 | MotorLoadTest |
Bitmask of flags to change the behaviour of tmode. DisarmOnLowThrottle means to disarm if throttle is held down for 1 second when landed. ArmOnHighThrottle means to arm if throttle is above 80% for 1 second. UpgradeToLoiter means to allow takeoff in LOITER mode by switching to ALT_HOLD, then auto-upgrading to LOITER once GPS is available. RTLStickCancel means that on large stick inputs in RTL mode that LOITER mode is engaged
This is the battery voltage below which no output limiting is done
This is the battery voltage above which thrust min is used
This sets the thrust multiplier when voltage is high
This sets the thrust multiplier when voltage is low
This scales the load test output, as a value between 0 and 1
This filters the load test output. A value of 1 means no filter. 2 means values are repeated once. 3 means values are repeated 3 times, etc
This sets the type of load test
Value | Meaning |
---|---|
0 | ConstantThrust |
1 | LogReplay1 |
2 | LogReplay2 |
Visual odometry camera connection type
Value | Meaning |
---|---|
0 | None |
1 | MAVLink |
2 | IntelT265 |
X position of the camera in body frame. Positive X is forward of the origin.
Y position of the camera in body frame. Positive Y is to the right of the origin.
Z position of the camera in body frame. Positive Z is down from the origin.
Visual odometery camera orientation
Value | Meaning |
---|---|
0 | Forward |
2 | Right |
4 | Back |
6 | Left |
24 | Up |
25 | Down |
Visual odometry scaling factor applied to position estimates from sensor
Visual odometry sensor delay relative to inertial measurements
Visual odometry velocity measurement noise in m/s
Visual odometry position measurement noise minimum (meters). This value will be used if the sensor provides a lower noise value (or no noise value)
Visual odometry yaw measurement noise minimum (radians), This value will be used if the sensor provides a lower noise value (or no noise value)
Toggles the Video Transmitter on and off
Value | Meaning |
---|---|
0 | Disable |
1 | Enable |
Video Transmitter Power Level. Different VTXs support different power levels, the power level chosen will be rounded down to the nearest supported power level
Video Transmitter Channel
Video Transmitter Band
Value | Meaning |
---|---|
0 | Band A |
1 | Band B |
2 | Band E |
3 | Airwave |
4 | RaceBand |
5 | Low RaceBand |
Video Transmitter Frequency. The frequency is derived from the setting of BAND and CHANNEL
Video Transmitter Options. Pitmode puts the VTX in a low power state. Unlocked enables certain restricted frequencies and power levels. Do not enable the Unlocked option unless you have appropriate permissions in your jurisdiction to transmit at high power levels.
Video Transmitter Maximum Power Level. Different VTXs support different power levels, this prevents the power aux switch from requesting too high a power level. The switch supports 6 power levels and the selected power will be a subdivision between 0 and this setting.
Winch Type
Value | Meaning |
---|---|
0 | None |
1 | PWM |
2 | Daiwa |
Winch deploy or retract rate maximum. Set to maximum rate with no load.
Winch control position error P gain
Defines the speed in cm/s which the aircraft will attempt to maintain horizontally during a WP mission
Defines the distance from a waypoint, that when crossed indicates the wp has been hit.
Defines the speed in cm/s which the aircraft will attempt to maintain while climbing during a WP mission
Defines the speed in cm/s which the aircraft will attempt to maintain while descending during a WP mission
Defines the horizontal acceleration in cm/s/s used during missions
Defines the vertical acceleration in cm/s/s used during missions
This controls if waypoint missions use rangefinder for terrain following
Value | Meaning |
---|---|
0 | Disable |
1 | Enable |
Defines the horizontal jerk in m/s/s used during missions
Allows you to enable (1) or disable (0) ZigZag auto feature
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Enable the auto sprayer in ZigZag mode. SPRAY_ENABLE = 1 and SERVOx_FUNCTION = 22(SprayerPump) / 23(SprayerSpinner) also must be set. This makes the sprayer on while moving to destination A or B. The sprayer will stop if the vehicle reaches destination or the flight mode is changed from ZigZag to other.
Value | Meaning |
---|---|
0 | Disabled |
1 | Enabled |
Waiting time after reached the destination
The distance to move sideways in ZigZag mode
The direction to move sideways in ZigZag mode
Value | Meaning |
---|---|
0 | forward |
1 | right |
2 | backward |
3 | left |
Total number of lines for ZigZag auto if 1 or more. -1: Infinity, 0: Just moving to sideways