Complete Parameter List

Full Parameter List of Plane latest V4.7.0 dev

You can change and check the parameters for another version:

This is a complete list of the parameters which can be set (e.g. via the MAVLink protocol) to control vehicle behaviour. They are stored in persistent storage on the vehicle.

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.

ArduPlane Parameters

FORMAT_VERSION: Eeprom format version number

Note: This parameter is for advanced users

This value is incremented when changes are made to the eeprom format

AUTOTUNE_LEVEL: Autotune level

Level of aggressiveness of pitch and roll PID gains. Lower values result in a 'softer' tune. Level 6 recommended for most planes. A value of 0 means to keep the current values of RMAX and TCONST for the controllers, tuning only the PID values

Increment

Range

1

0 to 10

AUTOTUNE_OPTIONS: Autotune options bitmask

Note: This parameter is for advanced users

Fixed Wing Autotune specific options. Useful on QuadPlanes with higher INS_GYRO_FILTER settings to prevent these filter values from being set too agressively during Fixed Wing Autotune.

Bitmask

Bit

Meaning

0

Disable FLTD update by Autotune

1

Disable FLTT update by Autotune

TELEM_DELAY: Telemetry startup delay

The amount of time (in seconds) to delay radio telemetry to prevent an Xbee bricking on power up

Increment

Range

Units

1

0 to 30

seconds

GCS_PID_MASK: GCS PID tuning mask

Note: This parameter is for advanced users

bitmask of PIDs to send MAVLink PID_TUNING messages for

Bitmask

Bit

Meaning

0

Roll

1

Pitch

2

Yaw

3

Steering

4

Landing

5

AccZ

KFF_RDDRMIX: Rudder Mix

Amount of rudder to add during aileron movement. Increase if nose initially yaws away from roll. Reduces adverse yaw.

Increment

Range

0.01

0 to 1

KFF_THR2PTCH: Throttle to Pitch Mix

Note: This parameter is for advanced users

Pitch up to add in proportion to throttle. 100% throttle will add this number of degrees to the pitch target.

Increment

Range

0.01

-5 to 5

STAB_PITCH_DOWN: Low throttle pitch down trim

Note: This parameter is for advanced users

Degrees of down pitch added when throttle is below TRIM_THROTTLE in FBWA and AUTOTUNE modes. Scales linearly so full value is added when THR_MIN is reached. Helps to keep airspeed higher in glides or landing approaches and prevents accidental stalls. 2 degrees recommended for most planes.

Increment

Range

Units

0.1

0 to 15

degrees

GLIDE_SLOPE_MIN: Glide slope minimum

Note: This parameter is for advanced users

This controls the minimum altitude change for a waypoint before a glide slope will be used instead of an immediate altitude change. The default value is 15 meters, which helps to smooth out waypoint missions where small altitude changes happen near waypoints. If you don't want glide slopes to be used in missions then you can set this to zero, which will disable glide slope calculations. Otherwise you can set it to a minimum number of meters of altitude error to the destination waypoint before a glide slope will be used to change altitude.

Increment

Range

Units

1

0 to 1000

meters

GLIDE_SLOPE_THR: Glide slope threshold

Note: This parameter is for advanced users

This controls the height above the glide slope the plane may be before rebuilding a glide slope. This is useful for smoothing out an autotakeoff

Increment

Range

Units

1

0 to 100

meters

STICK_MIXING: Stick Mixing

Note: This parameter is for advanced users

When enabled, this adds user stick input to the control surfaces in auto modes, allowing the user to have some degree of flight control without changing modes. There are two types of stick mixing available. If you set STICK_MIXING to 1 then it will use "fly by wire" mixing, which controls the roll and pitch in the same way that the FBWA mode does. This is the safest option if you usually fly ArduPlane in FBWA or FBWB mode. If you set STICK_MIXING to 3 then it will apply to the yaw while in quadplane modes only, such as while doing an automatic VTOL takeoff or landing.

Values

Value

Meaning

0

Disabled

1

FBWMixing

3

VTOL Yaw only

TKOFF_THR_MINSPD: Takeoff throttle min speed

Minimum GPS ground speed in m/s used by the speed check that un-suppresses throttle in auto-takeoff. This can be be used for catapult launches where you want the motor to engage only after the plane leaves the catapult, but it is preferable to use the TKOFF_THR_MINACC and TKOFF_THR_DELAY parameters for catapult launches due to the errors associated with GPS measurements. For hand launches with a pusher prop it is strongly advised that this parameter be set to a value no less than 4 m/s to provide additional protection against premature motor start. Note that the GPS velocity will lag the real velocity by about 0.5 seconds. The ground speed check is delayed by the TKOFF_THR_DELAY parameter.

Increment

Range

Units

0.1

0 to 30

meters per second

TKOFF_THR_MINACC: Takeoff throttle min acceleration

Minimum forward acceleration in m/s/s before arming the ground speed check in auto-takeoff. This is meant to be used for hand launches. Setting this value to 0 disables the acceleration test which means the ground speed check will always be armed which could allow GPS velocity jumps to start the engine. For hand launches and bungee launches this should be set to around 15. Also see TKOFF_ACCEL_CNT paramter for control of full "shake to arm".

Increment

Range

Units

0.1

0 to 30

meters per square second

TKOFF_THR_DELAY: Takeoff throttle delay

This parameter sets the time delay (in 1/10ths of a second) that the ground speed check is delayed after the forward acceleration check controlled by TKOFF_THR_MINACC has passed. For hand launches with pusher propellers it is essential that this is set to a value of no less than 2 (0.2 seconds) to ensure that the aircraft is safely clear of the throwers arm before the motor can start. For bungee launches a larger value can be used (such as 30) to give time for the bungee to release from the aircraft before the motor is started.

Increment

Range

Units

1

0 to 127

deciseconds

TKOFF_THR_MAX_T: Takeoff throttle maximum time

This sets the time that maximum throttle will be forced during a fixed wing takeoff.

Increment

Range

Units

0.5

0 to 10

seconds

TKOFF_THR_MIN: Takeoff minimum throttle

The minimum throttle to use in takeoffs in AUTO and TAKEOFF flight modes, when TKOFF_OPTIONS bit 0 is set. Also, the minimum throttle to use in a quadpane forward transition. This can be useful to ensure faster takeoffs or transitions on aircraft where the normal throttle control leads to a slow takeoff or transition. It is used when it is larger than THR_MIN, otherwise THR_MIN is used instead.

Increment

Range

Units

1

0 to 100

percent

TKOFF_THR_IDLE: Takeoff idle throttle

The idle throttle to hold after arming and before a takeoff. Applicable in TAKEOFF and AUTO modes.

Increment

Range

Units

1

0 to 100

percent

TKOFF_OPTIONS: Takeoff options

Note: This parameter is for advanced users

This selects the mode of the takeoff in AUTO and TAKEOFF flight modes.

Bitmask

Bit

Meaning

0

When unset the maximum allowed throttle is always used (THR_MAX or TKOFF_THR_MAX) during takeoff. When set TECS is allowed to operate between a minimum (THR_MIN or TKOFF_THR_MIN) and a maximum (THR_MAX or TKOFF_THR_MAX) limit. Applicable only when using an airspeed sensor.

TKOFF_TDRAG_ELEV: Takeoff tail dragger elevator

This parameter sets the amount of elevator to apply during the initial stage of a takeoff. It is used to hold the tail wheel of a taildragger on the ground during the initial takeoff stage to give maximum steering. This option should be combined with the TKOFF_TDRAG_SPD1 option and the GROUND_STEER_ALT option along with tuning of the ground steering controller. A value of zero means to bypass the initial "tail hold" stage of takeoff. Set to zero for hand and catapult launch. For tail-draggers you should normally set this to 100, meaning full up elevator during the initial stage of takeoff. For most tricycle undercarriage aircraft a value of zero will work well, but for some tricycle aircraft a small negative value (say around -20 to -30) will apply down elevator which will hold the nose wheel firmly on the ground during initial acceleration. Only use a negative value if you find that the nosewheel doesn't grip well during takeoff. Too much down elevator on a tricycle undercarriage may cause instability in steering as the plane pivots around the nosewheel. Add down elevator 10 percent at a time.

Increment

Range

Units

1

-100 to 100

percent

TKOFF_TDRAG_SPD1: Takeoff tail dragger speed1

This parameter sets the airspeed at which to stop holding the tail down and transition to rudder control of steering on the ground. When TKOFF_TDRAG_SPD1 is reached the pitch of the aircraft will be held level until TKOFF_ROTATE_SPD is reached, at which point the takeoff pitch specified in the mission will be used to "rotate" the pitch for takeoff climb. Set TKOFF_TDRAG_SPD1 to zero to go straight to rotation. This should be set to zero for hand launch and catapult launch. It should also be set to zero for tricycle undercarriages unless you are using the method above to gently hold the nose wheel down. For tail dragger aircraft it should be set just below the stall speed.

Increment

Range

Units

0.1

0 to 30

meters per second

TKOFF_ROTATE_SPD: Takeoff rotate speed

This parameter sets the airspeed at which the aircraft will "rotate", setting climb pitch specified in the mission. If TKOFF_ROTATE_SPD is zero then the climb pitch will be used as soon as takeoff is started. For hand launch and catapult launches a TKOFF_ROTATE_SPD of zero should be set. For all ground launches TKOFF_ROTATE_SPD should be set above the stall speed, usually by about 10 to 30 percent. During the run, use TKOFF_GND_PITCH to keep the aircraft on the runway while below this airspeed.

Increment

Range

Units

0.1

0 to 30

meters per second

TKOFF_THR_SLEW: Takeoff throttle slew rate

This parameter sets the slew rate for the throttle during auto takeoff. When this is zero the THR_SLEWRATE parameter is used during takeoff. For rolling takeoffs it can be a good idea to set a lower slewrate for takeoff to give a slower acceleration which can improve ground steering control. The value is a percentage throttle change per second, so a value of 20 means to advance the throttle over 5 seconds on takeoff. Values below 20 are not recommended as they may cause the plane to try to climb out with too little throttle. A value of -1 means no limit on slew rate in takeoff.

Increment

Range

Units

1

-1 to 127

percent per second

TKOFF_PLIM_SEC: Takeoff pitch limit reduction

Note: This parameter is for advanced users

This parameter reduces the pitch minimum limit of an auto-takeoff just a few seconds before it reaches the target altitude. This reduces overshoot by allowing the flight controller to start leveling off a few seconds before reaching the target height. When set to zero, the mission pitch min is enforced all the way to and through the target altitude, otherwise the pitch min slowly reduces to zero in the final segment. This is the pitch_min, not the demand. The flight controller should still be commanding to gain altitude to finish the takeoff but with this param it is not forcing it higher than it wants to be.

Increment

Range

Units

0.5

0 to 10

seconds

TKOFF_FLAP_PCNT: Takeoff flap percentage

Note: This parameter is for advanced users

The amount of flaps (as a percentage) to apply in automatic takeoff

Increment

Range

Units

1

0 to 100

percent

LEVEL_ROLL_LIMIT: Level flight roll limit

This controls the maximum bank angle in degrees during flight modes where level flight is desired, such as in the final stages of landing, and during auto takeoff. This should be a small angle (such as 5 degrees) to prevent a wing hitting the runway during takeoff or landing. Setting this to zero will completely disable heading hold on auto takeoff while below 5 meters and during the flare portion of a final landing approach.

Increment

Range

Units

1

0 to 45

degrees

USE_REV_THRUST: Bitmask for when to allow negative reverse thrust

Note: This parameter is for advanced users

This controls when to use reverse thrust. If set to zero then reverse thrust is never used. If set to a non-zero value then the bits correspond to flight stages where reverse thrust may be used. The most commonly used value for USE_REV_THRUST is 2, which means AUTO_LAND only. That enables reverse thrust in the landing stage of AUTO mode. Another common choice is 1, which means to use reverse thrust in all auto flight stages. Reverse thrust is always used in MANUAL mode if enabled with THR_MIN < 0. In non-autothrottle controlled modes, if reverse thrust is not used, then THR_MIN is effectively set to 0 for that mode.

Bitmask

Bit

Meaning

0

AUTO_ALWAYS

1

AUTO_LAND

2

AUTO_LOITER_TO_ALT

3

AUTO_LOITER_ALL

4

AUTO_WAYPOINTS

5

LOITER

6

RTL

7

CIRCLE

8

CRUISE

9

FBWB

10

GUIDED

11

AUTO_LANDING_PATTERN

12

FBWA

13

ACRO

14

STABILIZE

15

THERMAL

ALT_OFFSET: Altitude offset

Note: This parameter is for advanced users

This is added to the target altitude in automatic flight. It can be used to add a global altitude offset to a mission

Increment

Range

Units

1

-32767 to 32767

meters

WP_RADIUS: Waypoint Radius

Defines the maximum distance from a waypoint that when crossed indicates the waypoint may be complete. To avoid the aircraft looping around the waypoint in case it misses by more than the WP_RADIUS an additional check is made to see if the aircraft has crossed a "finish line" passing through the waypoint and perpendicular to the flight path from the previous waypoint. If that finish line is crossed then the waypoint is considered complete. Note that the navigation controller may decide to turn later than WP_RADIUS before a waypoint, based on how sharp the turn is and the speed of the aircraft. It is safe to set WP_RADIUS much larger than the usual turn radius of your aircraft and the navigation controller will work out when to turn. If you set WP_RADIUS too small then you will tend to overshoot the turns.

Increment

Range

Units

1

1 to 32767

meters

WP_MAX_RADIUS: Waypoint Maximum Radius

Sets the maximum distance to a waypoint for the waypoint to be considered complete. This overrides the "cross the finish line" logic that is normally used to consider a waypoint complete. For normal AUTO behaviour this parameter should be set to zero. Using a non-zero value is only recommended when it is critical that the aircraft does approach within the given radius, and should loop around until it has done so. This can cause the aircraft to loop forever if its turn radius is greater than the maximum radius set.

Increment

Range

Units

1

0 to 32767

meters

WP_LOITER_RAD: Waypoint Loiter Radius

Defines the distance from the waypoint center, the plane will maintain during a loiter. If you set this value to a negative number then the default loiter direction will be counter-clockwise instead of clockwise.

Increment

Range

Units

1

-32767 to 32767

meters

RTL_RADIUS: RTL loiter radius

Defines the radius of the loiter circle when in RTL mode. If this is zero then WP_LOITER_RAD is used. If the radius is negative then a counter-clockwise is used. If positive then a clockwise loiter is used.

Increment

Range

Units

1

-32767 to 32767

meters

STALL_PREVENTION: Enable stall prevention

Enables roll limits at low airspeed in roll limiting flight modes. Roll limits based on aerodynamic load factor in turns and scale on AIRSPEED_MIN that must be set correctly. Without airspeed sensor, uses synthetic airspeed from wind speed estimate that may both be inaccurate.

Values

Value

Meaning

0

Disabled

1

Enabled

AIRSPEED_CRUISE: Target cruise airspeed

Target cruise airspeed in m/s in automatic throttle modes. Value is as an indicated (calibrated/apparent) airspeed.

Units

meters per second

AIRSPEED_MIN: Minimum Airspeed

Minimum airspeed demanded in automatic throttle modes. Should be set to 20% higher than level flight stall speed.

Increment

Range

Units

1

5 to 100

meters per second

AIRSPEED_MAX: Maximum Airspeed

Maximum airspeed demanded in automatic throttle modes. Should be set slightly less than level flight speed at THR_MAX and also at least 50% above AIRSPEED_MIN to allow for accurate TECS altitude control.

Increment

Range

Units

1

5 to 100

meters per second

AIRSPEED_STALL: Stall airspeed

If stall prevention is enabled this speed is used to calculate the minimum airspeed while banking. If this is set to 0 then the stall speed is assumed to be the minimum airspeed speed. Typically set slightly higher then true stall speed. Value is as an indicated (calibrated/apparent) airspeed.

Range

Units

5 to 75

meters per second

FBWB_ELEV_REV: Fly By Wire elevator reverse

Reverse sense of elevator in FBWB and CRUISE modes. When set to 0 up elevator (pulling back on the stick) means to lower altitude. When set to 1, up elevator means to raise altitude.

Values

Value

Meaning

0

Disabled

1

Enabled

TERRAIN_FOLLOW: Use terrain following

This enables terrain following for CRUISE mode, FBWB mode, RTL and for rally points. To use this option you also need to set TERRAIN_ENABLE to 1, which enables terrain data fetching from the GCS, and you need to have a GCS that supports sending terrain data to the aircraft. When terrain following is enabled then CRUISE and FBWB mode will hold height above terrain rather than height above home. In RTL the return to launch altitude will be considered to be a height above the terrain. Rally point altitudes will be taken as height above the terrain. This option does not affect mission items, which have a per-waypoint flag for whether they are height above home or height above the terrain. To use terrain following missions you need a ground station which can set the waypoint type to be a terrain height waypoint when creating the mission.

Bitmask

Bit

Meaning

0

Enable all modes

1

FBWB

2

Cruise

3

Auto

4

RTL

5

Avoid_ADSB

6

Guided

7

Loiter

8

Circle

9

QRTL

10

QLand

11

Qloiter

TERRAIN_LOOKAHD: Terrain lookahead

This controls how far ahead the terrain following code looks to ensure it stays above upcoming terrain. A value of zero means no lookahead, so the controller will track only the terrain directly below the aircraft. The lookahead will never extend beyond the next waypoint when in AUTO mode.

Range

Units

0 to 10000

meters

FBWB_CLIMB_RATE: Fly By Wire B altitude change rate

This sets the rate in m/s at which FBWB and CRUISE modes will change its target altitude for full elevator deflection. Note that the actual climb rate of the aircraft can be lower than this, depending on your airspeed and throttle control settings. If you have this parameter set to the default value of 2.0, then holding the elevator at maximum deflection for 10 seconds would change the target altitude by 20 meters.

Increment

Range

Units

0.1

1 to 10

meters per second

THR_MIN: Minimum Throttle

Minimum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set. Negative values allow reverse thrust if hardware supports it.

Increment

Range

Units

1

-100 to 100

percent

THR_MAX: Maximum Throttle

Maximum throttle percentage used in all modes except manual, provided THR_PASS_STAB is not set.

Increment

Range

Units

1

0 to 100

percent

TKOFF_THR_MAX: Maximum Throttle for takeoff

Note: This parameter is for advanced users

The maximum throttle setting during automatic takeoff. If this is zero then THR_MAX is used for takeoff as well.

Increment

Range

Units

1

0 to 100

percent

THR_SLEWRATE: Throttle slew rate

Maximum change in throttle percentage per second. Lower limit based on 1 microsend of servo increase per loop. Divide SCHED_LOOP_RATE by approximately 10 to determine minimum achievable value.

Increment

Range

Units

1

0 to 127

percent per second

FLAP_SLEWRATE: Flap slew rate

Note: This parameter is for advanced users

maximum percentage change in flap output per second. A setting of 25 means to not change the flap by more than 25% of the full flap range in one second. A value of 0 means no rate limiting.

Increment

Range

Units

1

0 to 100

percent per second

THR_SUPP_MAN: Throttle suppress manual passthru

Note: This parameter is for advanced users

When throttle is suppressed in auto mode it is normally forced to zero. If you enable this option, then while suppressed it will be manual throttle. This is useful on petrol engines to hold the idle throttle manually while waiting for takeoff

Values

Value

Meaning

0

Disabled

1

Enabled

THR_PASS_STAB: Throttle passthru in stabilize

Note: This parameter is for advanced users

If this is set then when in STABILIZE, FBWA or ACRO modes the throttle is a direct passthru from the transmitter. This means the THR_MIN and THR_MAX settings are not used in these modes. This is useful for petrol engines where you setup a throttle cut switch that suppresses the throttle below the normal minimum.

Values

Value

Meaning

0

Disabled

1

Enabled

THR_FAILSAFE: Throttle and RC Failsafe Enable

0 disables the failsafe. 1 enables failsafe on loss of RC input. This is detected either by throttle values below THR_FS_VALUE, loss of receiver valid pulses/data, or by the FS bit in receivers that provide it, like SBUS. A programmable failsafe action will occur and RC inputs, if present, will be ignored. A value of 2 means that the RC inputs won't be used when RC failsafe is detected by any of the above methods, but it won't trigger an RC failsafe action.

Values

Value

Meaning

0

Disabled

1

Enabled

2

EnabledNoFailsafe

THR_FS_VALUE: Throttle Failsafe Value

The PWM level on the throttle input channel below which throttle failsafe triggers. Note that this should be well below the normal minimum for your throttle channel.

Increment

Range

1

925 to 2200

TRIM_THROTTLE: Throttle cruise percentage

Target percentage of throttle to apply for flight in automatic throttle modes and throttle percentage that maintains AIRSPEED_CRUISE. Caution: low battery voltages at the end of flights may require higher throttle to maintain airspeed.

Increment

Range

Units

1

0 to 100

percent

THROTTLE_NUDGE: Throttle nudge enable

When enabled, this uses the throttle input in auto-throttle modes to 'nudge' the throttle or airspeed to higher or lower values. When you have an airspeed sensor the nudge affects the target airspeed, so that throttle inputs above 50% will increase the target airspeed from AIRSPEED_CRUISE up to a maximum of AIRSPEED_MAX. When no airspeed sensor is enabled the throttle nudge will push up the target throttle for throttle inputs above 50%.

Values

Value

Meaning

0

Disabled

1

Enabled

FS_SHORT_ACTN: Short failsafe action

The action to take on a short (FS_SHORT_TIMEOUT) failsafe event. A short failsafe event can be triggered either by loss of RC control (see THR_FS_VALUE) or by loss of GCS control (see FS_GCS_ENABL). If in CIRCLE or RTL mode this parameter is ignored. A short failsafe event in stabilization and manual modes will cause a change to CIRCLE mode if FS_SHORT_ACTN is 0 or 1, a change to FBWA mode with zero throttle if FS_SHORT_ACTN is 2, and a change to FBWB mode if FS_SHORT_ACTN is 4. In all other modes (AUTO, GUIDED and LOITER) a short failsafe event will cause no mode change if FS_SHORT_ACTN is set to 0, will cause a change to CIRCLE mode if set to 1, will change to FBWA mode with zero throttle if set to 2, or will change to FBWB if set to 4. Please see the documentation for FS_LONG_ACTN for the behaviour after FS_LONG_TIMEOUT seconds of failsafe. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5(QRTL) or 20(RTL) are set.

Values

Value

Meaning

0

CIRCLE/no change(if already in AUTO|GUIDED|LOITER)

1

CIRCLE

2

FBWA at zero throttle

3

Disable

4

FBWB

FS_SHORT_TIMEOUT: Short failsafe timeout

The time in seconds that a failsafe condition has to persist before a short failsafe event will occur. This defaults to 1.5 seconds

Increment

Range

Units

0.5

1 to 100

seconds

FS_LONG_ACTN: Long failsafe action

The action to take on a long (FS_LONG_TIMEOUT seconds) failsafe event. If the aircraft was in a stabilization or manual mode when failsafe started and a long failsafe occurs then it will change to RTL mode if FS_LONG_ACTN is 0 or 1, and will change to FBWA if FS_LONG_ACTN is set to 2. If the aircraft was in an auto mode (such as AUTO or GUIDED) when the failsafe started then it will continue in the auto mode if FS_LONG_ACTN is set to 0, will change to RTL mode if FS_LONG_ACTN is set to 1 and will change to FBWA mode if FS_LONG_ACTN is set to 2. If FS_LONG_ACTN is set to 3, the parachute will be deployed (make sure the chute is configured and enabled). If FS_LONG_ACTN is set to 4 the aircraft will switch to mode AUTO with the current waypoint if it is not already in mode AUTO, unless it is in the middle of a landing sequence. This parameter only applies to failsafes during fixed wing modes. Quadplane modes will switch to QLAND unless Q_OPTIONS bit 5 (QRTL) or 20(RTL) are set.

Values

Value

Meaning

0

Continue

1

ReturnToLaunch

2

Glide

3

Deploy Parachute

4

Auto

FS_LONG_TIMEOUT: Long failsafe timeout

The time in seconds that a failsafe condition has to persist before a long failsafe event will occur. This defaults to 5 seconds.

Increment

Range

Units

0.5

1 to 300

seconds

FS_GCS_ENABL: GCS failsafe enable

Enable ground control station telemetry failsafe. Failsafe will trigger after FS_LONG_TIMEOUT seconds of no MAVLink heartbeat messages. There are three possible enabled settings. Setting FS_GCS_ENABL to 1 means that GCS failsafe will be triggered when the aircraft has not received a MAVLink HEARTBEAT message. Setting FS_GCS_ENABL to 2 means that GCS failsafe will be triggered on either a loss of HEARTBEAT messages, or a RADIO_STATUS message from a MAVLink enabled 3DR radio indicating that the ground station is not receiving status updates from the aircraft, which is indicated by the RADIO_STATUS.remrssi field being zero (this may happen if you have a one way link due to asymmetric noise on the ground station and aircraft radios).Setting FS_GCS_ENABL to 3 means that GCS failsafe will be triggered by Heartbeat(like option one), but only in AUTO mode. WARNING: Enabling this option opens up the possibility of your plane going into failsafe mode and running the motor on the ground it it loses contact with your ground station. If this option is enabled on an electric plane then you should enable ARMING_REQUIRED.

Values

Value

Meaning

0

Disabled

1

Heartbeat

2

HeartbeatAndREMRSSI

3

HeartbeatAndAUTO

FLTMODE_CH: Flightmode channel

Note: This parameter is for advanced users

RC Channel to use for flight mode control

Values

Value

Meaning

0

Disabled

1

Channel 1

2

Channel 2

3

Channel 3

4

Channel 4

5

Channel 5

6

Channel 6

7

Channel 7

8

Channel 8

9

Channel 9

10

Channel 10

11

Channel 11

12

Channel 12

13

Channel 13

14

Channel 14

15

Channel 15

16

Channel 16

FLTMODE1: FlightMode1

Flight mode for switch position 1 (910 to 1230 and above 2049)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

FLTMODE2: FlightMode2

Flight mode for switch position 2 (1231 to 1360)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

FLTMODE3: FlightMode3

Flight mode for switch position 3 (1361 to 1490)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

FLTMODE4: FlightMode4

Flight mode for switch position 4 (1491 to 1620)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

FLTMODE5: FlightMode5

Flight mode for switch position 5 (1621 to 1749)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

FLTMODE6: FlightMode6

Flight mode for switch position 6 (1750 to 2049)

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

INITIAL_MODE: Initial flight mode

Note: This parameter is for advanced users

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.

Values

Value

Meaning

0

Manual

1

CIRCLE

2

STABILIZE

3

TRAINING

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

10

Auto

11

RTL

12

Loiter

13

TAKEOFF

14

AVOID_ADSB

15

Guided

17

QSTABILIZE

18

QHOVER

19

QLOITER

20

QLAND

21

QRTL

22

QAUTOTUNE

23

QACRO

24

THERMAL

25

Loiter to QLand

ROLL_LIMIT_DEG: Maximum Bank Angle

Maximum bank angle commanded in modes with stabilized limits. Increase this value for sharper turns, but decrease to prevent accelerated stalls.

Increment

Range

Units

1

0 to 90

degrees

PTCH_LIM_MAX_DEG: Maximum Pitch Angle

Maximum pitch up angle commanded in modes with stabilized limits.

Increment

Range

Units

1

0 to 90

degrees

PTCH_LIM_MIN_DEG: Minimum Pitch Angle

Maximum pitch down angle commanded in modes with stabilized limits

Increment

Range

Units

1

-90 to 0

degrees

ACRO_ROLL_RATE: ACRO mode roll rate

The maximum roll rate at full stick deflection in ACRO mode

Increment

Range

Units

1

10 to 500

degrees per second

ACRO_PITCH_RATE: ACRO mode pitch rate

The maximum pitch rate at full stick deflection in ACRO mode

Increment

Range

Units

1

10 to 500

degrees per second

ACRO_YAW_RATE: ACRO mode yaw rate

The maximum yaw rate at full stick deflection in ACRO mode. If this is zero then rudder is directly controlled by rudder stick input. This option is only available if you also set YAW_RATE_ENABLE to 1.

Increment

Range

Units

1

0 to 500

degrees per second

ACRO_LOCKING: ACRO mode attitude locking

Enable attitude locking when sticks are released. If set to 2 then quaternion based locking is used if the yaw rate controller is enabled. Quaternion based locking will hold any attitude

Values

Value

Meaning

0

Disabled

1

Enabled

2

Quaternion

GROUND_STEER_ALT: Ground steer altitude

Altitude at which to use the ground steering controller on the rudder. If non-zero then the STEER2SRV controller will be used to control the rudder for altitudes within this limit of the home altitude.

Increment

Range

Units

0.1

-100 to 100

meters

GROUND_STEER_DPS: Ground steer rate

Note: This parameter is for advanced users

Ground steering rate in degrees per second for full rudder stick deflection

Increment

Range

Units

1

10 to 360

degrees per second

MIXING_GAIN: Mixing Gain

The gain for the Vtail and elevon output mixers. The default is 0.5, which ensures that the mixer doesn't saturate, allowing both input channels to go to extremes while retaining control over the output. Hardware mixers often have a 1.0 gain, which gives more servo throw, but can saturate. If you don't have enough throw on your servos with VTAIL_OUTPUT or ELEVON_OUTPUT enabled then you can raise the gain using MIXING_GAIN. The mixer allows outputs in the range 900 to 2100 microseconds.

Range

0.5 to 1.2

RUDDER_ONLY: Rudder only aircraft

Enable rudder only mode. The rudder will control attitude in attitude controlled modes (such as FBWA). You should setup your transmitter to send roll stick inputs to the RCMAP_YAW channel (normally channel 4). The rudder servo should be attached to the RCMAP_YAW channel as well. Note that automatic ground steering will be disabled for rudder only aircraft. You should also set KFF_RDDRMIX to 1.0. You will also need to setup the YAW2SRV_DAMP yaw damping appropriately for your aircraft. A value of 0.5 for YAW2SRV_DAMP is a good starting point.

Values

Value

Meaning

0

Disabled

1

Enabled

MIXING_OFFSET: Mixing Offset

The offset for the Vtail and elevon output mixers, as a percentage. This can be used in combination with MIXING_GAIN to configure how the control surfaces respond to input. The response to aileron or elevator input can be increased by setting this parameter to a positive or negative value. A common usage is to enter a positive value to increase the aileron response of the elevons of a flying wing. The default value of zero will leave the aileron-input response equal to the elevator-input response.

Range

Units

-1000 to 1000

decipercent

DSPOILR_RUD_RATE: Differential spoilers rudder rate

Sets the amount of deflection that the rudder output will apply to the differential spoilers, as a percentage. The default value of 100 results in full rudder applying full deflection. A value of 0 will result in the differential spoilers exactly following the elevons (no rudder effect).

Range

Units

-100 to 100

percent

LOG_BITMASK: Log bitmask

Note: This parameter is for advanced users

Bitmap of what on-board log types to enable. This value is made up of the sum of each of the log types you want to be saved. It is usually best just to enable all basic log types by setting this to 65535.

Bitmask

Bit

Meaning

0

Fast Attitude

1

Medium Attitude

2

GPS

3

Performance

4

Control Tuning

5

Navigation Tuning

7

IMU

8

Mission Commands

9

Battery Monitor

10

Compass

11

TECS

12

Camera

13

RC Input-Output

14

Rangefinder

19

Raw IMU

20

Fullrate Attitude

21

Video Stabilization

22

Fullrate Notch

SCALING_SPEED: speed used for speed scaling calculations

Note: This parameter is for advanced users

Airspeed in m/s to use when calculating surface speed scaling. Note that changing this value will affect all PID values

Increment

Range

Units

0.1

0 to 50

meters per second

MIN_GROUNDSPEED: Minimum ground speed

Note: This parameter is for advanced users

Minimum ground speed when under airspeed control

Units

meters per second

PTCH_TRIM_DEG: Pitch angle offset

Offset in degrees used for in-flight pitch trimming for level flight. Correct ground leveling is an alternative to changing this parameter.

Range

Units

-45 to 45

degrees

RTL_ALTITUDE: RTL altitude

Target altitude above home for RTL mode. Maintains current altitude if set to -1. Rally point altitudes are used if plane does not return to home.

Units

meters

CRUISE_ALT_FLOOR: Minimum altitude for FBWB and CRUISE mode

This is the minimum altitude in meters (above home) that FBWB and CRUISE modes will allow. If you attempt to descend below this altitude then the plane will level off. It will also force a climb to this altitude if below in these modes. A value of zero means no limit.

Units

meters

FLAP_1_PERCNT: Flap 1 percentage

Note: This parameter is for advanced users

The percentage change in flap position when FLAP_1_SPEED is reached. Use zero to disable flaps

Increment

Range

Units

1

0 to 100

percent

FLAP_1_SPEED: Flap 1 speed

Note: This parameter is for advanced users

The speed in meters per second at which to engage FLAP_1_PERCENT of flaps. Note that FLAP_1_SPEED should be greater than or equal to FLAP_2_SPEED

Increment

Range

Units

1

0 to 100

meters per second

FLAP_2_PERCNT: Flap 2 percentage

Note: This parameter is for advanced users

The percentage change in flap position when FLAP_2_SPEED is reached. Use zero to disable flaps

Increment

Range

Units

1

0 to 100

percent

FLAP_2_SPEED: Flap 2 speed

Note: This parameter is for advanced users

The speed in meters per second at which to engage FLAP_2_PERCENT of flaps. Note that FLAP_1_SPEED should be greater than or equal to FLAP_2_SPEED

Increment

Range

Units

1

0 to 100

meters per second

OVERRIDE_CHAN: IO override channel

Note: This parameter is for advanced users

If set to a non-zero value then this is an RC input channel number to use for giving IO manual control in case the main FMU microcontroller on a board with a IO co-processor fails. When this RC input channel goes above 1750 the FMU microcontroller will no longer be involved in controlling the servos and instead the IO microcontroller will directly control the servos. Note that IO manual control will be automatically activated if the FMU crashes for any reason. This parameter allows you to test for correct manual behaviour without actually crashing the FMU. This parameter is can be set to a non-zero value either for ground testing purposes or for giving the effect of an external override control board. Note that you may set OVERRIDE_CHAN to the same channel as FLTMODE_CH to get IO based override when in flight mode 6. Note that when override is triggered due to a FMU crash the 6 auxiliary output channels on the FMU will no longer be updated, so all the flight controls you need must be assigned to the first 8 channels on boards with an IOMCU.

Increment

Range

1

0 to 16

RTL_AUTOLAND: RTL auto land

Automatically begin landing sequence after arriving at RTL location. This requires the addition of a DO_LAND_START mission item, which acts as a marker for the start of a landing sequence. The closest landing sequence will be chosen to the current location. If this is set to 0 and there is a DO_LAND_START mission item then you will get an arming check failure. You can set to a value of 3 to avoid the arming check failure and use the DO_LAND_START for go-around without it changing RTL behaviour. For a value of 1 a rally point will be used instead of HOME if in range (see rally point documentation).

Values

Value

Meaning

0

Disable

1

Fly HOME then land via DO_LAND_START mission item

2

Go directly to landing sequence via DO_LAND_START mission item

3

OnlyForGoAround

4

Go directly to landing sequence via DO_RETURN_PATH_START mission item

CRASH_ACC_THRESH: Crash Deceleration Threshold

Note: This parameter is for advanced users

X-Axis deceleration threshold to notify the crash detector that there was a possible impact which helps disarm the motor quickly after a crash. This value should be much higher than normal negative x-axis forces during normal flight, check flight log files to determine the average IMU.x values for your aircraft and motor type. Higher value means less sensative (triggers on higher impact). For electric planes that don't vibrate much during fight a value of 25 is good (that's about 2.5G). For petrol/nitro planes you'll want a higher value. Set to 0 to disable the collision detector.

Increment

Range

Units

1

10 to 127

meters per square second

CRASH_DETECT: Crash Detection

Note: This parameter is for advanced users

Automatically detect a crash during AUTO flight and perform the bitmask selected action(s). Disarm will turn off motor for safety and to help against burning out ESC and motor. Set to 0 to disable crash detection.

Bitmask

Bit

Meaning

0

Disarm

RNGFND_LANDING: Enable rangefinder for landing

This enables the use of a rangefinder for automatic landing. The rangefinder will be used both on the landing approach and for final flare

Values

Value

Meaning

0

Disabled

1

Enabled

SYSID_ENFORCE: GCS sysid enforcement

Note: This parameter is for advanced users

This controls whether packets from other than the expected GCS system ID will be accepted

Values

Value

Meaning

0

NotEnforced

1

Enforced

RUDD_DT_GAIN: rudder differential thrust gain

gain control from rudder to differential thrust

Increment

Range

Units

1

0 to 100

percent

MANUAL_RCMASK: Manual R/C pass-through mask

Note: This parameter is for advanced users

Mask of R/C channels to pass directly to corresponding output channel when in MANUAL mode. When in any mode except MANUAL the channels selected with this option behave normally. This parameter is designed to allow for complex mixing strategies to be used for MANUAL flight using transmitter based mixing. Note that when this option is used you need to be very careful with pre-flight checks to ensure that the output is correct both in MANUAL and non-MANUAL modes.

Bitmask

Bit

Meaning

0

Chan1

1

Chan2

2

Chan3

3

Chan4

4

Chan5

5

Chan6

6

Chan7

7

Chan8

8

Chan9

9

Chan10

10

Chan11

11

Chan12

12

Chan13

13

Chan14

14

Chan15

15

Chan16

HOME_RESET_ALT: Home reset altitude threshold

Note: This parameter is for advanced users

When the aircraft is within this altitude of the home waypoint, while disarmed it will automatically update the home position. Set to 0 to continously reset it.

Range

Units

Values

-1 to 127

meters

Value

Meaning

-1

Never reset

0

Always reset

FLIGHT_OPTIONS: Flight mode options

Note: This parameter is for advanced users

Flight mode specific options

Bitmask

Bit

Meaning

0

Rudder mixing in direct flight modes only (Manual/Stabilize/Acro)

1

Use centered throttle in Cruise or FBWB to indicate trim airspeed

2

Disable attitude check for takeoff arming

3

Force target airspeed to trim airspeed in Cruise or FBWB

4

Climb to RTL_ALTITUDE before turning for RTL

5

Enable yaw damper in acro mode

6

Supress speed scaling during auto takeoffs to be 1 or less to prevent oscillations without airspeed sensor.

7

EnableDefaultAirspeed for takeoff

8

Remove the PTCH_TRIM_DEG on the GCS horizon

9

Remove the PTCH_TRIM_DEG on the OSD horizon

10

Adjust mid-throttle to be TRIM_THROTTLE in non-auto throttle modes except MANUAL

11

Disable suppression of fixed wing rate gains in ground mode

12

Enable FBWB style loiter altitude control

13

Indicate takeoff waiting for neutral rudder with flight control surfaces

14

In AUTO - climb to next waypoint altitude immediately instead of linear climb

TKOFF_ACCEL_CNT: Takeoff throttle acceleration count

This is the number of acceleration events to require for arming with TKOFF_THR_MINACC. The default is 1, which means a single forward acceleration above TKOFF_THR_MINACC will arm. By setting this higher than 1 you can require more forward/backward movements to arm.

Range

1 to 10

DSPOILER_CROW_W1: Differential spoiler crow flaps outer weight

Note: This parameter is for advanced users

This is amount of deflection applied to the two outer surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 25.

Increment

Range

Units

1

0 to 100

percent

DSPOILER_CROW_W2: Differential spoiler crow flaps inner weight

Note: This parameter is for advanced users

This is amount of deflection applied to the two inner surfaces for differential spoilers for flaps to give crow flaps. It is a number from 0 to 100. At zero no crow flaps are applied. A recommended starting value is 45.

Increment

Range

Units

1

0 to 100

percent

TKOFF_TIMEOUT: Takeoff timeout

This is the timeout for an automatic takeoff. If this is non-zero and the aircraft does not reach a ground speed of at least 4 m/s within this number of seconds then the takeoff is aborted and the vehicle disarmed. If the value is zero then no timeout applies.

Increment

Range

Units

1

0 to 120

seconds

DSPOILER_OPTS: Differential spoiler and crow flaps options

Note: This parameter is for advanced users

Differential spoiler and crow flaps options. Progressive crow flaps only first (0-50% flap in) then crow flaps (50 - 100% flap in).

Bitmask

Bit

Meaning

0

Pitch input

1

use both control surfaces on each wing for roll

2

Progressive crow flaps

DSPOILER_AILMTCH: Differential spoiler aileron matching

Note: This parameter is for advanced users

This scales down the inner flaps so less than full downwards range can be used for differential spoiler and full span ailerons, 100 is use full range, upwards travel is unaffected

Increment

Range

Units

1

0 to 100

percent

FWD_BAT_VOLT_MAX: Forward throttle battery voltage compensation maximum voltage

Note: This parameter is for advanced users

Forward throttle battery voltage compensation maximum voltage (voltage above this will have no additional scaling effect on thrust). Recommend 4.2 * cell count, 0 = Disabled. Recommend THR_MAX is set to no more than 100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX, THR_MIN is set to no less than -100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX and climb descent rate limits are set accordingly.

Increment

Range

Units

0.1

6 to 35

volt

FWD_BAT_VOLT_MIN: Forward throttle battery voltage compensation minimum voltage

Note: This parameter is for advanced users

Forward throttle battery voltage compensation minimum voltage (voltage below this will have no additional scaling effect on thrust). Recommend 3.5 * cell count, 0 = Disabled. Recommend THR_MAX is set to no more than 100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX, THR_MIN is set to no less than -100 x FWD_BAT_VOLT_MIN / FWD_BAT_VOLT_MAX and climb descent rate limits are set accordingly.

Increment

Range

Units

0.1

6 to 35

volt

FWD_BAT_IDX: Forward throttle battery compensation index

Note: This parameter is for advanced users

Which battery monitor should be used for doing compensation for the forward throttle

Values

Value

Meaning

0

First battery

1

Second battery

FS_EKF_THRESH: EKF failsafe variance threshold

Note: This parameter is for advanced users

Allows setting the maximum acceptable compass and velocity variance used to check navigation health in VTOL modes

Values

Value

Meaning

0.6

Strict

0.8

Default

1.0

Relaxed

RTL_CLIMB_MIN: RTL minimum climb

The vehicle will climb this many m during the initial climb portion of the RTL. During this time the roll will be limited to LEVEL_ROLL_LIMIT degrees.

Increment

Range

Units

1

0 to 30

meters

MAN_EXPO_ROLL: Manual control expo for roll

Percentage exponential for roll input in MANUAL, ACRO and TRAINING modes

Increment

Range

1

0 to 100

MAN_EXPO_PITCH: Manual input expo for pitch

Percentage exponential for pitch input in MANUAL, ACRO and TRAINING modes

Increment

Range

1

0 to 100

MAN_EXPO_RUDDER: Manual input expo for rudder

Percentage exponential for rudder input in MANUAL, ACRO and TRAINING modes

Increment

Range

1

0 to 100

ONESHOT_MASK: Oneshot output mask

Note: This parameter is for advanced users

Mask of output channels to use oneshot on

Bitmask

Bit

Meaning

0

Servo 1

1

Servo 2

2

Servo 3

3

Servo 4

4

Servo 5

5

Servo 6

6

Servo 7

7

Servo 8

8

Servo 9

9

Servo 10

10

Servo 11

11

Servo 12

12

Servo 13

13

Servo 14

14

Servo 15

AUTOTUNE_AXES: Autotune axis bitmask

1-byte bitmap of axes to autotune

Bitmask

Bit

Meaning

0

Roll

1

Pitch

2

Yaw

RNGFND_LND_ORNT: rangefinder landing orientation

The orientation of rangefinder to use for landing detection. Should be set to Down for normal downward facing rangefinder and Back for rearward facing rangefinder for quadplane tailsitters. Custom orientation can be used with Custom1 or Custom2. The orientation must match at least one of the available rangefinders.

Values

Value

Meaning

4

Back

25

Down

101

Custom1

102

Custom2

VEHICLE Parameters

FLTMODE_GCSBLOCK: Flight mode block from GCS

Bitmask of flight modes to disable for GCS selection. Mode can still be accessed via RC or failsafe.

Bitmask

Bit

Meaning

0

Manual

1

Circle

2

Stabilize

3

Training

4

ACRO

5

FBWA

6

FBWB

7

CRUISE

8

AUTOTUNE

9

Auto

10

Loiter

11

Takeoff

12

AVOID_ADSB

13

Guided

14

THERMAL

15

QSTABILIZE

16

QHOVER

17

QLOITER

18

QACRO

19

QAUTOTUNE

ADSB_ Parameters

ADSB_TYPE: ADSB Type

Note: Reboot required after change

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

Values

Value

Meaning

0

Disabled

1

uAvionix-MAVLink

2

Sagetech

3

uAvionix-UCP

4

Sagetech MX Series

ADSB_LIST_MAX: ADSB vehicle list size

Note: This parameter is for advanced users
Note: Reboot required after change

ADSB list size of nearest vehicles. Longer lists take longer to refresh with lower SRx_ADSB values.

Range

1 to 100

ADSB_LIST_RADIUS: ADSB vehicle list radius filter

Note: This parameter is for advanced users

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.

Range

Units

0 to 100000

meters

ADSB_ICAO_ID: ICAO_ID vehicle identification number

Note: This parameter is for advanced users

ICAO_ID unique vehicle identification number of this aircraft. This is an 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.

Range

-1 to 16777215

ADSB_EMIT_TYPE: Emitter type

Note: This parameter is for advanced users

ADSB classification for the type of vehicle emitting the transponder signal. Default value is 14 (UAV).

Values

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

ADSB_LEN_WIDTH: Aircraft length and width

Note: This parameter is for advanced users

Aircraft length and width dimension options in Length and Width in meters. In most cases, use a value of 1 for smallest size.

Values

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

ADSB_OFFSET_LAT: GPS antenna lateral offset

Note: This parameter is for advanced users

GPS antenna lateral offset. This describes the physical location offset from center of the GPS antenna on the aircraft.

Values

Value

Meaning

0

NoData

1

Left2m

2

Left4m

3

Left6m

4

Center

5

Right2m

6

Right4m

7

Right6m

ADSB_OFFSET_LON: GPS antenna longitudinal offset

Note: This parameter is for advanced users

GPS antenna longitudinal offset. This is usually set to 1, Applied By Sensor

Values

Value

Meaning

0

NO_DATA

1

AppliedBySensor

ADSB_RF_SELECT: Transceiver RF selection

Note: This parameter is for advanced users

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.

Bitmask

Bit

Meaning

0

Rx

1

Tx

ADSB_SQUAWK: Squawk code

Note: This parameter is for advanced users

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.

Range

Units

0 to 7777

octal

ADSB_RF_CAPABLE: RF capabilities

Note: This parameter is for advanced users

Describes your hardware RF In/Out capabilities.

Bitmask

Bit

Meaning

0

UAT_in

1

1090ES_in

2

UAT_out

3

1090ES_out

ADSB_LIST_ALT: ADSB vehicle list altitude filter

Note: This parameter is for advanced users

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.

Range

Units

0 to 32767

meters

ADSB_ICAO_SPECL: ICAO_ID of special vehicle

Note: This parameter is for advanced users

ICAO_ID of special vehicle that ignores ADSB_LIST_RADIUS and ADSB_LIST_ALT. The vehicle is always tracked. Use 0 to disable.

ADSB_LOG: ADS-B logging

Note: This parameter is for advanced users

0: no logging, 1: log only special ID, 2:log all

Values

Value

Meaning

0

no logging

1

log only special ID

2

log all

ADSB_OPTIONS: ADS-B Options

Note: This parameter is for advanced users

Options for emergency failsafe codes and device capabilities

Bitmask

Bit

Meaning

0

Ping200X Send GPS

1

Squawk 7400 on RC failsafe

2

Squawk 7400 on GCS failsafe

3

Sagetech MXS use External Config

AFS_ Parameters

AFS_ENABLE: Enable Advanced Failsafe

Note: This parameter is for advanced users

This enables the advanced failsafe system. If this is set to zero (disable) then all the other AFS options have no effect

AFS_MAN_PIN: Manual Pin

Note: This parameter is for advanced users

This sets a digital output pin to set high when in manual mode. See the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.

AFS_HB_PIN: Heartbeat Pin

Note: This parameter is for advanced users

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. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.

Values

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

AFS_WP_COMMS: Comms Waypoint

Note: This parameter is for advanced users

Waypoint number to navigate to on comms loss

AFS_WP_GPS_LOSS: GPS Loss Waypoint

Note: This parameter is for advanced users

Waypoint number to navigate to on GPS lock loss

AFS_TERMINATE: Force Terminate

Note: This parameter is for advanced users

Can be set in flight to force termination of the heartbeat signal

AFS_TERM_ACTION: Terminate action

Note: This parameter is for advanced users

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

AFS_TERM_PIN: Terminate Pin

Note: This parameter is for advanced users

This sets a digital output pin to set high on flight termination. Some common values are given, but see the Wiki's "GPIOs" page for how to determine the pin number for a given autopilot.

Values

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

AFS_AMSL_LIMIT: AMSL limit

Note: This parameter is for advanced users

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.

Units

meters

AFS_AMSL_ERR_GPS: Error margin for GPS based AMSL limit

Note: This parameter is for advanced users

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.

Units

meters

AFS_QNH_PRESSURE: QNH pressure

Note: This parameter is for advanced users

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.

Units

hectopascal

AFS_MAX_GPS_LOSS: Maximum number of GPS loss events

Note: This parameter is for advanced users

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.

AFS_MAX_COM_LOSS: Maximum number of comms loss events

Note: This parameter is for advanced users

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.

AFS_GEOFENCE: Enable geofence Advanced Failsafe

Note: This parameter is for advanced users

This enables the geofence part of the AFS. Will only be in effect if AFS_ENABLE is also 1

AFS_RC: Enable RC Advanced Failsafe

Note: This parameter is for advanced users

This enables the RC part of the AFS. Will only be in effect if AFS_ENABLE is also 1

AFS_RC_MAN_ONLY: Enable RC Termination only in manual control modes

Note: This parameter is for advanced users

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.

AFS_DUAL_LOSS: Enable dual loss terminate due to failure of both GCS and GPS simultaneously

Note: This parameter is for advanced users

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.

AFS_RC_FAIL_TIME: RC failure time

Note: This parameter is for advanced users

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.

Units

seconds

AFS_MAX_RANGE: Max allowed range

Note: This parameter is for advanced users

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.

Units

kilometers

AFS_OPTIONS: AFS options

See description for each bitmask bit description

Bitmask

Bit

Meaning

0

Continue the mission even after comms are recovered (does not go to the mission item at the time comms were lost)

1

Enable AFS for all autonomous modes (not just AUTO)

AFS_GCS_TIMEOUT: GCS timeout

Note: This parameter is for advanced users

The time (in seconds) of persistent data link loss before GCS failsafe occurs.

Units

seconds

AHRS_ Parameters

AHRS_GPS_GAIN: AHRS GPS gain

Note: This parameter is for advanced users

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.

Increment

Range

.01

0.0 to 1.0

AHRS_GPS_USE: AHRS use GPS for DCM navigation and position-down

Note: This parameter is for advanced users

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 according to its own parameters. A value of 2 means to use GPS for height as well as position - both in DCM estimation and when determining altitude-above-home.

Values

Value

Meaning

0

Disabled

1

Use GPS for DCM position

2

Use GPS for DCM position and height

AHRS_YAW_P: Yaw P

Note: This parameter is for advanced users

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.

Increment

Range

.01

0.1 to 0.4

AHRS_RP_P: AHRS RP_P

Note: This parameter is for advanced users

This controls how fast the accelerometers correct the attitude

Increment

Range

.01

0.1 to 0.4

AHRS_WIND_MAX: Maximum wind

Note: This parameter is for advanced users

This sets the maximum allowable difference between ground speed and airspeed. A value of zero means to use the airspeed as is. This allows the plane to cope with a failing airspeed sensor by clipping it to groundspeed plus/minus this limit. See ARSPD_OPTIONS and ARSPD_WIND_MAX to disable airspeed sensors.

Increment

Range

Units

1

0 to 127

meters per second

AHRS_TRIM_X: AHRS Trim Roll

Compensates for the roll angle difference between the control board and the frame. Positive values make the vehicle roll right.

Increment

Range

Units

0.01

-0.1745 to +0.1745

radians

AHRS_TRIM_Y: AHRS Trim Pitch

Compensates for the pitch angle difference between the control board and the frame. Positive values make the vehicle pitch up/back.

Increment

Range

Units

0.01

-0.1745 to +0.1745

radians

AHRS_TRIM_Z: AHRS Trim Yaw

Note: This parameter is for advanced users

Not Used

Increment

Range

Units

0.01

-0.1745 to +0.1745

radians

AHRS_ORIENTATION: Board Orientation

Note: This parameter is for advanced users

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. The label for each option is specified in the order of rotations for that orientation. This option takes affect on next boot. After changing you will need to re-level your vehicle. Firmware versions 4.2 and prior can use a CUSTOM (100) rotation to set the AHRS_CUSTOM_ROLL/PIT/YAW angles for AHRS orientation. Later versions provide two general custom rotations which can be used, Custom 1 and Custom 2, with CUST_ROT1_ROLL/PIT/YAW or CUST_ROT2_ROLL/PIT/YAW angles.

Values

Value

Meaning

0

None

1

Yaw45

2

Yaw90

3

Yaw135

4

Yaw180

5

Yaw225

6

Yaw270

7

Yaw315

8

Roll180

9

Yaw45Roll180

10

Yaw90Roll180

11

Yaw135Roll180

12

Pitch180

13

Yaw225Roll180

14

Yaw270Roll180

15

Yaw315Roll180

16

Roll90

17

Yaw45Roll90

18

Yaw90Roll90

19

Yaw135Roll90

20

Roll270

21

Yaw45Roll270

22

Yaw90Roll270

23

Yaw135Roll270

24

Pitch90

25

Pitch270

26

Yaw90Pitch180

27

Yaw270Pitch180

28

Pitch90Roll90

29

Pitch90Roll180

30

Pitch90Roll270

31

Pitch180Roll90

32

Pitch180Roll270

33

Pitch270Roll90

34

Pitch270Roll180

35

Pitch270Roll270

36

Yaw90Pitch180Roll90

37

Yaw270Roll90

38

Yaw293Pitch68Roll180

39

Pitch315

40

Pitch315Roll90

42

Roll45

43

Roll315

100

Custom 4.1 and older

101

Custom 1

102

Custom 2

AHRS_COMP_BETA: AHRS Velocity Complementary Filter Beta Coefficient

Note: This parameter is for advanced users

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.

Increment

Range

.01

0.001 to 0.5

AHRS_GPS_MINSATS: AHRS GPS Minimum satellites

Note: This parameter is for advanced users

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.

Increment

Range

1

0 to 10

AHRS_EKF_TYPE: Use NavEKF Kalman filter for attitude and position estimation

Note: This parameter is for advanced users

This controls which NavEKF Kalman filter version is used for attitude and position estimation

Values

Value

Meaning

0

Disabled

2

Enable EKF2

3

Enable EKF3

11

ExternalAHRS

AHRS_CUSTOM_ROLL: Board orientation roll offset

Note: This parameter is for advanced users

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.

Increment

Range

Units

1

-180 to 180

degrees

AHRS_CUSTOM_PIT: Board orientation pitch offset

Note: This parameter is for advanced users

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.

Increment

Range

Units

1

-180 to 180

degrees

AHRS_CUSTOM_YAW: Board orientation yaw offset

Note: This parameter is for advanced users

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.

Increment

Range

Units

1

-180 to 180

degrees

AHRS_OPTIONS: Optional AHRS behaviour

Note: This parameter is for advanced users

This controls optional AHRS behaviour. Setting DisableDCMFallbackFW will change the AHRS behaviour for fixed wing aircraft in fly-forward flight to not fall back to DCM when the EKF stops navigating. Setting DisableDCMFallbackVTOL will change the AHRS behaviour for fixed wing aircraft in non fly-forward (VTOL) flight to not fall back to DCM when the EKF stops navigating. Setting DontDisableAirspeedUsingEKF disables the EKF based innovation check for airspeed consistency

Bitmask

Bit

Meaning

0

DisableDCMFallbackFW

1

DisableDCMFallbackVTOL

2

DontDisableAirspeedUsingEKF

AIS_ Parameters

AIS_TYPE: AIS receiver type

Note: Reboot required after change

AIS receiver type

Values

Value

Meaning

0

None

1

NMEA AIVDM message

AIS_LIST_MAX: AIS vessel list size

Note: This parameter is for advanced users

AIS list size of nearest vessels. Longer lists take longer to refresh with lower SRx_ADSB values.

Range

1 to 100

AIS_TIME_OUT: AIS vessel time out

Note: This parameter is for advanced users

if no updates are received in this time a vessel will be removed from the list

Range

Units

1 to 2000

seconds

AIS_LOGGING: AIS logging options

Note: This parameter is for advanced users

Bitmask of AIS logging options

Bitmask

Bit

Meaning

0

Log all AIVDM messages

1

Log only unsupported AIVDM messages

2

Log decoded messages

ARMING_ Parameters

ARMING_BBOX_SPD: Blackbox speed

Note: This parameter is for advanced users

This is a 3D GPS speed threshold above which we will force arm the vehicle to start logging. WARNING: This should only be used on a vehicle with no propellers attached to the flight controller and when the flight controller is not in control of the vehicle.

Increment

Range

Units

1

1 to 20

meters per second

ARMING_REQUIRE: Require Arming Motors

Note: This parameter is for advanced users

Arming disabled until some requirements are met. If 0, there are no requirements (arm immediately). If 1, sends the minimum throttle PWM value to the throttle channel when disarmed. If 2, send 0 PWM (no signal) to throttle channel when disarmed. On planes with ICE enabled and the throttle while disarmed option set in ICE_OPTIONS, the motor will always get THR_MIN when disarmed. Arming will occur using either rudder stick arming (if enabled) or GCS command when all mandatory and ARMING_CHECK items are satisfied. Note, when setting this parameter to 0, a reboot is required to immediately arm the plane.

Values

Value

Meaning

0

Disabled

1

minimum PWM when disarmed

2

0 PWM when disarmed

ARMING_ACCTHRESH: Accelerometer error threshold

Note: This parameter is for advanced users

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.

Range

Units

0.25 to 3.0

meters per square second

ARMING_RUDDER: Arming with Rudder enable/disable

Note: This parameter is for advanced users

Allow arm/disarm by rudder input. When enabled arming can be done with right rudder, disarming with left rudder. Rudder arming only works with throttle at zero +- deadzone (RCx_DZ). Depending on vehicle type, arming in certain modes is prevented. See the wiki for each vehicle. Caution is recommended when arming if it is allowed in an auto-throttle mode!

Values

Value

Meaning

0

Disabled

1

ArmingOnly

2

ArmOrDisarm

ARMING_MIS_ITEMS: Required mission items

Note: This parameter is for advanced users

Bitmask of mission items that are required to be planned in order to arm the aircraft

Bitmask

Bit

Meaning

0

Land

1

VTOL Land

2

DO_LAND_START

3

Takeoff

4

VTOL Takeoff

5

Rallypoint

6

RTL

ARMING_CHECK: Arm Checks to Perform (bitmask)

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.

Bitmask

Bit

Meaning

0

All

1

Barometer

2

Compass

3

GPS lock

4

INS

5

Parameters

6

RC Channels

7

Board voltage

8

Battery Level

9

Airspeed

10

Logging Available

11

Hardware safety switch

12

GPS Configuration

13

System

14

Mission

15

Rangefinder

16

Camera

17

AuxAuth

19

FFT

ARMING_OPTIONS: Arming options

Note: This parameter is for advanced users

Options that can be applied to change arming behaviour

Bitmask

Bit

Meaning

0

Disable prearm display

1

Do not send status text on state change

ARMING_MAGTHRESH: Compass magnetic field strength error threshold vs earth magnetic model

Note: This parameter is for advanced users

Compass magnetic field strength error threshold vs earth magnetic model. X and y axis are compared using this threhold, Z axis uses 2x this threshold. 0 to disable check

Range

Units

0 to 500

milligauss

ARMING_CRSDP_IGN: Disable CrashDump Arming check

Note: This parameter is for advanced users

Must have value "1" if crashdump data is present on the system, or a prearm failure will be raised. Do not set this parameter unless the risks of doing so are fully understood. The presence of a crash dump means that the firmware currently installed has suffered a critical software failure which resulted in the autopilot immediately rebooting. The crashdump file gives diagnostic information which can help in finding the issue, please contact the ArduPIlot support team. If this crashdump data is present, the vehicle is likely unsafe to fly. Check the ArduPilot documentation for more details.

Values

Value

Meaning

0

Crash Dump arming check active

1

Crash Dump arming check deactivated

ARSPD Parameters

ARSPD_ENABLE: Airspeed Enable

Enable airspeed sensor support

Values

Value

Meaning

0

Disable

1

Enable

ARSPD_TUBE_ORDER: Control pitot tube order

Note: This parameter is for advanced users

This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.

Values

Value

Meaning

0

Normal

1

Swapped

2

Auto Detect

ARSPD_PRIMARY: Primary airspeed sensor

Note: This parameter is for advanced users

This selects which airspeed sensor will be the primary if multiple sensors are found

Values

Value

Meaning

0

FirstSensor

1

2ndSensor

ARSPD_OPTIONS: Airspeed options bitmask

Note: This parameter is for advanced users

Bitmask of options to use with airspeed. 0:Disable use based on airspeed/groundspeed mismatch (see ARSPD_WIND_MAX), 1:Automatically reenable use based on airspeed/groundspeed mismatch recovery (see ARSPD_WIND_MAX) 2:Disable voltage correction, 3:Check that the airspeed is statistically consistent with the navigation EKF vehicle and wind velocity estimates using EKF3 (requires AHRS_EKF_TYPE = 3), 4:Report cal offset to GCS

Bitmask

Bit

Meaning

0

SpeedMismatchDisable

1

AllowSpeedMismatchRecovery

2

DisableVoltageCorrection

3

UseEkf3Consistency

4

ReportOffset

ARSPD_WIND_MAX: Maximum airspeed and ground speed difference

Note: This parameter is for advanced users

If the difference between airspeed and ground speed is greater than this value the sensor will be marked unhealthy. Using ARSPD_OPTION this health value can be used to disable the sensor.

Units

meters per second

ARSPD_WIND_WARN: Airspeed and GPS speed difference that gives a warning

Note: This parameter is for advanced users

If the difference between airspeed and GPS speed is greater than this value the sensor will issue a warning. If 0 ARSPD_WIND_MAX is used.

Units

meters per second

ARSPD_WIND_GATE: Re-enable Consistency Check Gate Size

Note: This parameter is for advanced users

Number of standard deviations applied to the re-enable EKF consistency check that is used when ARSPD_OPTIONS bit position 3 is set. Larger values will make the re-enabling of the airspeed sensor faster, but increase the likelihood of re-enabling a degraded sensor. The value can be tuned by using the ARSP.TR log message by setting ARSPD_WIND_GATE to a value that is higher than the value for ARSP.TR observed with a healthy airspeed sensor. Occasional transients in ARSP.TR above the value set by ARSPD_WIND_GATE can be tolerated provided they are less than 5 seconds in duration and less than 10% duty cycle.

Range

0.0 to 10.0

ARSPD_OFF_PCNT: Maximum offset cal speed error

Note: This parameter is for advanced users

The maximum percentage speed change in airspeed reports that is allowed due to offset changes between calibrations before a warning is issued. This potential speed error is in percent of AIRSPEED_MIN. 0 disables. Helps warn of calibrations without pitot being covered.

Range

Units

0.0 to 10.0

percent

ARSPD2_ Parameters

ARSPD2_TYPE: Airspeed type

Type of airspeed sensor

Values

Value

Meaning

0

None

1

I2C-MS4525D0

2

Analog

3

I2C-MS5525

4

I2C-MS5525 (0x76)

5

I2C-MS5525 (0x77)

6

I2C-SDP3X

7

I2C-DLVR-5in

8

DroneCAN

9

I2C-DLVR-10in

10

I2C-DLVR-20in

11

I2C-DLVR-30in

12

I2C-DLVR-60in

13

NMEA water speed

14

MSP

15

ASP5033

16

ExternalAHRS

100

SITL

ARSPD2_USE: Airspeed use

Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).

Values

Value

Meaning

0

DoNotUse

1

Use

2

UseWhenZeroThrottle

ARSPD2_OFFSET: Airspeed offset

Note: This parameter is for advanced users

Airspeed calibration offset

Increment

0.1

ARSPD2_RATIO: Airspeed ratio

Note: This parameter is for advanced users

Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.

Increment

0.1

ARSPD2_PIN: Airspeed pin

Note: This parameter is for advanced users

The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins".

Values

Value

Meaning

-1

Disabled

2

Pixhawk/Pixracer/Navio2/Pixhawk2_PM1

5

Navigator

13

Pixhawk2_PM2/CubeOrange_PM2

14

CubeOrange

16

Durandal

100

PX4-v1

ARSPD2_AUTOCAL: Automatic airspeed ratio calibration

Note: This parameter is for advanced users

Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.

ARSPD2_TUBE_ORDR: Control pitot tube order

Note: This parameter is for advanced users

This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.

Values

Value

Meaning

0

Normal

1

Swapped

2

Auto Detect

ARSPD2_SKIP_CAL: Skip airspeed offset calibration on startup

Note: This parameter is for advanced users

This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.

Values

Value

Meaning

0

Disable

1

Enable

ARSPD2_PSI_RANGE: The PSI range of the device

Note: This parameter is for advanced users

This parameter allows you to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device

ARSPD2_BUS: Airspeed I2C bus

Note: This parameter is for advanced users
Note: Reboot required after change

Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.

Values

Value

Meaning

0

Bus0

1

Bus1

2

Bus2

ARSPD2_DEVID: Airspeed ID

Note: This parameter is for advanced users

Airspeed sensor ID, taking into account its type, bus and instance

ReadOnly

True

ARSPD_ Parameters

ARSPD_TYPE: Airspeed type

Type of airspeed sensor

Values

Value

Meaning

0

None

1

I2C-MS4525D0

2

Analog

3

I2C-MS5525

4

I2C-MS5525 (0x76)

5

I2C-MS5525 (0x77)

6

I2C-SDP3X

7

I2C-DLVR-5in

8

DroneCAN

9

I2C-DLVR-10in

10

I2C-DLVR-20in

11

I2C-DLVR-30in

12

I2C-DLVR-60in

13

NMEA water speed

14

MSP

15

ASP5033

16

ExternalAHRS

100

SITL

ARSPD_USE: Airspeed use

Enables airspeed use for automatic throttle modes and replaces control from THR_TRIM. Continues to display and log airspeed if set to 0. Uses airspeed for control if set to 1. Only uses airspeed when throttle = 0 if set to 2 (useful for gliders with airspeed sensors behind propellers).

Values

Value

Meaning

0

DoNotUse

1

Use

2

UseWhenZeroThrottle

ARSPD_OFFSET: Airspeed offset

Note: This parameter is for advanced users

Airspeed calibration offset

Increment

0.1

ARSPD_RATIO: Airspeed ratio

Note: This parameter is for advanced users

Calibrates pitot tube pressure to velocity. Increasing this value will indicate a higher airspeed at any given dynamic pressure.

Increment

0.1

ARSPD_PIN: Airspeed pin

Note: This parameter is for advanced users

The pin number that the airspeed sensor is connected to for analog sensors. Values for some autopilots are given as examples. Search wiki for "Analog pins".

Values

Value

Meaning

-1

Disabled

2

Pixhawk/Pixracer/Navio2/Pixhawk2_PM1

5

Navigator

13

Pixhawk2_PM2/CubeOrange_PM2

14

CubeOrange

16

Durandal

100

PX4-v1

ARSPD_AUTOCAL: Automatic airspeed ratio calibration

Note: This parameter is for advanced users

Enables automatic adjustment of airspeed ratio during a calibration flight based on estimation of ground speed and true airspeed. New ratio saved every 2 minutes if change is > 5%. Should not be left enabled.

ARSPD_TUBE_ORDR: Control pitot tube order

Note: This parameter is for advanced users

This parameter allows you to control whether the order in which the tubes are attached to your pitot tube matters. If you set this to 0 then the first (often the top) connector on the sensor needs to be the stagnation pressure (the pressure at the tip of the pitot tube). If set to 1 then the second (often the bottom) connector needs to be the stagnation pressure. If set to 2 (the default) then the airspeed driver will accept either order. The reason you may wish to specify the order is it will allow your airspeed sensor to detect if the aircraft is receiving excessive pressure on the static port compared to the stagnation port such as during a stall, which would otherwise be seen as a positive airspeed.

Values

Value

Meaning

0

Normal

1

Swapped

2

Auto Detect

ARSPD_SKIP_CAL: Skip airspeed offset calibration on startup

Note: This parameter is for advanced users

This parameter allows you to skip airspeed offset calibration on startup, instead using the offset from the last calibration. This may be desirable if the offset variance between flights for your sensor is low and you want to avoid having to cover the pitot tube on each boot.

Values

Value

Meaning

0

Disable

1

Enable

ARSPD_PSI_RANGE: The PSI range of the device

Note: This parameter is for advanced users

This parameter allows you to set the PSI (pounds per square inch) range for your sensor. You should not change this unless you examine the datasheet for your device

ARSPD_BUS: Airspeed I2C bus

Note: This parameter is for advanced users
Note: Reboot required after change

Bus number of the I2C bus where the airspeed sensor is connected. May not correspond to board's I2C bus number labels. Retry another bus and reboot if airspeed sensor fails to initialize.

Values

Value

Meaning

0

Bus0

1

Bus1

2

Bus2

ARSPD_DEVID: Airspeed ID

Note: This parameter is for advanced users

Airspeed sensor ID, taking into account its type, bus and instance

ReadOnly

True

AVD_ Parameters

AVD_ENABLE: Enable Avoidance using ADSB

Note: This parameter is for advanced users

Enable Avoidance using ADSB

Values

Value

Meaning

0

Disabled

1

Enabled

AVD_F_ACTION: Collision Avoidance Behavior

Note: This parameter is for advanced users

Specifies aircraft behaviour when a collision is imminent

Values

Value

Meaning

0

None

1

Report

2

Climb Or Descend

3

Move Horizontally

4

Move Perpendicularly in 3D

5

RTL

6

Hover

AVD_W_ACTION: Collision Avoidance Behavior - Warn

Note: This parameter is for advanced users

Specifies aircraft behaviour when a collision may occur

Values

Value

Meaning

0

None

1

Report

AVD_F_RCVRY: Recovery behaviour after a fail event

Note: This parameter is for advanced users

Determines what the aircraft will do after a fail event is resolved

Values

Value

Meaning

0

Remain in AVOID_ADSB

1

Resume previous flight mode

2

RTL

3

Resume if AUTO else Loiter

AVD_OBS_MAX: Maximum number of obstacles to track

Note: This parameter is for advanced users

Maximum number of obstacles to track

AVD_W_TIME: Time Horizon Warn

Note: This parameter is for advanced users

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)

Units

seconds

AVD_F_TIME: Time Horizon Fail

Note: This parameter is for advanced users

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

Units

seconds

AVD_W_DIST_XY: Distance Warn XY

Note: This parameter is for advanced users

Closest allowed projected distance before W_ACTION is undertaken

Units

meters

AVD_F_DIST_XY: Distance Fail XY

Note: This parameter is for advanced users

Closest allowed projected distance before F_ACTION is undertaken

Units

meters

AVD_W_DIST_Z: Distance Warn Z

Note: This parameter is for advanced users

Closest allowed projected distance before BEHAVIOUR_W is undertaken

Units

meters

AVD_F_DIST_Z: Distance Fail Z

Note: This parameter is for advanced users

Closest allowed projected distance before BEHAVIOUR_F is undertaken

Units

meters

AVD_F_ALT_MIN: ADS-B avoidance minimum altitude

Note: This parameter is for advanced users

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.

Units

meters

BARO Parameters

BARO1_GND_PRESS: Ground Pressure

Note: This parameter is for advanced users

calibrated ground pressure in Pascals

Increment

ReadOnly

Units

Volatile

1

True

pascal

True

BARO_GND_TEMP: ground temperature

Note: This parameter is for advanced users

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.

Increment

Units

Volatile

1

degrees Celsius

True

BARO_ALT_OFFSET: altitude offset

Note: This parameter is for advanced users

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.

Increment

Units

0.1

meters

BARO_PRIMARY: Primary barometer

Note: This parameter is for advanced users

This selects which barometer will be the primary if multiple barometers are found

Values

Value

Meaning

0

FirstBaro

1

2ndBaro

2

3rdBaro

BARO_EXT_BUS: External baro bus

Note: This parameter is for advanced users

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 BARO_PROBE_EXT parameter.

Values

Value

Meaning

-1

Disabled

0

Bus0

1

Bus1

6

Bus6

BARO2_GND_PRESS: Ground Pressure

Note: This parameter is for advanced users

calibrated ground pressure in Pascals

Increment

ReadOnly

Units

Volatile

1

True

pascal

True

BARO3_GND_PRESS: Absolute Pressure

Note: This parameter is for advanced users

calibrated ground pressure in Pascals

Increment

ReadOnly

Units

Volatile

1

True

pascal

True

BARO_FLTR_RNG: Range in which sample is accepted

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.

Increment

Range

Units

1

0 to 100

percent

BARO_PROBE_EXT: External barometers to probe

Note: This parameter is for advanced users

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 BARO_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 BARO_EXT_BUS.

Bitmask

Bit

Meaning

0

BMP085

1

BMP280

2

MS5611

3

MS5607

4

MS5637

5

FBM320

6

DPS280

7

LPS25H

8

Keller

9

MS5837

10

BMP388

11

SPL06

12

MSP

13

BMP581

BARO1_DEVID: Baro ID

Note: This parameter is for advanced users

Barometer sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO2_DEVID: Baro ID2

Note: This parameter is for advanced users

Barometer2 sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO3_DEVID: Baro ID3

Note: This parameter is for advanced users

Barometer3 sensor ID, taking into account its type, bus and instance

ReadOnly

True

BARO_FIELD_ELV: field elevation

Note: This parameter is for advanced users

User provided field elevation in meters. 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. Changes to this parameter will only be used when disarmed. A value of 0 means the EKF origin height is used for takeoff height above sea level.

Increment

Units

Volatile

0.1

meters

True

BARO_ALTERR_MAX: Altitude error maximum

Note: This parameter is for advanced users

This is the maximum acceptable altitude discrepancy between GPS altitude and barometric presssure altitude calculated against a standard atmosphere for arming checks to pass. If you are getting an arming error due to this parameter then you may have a faulty or substituted barometer. A common issue is vendors replacing a MS5611 in a "Pixhawk" with a MS5607. If you have that issue then please see BARO_OPTIONS parameter to force the MS5611 to be treated as a MS5607. This check is disabled if the value is zero.

Increment

Range

Units

1

0 to 5000

meters

BARO_OPTIONS: Barometer options

Note: This parameter is for advanced users

Barometer options

Bitmask

Bit

Meaning

0

Treat MS5611 as MS5607

BARO1_WCF_ Parameters

BARO1_WCF_ENABLE: Wind coefficient enable

Note: This parameter is for advanced users

This enables the use of wind coefficients for barometer compensation

Values

Value

Meaning

0

Disabled

1

Enabled

BARO1_WCF_FWD: Pressure error coefficient in positive X direction (forward)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO1_WCF_BCK: Pressure error coefficient in negative X direction (backwards)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO1_WCF_RGT: Pressure error coefficient in positive Y direction (right)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO1_WCF_LFT: Pressure error coefficient in negative Y direction (left)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO1_WCF_UP: Pressure error coefficient in positive Z direction (up)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO1_WCF_DN: Pressure error coefficient in negative Z direction (down)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_ Parameters

BARO2_WCF_ENABLE: Wind coefficient enable

Note: This parameter is for advanced users

This enables the use of wind coefficients for barometer compensation

Values

Value

Meaning

0

Disabled

1

Enabled

BARO2_WCF_FWD: Pressure error coefficient in positive X direction (forward)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_BCK: Pressure error coefficient in negative X direction (backwards)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_RGT: Pressure error coefficient in positive Y direction (right)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_LFT: Pressure error coefficient in negative Y direction (left)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_UP: Pressure error coefficient in positive Z direction (up)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO2_WCF_DN: Pressure error coefficient in negative Z direction (down)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_ Parameters

BARO3_WCF_ENABLE: Wind coefficient enable

Note: This parameter is for advanced users

This enables the use of wind coefficients for barometer compensation

Values

Value

Meaning

0

Disabled

1

Enabled

BARO3_WCF_FWD: Pressure error coefficient in positive X direction (forward)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_BCK: Pressure error coefficient in negative X direction (backwards)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_RGT: Pressure error coefficient in positive Y direction (right)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_LFT: Pressure error coefficient in negative Y direction (left)

Note: This parameter is for advanced users

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_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_UP: Pressure error coefficient in positive Z direction (up)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a positive wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during climbing flight (or forward flight with a high forwards lean angle), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BARO3_WCF_DN: Pressure error coefficient in negative Z direction (down)

Note: This parameter is for advanced users

This is the ratio of static pressure error to dynamic pressure generated by a negative wind relative velocity along the Z body axis. If the baro height estimate rises above truth height during descending flight (or forward flight with a high backwards lean angle, eg braking manoeuvre), then this should be a negative number. Multirotors can use this feature only if using EKF3 and if the EK3_DRAG_BCOEF_X and EK3_DRAG_BCOEF_Y parameters have been tuned.

Increment

Range

0.05

-1.0 to 1.0

BATT2_ Parameters

BATT2_MONITOR: Battery monitoring

Note: Reboot required after change

Controls enabling monitoring of the battery's voltage and current

Values

Value

Meaning

0

Disabled

3

Analog Voltage Only

4

Analog Voltage and Current

5

Solo

6

Bebop

7

SMBus-Generic

8

DroneCAN-BatteryInfo

9

ESC

10

Sum Of Selected Monitors

11

FuelFlow

12

FuelLevelPWM

13

SMBUS-SUI3

14

SMBUS-SUI6

15

NeoDesign

16

SMBus-Maxell

17

Generator-Elec

18

Generator-Fuel

19

Rotoye

20

MPPT

21

INA2XX

22

LTC2946

23

Torqeedo

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATT2_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

BATT2_WATT_MAX: Maximum allowed power (Watts)

Note: This parameter is for advanced users

If battery wattage (voltage * current) exceeds this value then the system will reduce max throttle (THR_MAX, TKOFF_THR_MAX and THR_MIN for reverse thrust) to satisfy this limit. This helps limit high current to low C rated batteries regardless of battery voltage. The max throttle will slowly grow back to THR_MAX (or TKOFF_THR_MAX ) and THR_MIN if demanding the current max and under the watt max. Use 0 to disable.

Increment

Units

1

watt

BATT2_SERIAL_NUM: Battery serial number

Note: This parameter is for advanced users

Battery serial number, automatically filled in for SMBus batteries, otherwise will be -1. With DroneCan it is the battery_id.

BATT2_LOW_TIMER: Low voltage timeout

Note: This parameter is for advanced users

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.

Increment

Range

Units

1

0 to 120

seconds

BATT2_FS_VOLTSRC: Failsafe voltage source

Note: This parameter is for advanced users

Voltage type used for detection of low voltage event

Values

Value

Meaning

0

Raw Voltage

1

Sag Compensated Voltage

BATT2_LOW_VOLT: Low battery 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.

Increment

Units

0.1

volt

BATT2_LOW_MAH: Low battery capacity

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.

Increment

Units

50

milliampere hour

BATT2_CRT_VOLT: Critical battery voltage

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.

Increment

Units

0.1

volt

BATT2_CRT_MAH: Battery critical capacity

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.

Increment

Units

50

milliampere hour

BATT2_FS_LOW_ACT: Low battery failsafe action

What action the vehicle should perform if it hits a low battery failsafe

Values

Value

Meaning

0

None

1

RTL

2

Land

3

Terminate

4

QLand

6

Loiter to QLand

BATT2_FS_CRT_ACT: Critical battery failsafe action

What action the vehicle should perform if it hits a critical battery failsafe

Values

Value

Meaning

0

None

1

RTL

2

Land

3

Terminate

4

QLand

5

Parachute

6

Loiter to QLand

BATT2_ARM_VOLT: Required arming voltage

Note: This parameter is for advanced users

Battery voltage level which is required to arm the aircraft. Set to 0 to allow arming at any voltage.

Increment

Units

0.1

volt

BATT2_ARM_MAH: Required arming remaining capacity

Note: This parameter is for advanced users

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.

Increment

Units

50

milliampere hour

BATT2_OPTIONS: Battery monitor options

Note: This parameter is for advanced users

This sets options to change the behaviour of the battery monitor

Bitmask

Bit

Meaning

0

Ignore DroneCAN SoC

1

MPPT reports input voltage and current

2

MPPT Powered off when disarmed

3

MPPT Powered on when armed

4

MPPT Powered off at boot

5

MPPT Powered on at boot

6

Send resistance compensated voltage to GCS

7

Allow DroneCAN InfoAux to be from a different CAN node

9

Sum monitor measures minimum voltage instead of average

BATT2_ESC_INDEX: ESC Telemetry Index to write to

Note: This parameter is for advanced users

ESC Telemetry Index to write voltage, current, consumption and temperature data to. Use 0 to disable.

Increment

Range

1

0 to 10

BATT2_VOLT_PIN: Battery Voltage sensing pin

Note: Reboot required after change

Sets the analog input pin that should be used for voltage monitoring.

Values

Value

Meaning

-1

Disabled

2

Pixhawk/Pixracer/Navio2/Pixhawk2_PM1

5

Navigator

13

Pixhawk2_PM2/CubeOrange_PM2

14

CubeOrange

16

Durandal

100

PX4-v1

BATT2_CURR_PIN: Battery Current sensing pin

Note: Reboot required after change

Sets the analog input pin that should be used for current monitoring.

Values

Value

Meaning

-1

Disabled

3

Pixhawk/Pixracer/Navio2/Pixhawk2_PM1

4

CubeOrange_PM2/Navigator

14

Pixhawk2_PM2

15

CubeOrange

17

Durandal

101

PX4-v1

BATT2_VOLT_MULT: Voltage Multiplier

Note: This parameter is for advanced users

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.

BATT2_AMP_PERVLT: Amps per volt

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. For Synthetic Current sensor monitors, this is the maximum, full throttle current draw.

Units

ampere per volt

BATT2_AMP_OFFSET: AMP offset

Voltage offset at zero current on current sensor for Analog Sensors. For Synthetic Current sensor, this offset is the zero throttle system current and is added to the calculated throttle base current.

Units

volt

BATT2_VLT_OFFSET: Voltage offset

Note: This parameter is for advanced users

Voltage offset on voltage pin. This allows for an offset due to a diode. This voltage is subtracted before the scaling is applied.

Units

volt

BATT2_I2C_BUS (AP_BattMonitor_SMBus): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT2_I2C_ADDR (AP_BattMonitor_SMBus): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address

Range

0 to 127

BATT2_SUM_MASK: Battery Sum mask

0: sum of remaining battery monitors, If none 0 sum of specified monitors. Current will be summed and voltages averaged.

Bitmask

Bit

Meaning

0

monitor 1

1

monitor 2

2

monitor 3

3

monitor 4

4

monitor 5

5

monitor 6

6

monitor 7

7

monitor 8

8

monitor 9

BATT2_CURR_MULT: Scales reported power monitor current

Note: This parameter is for advanced users

Multiplier applied to all current related reports to allow for adjustment if no UAVCAN param access or current splitting applications

Range

.1 to 10

BATT2_FL_VLT_MIN: Empty fuel level voltage

Note: This parameter is for advanced users

The voltage seen on the analog pin when the fuel tank is empty. Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

Units

0.01 to 10

volt

BATT2_FL_V_MULT: Fuel level voltage multiplier

Note: This parameter is for advanced users

Voltage multiplier to determine what the full tank voltage reading is. This is calculated as 1 / (Voltage_Full - Voltage_Empty) Note: For this type of battery monitor, the voltage seen by the analog pin is displayed as battery voltage on a GCS.

Range

0.01 to 10

BATT2_FL_FLTR: Fuel level filter frequency

Note: This parameter is for advanced users
Note: Reboot required after change

Filter frequency in Hertz where a low pass filter is used. This is used to filter out tank slosh from the fuel level reading. A value of -1 disables the filter and unfiltered voltage is used to determine the fuel level. The suggested values at in the range of 0.2 Hz to 0.5 Hz.

Range

Units

-1 to 1

hertz

BATT2_FL_PIN: Fuel level analog pin number

Analog input pin that fuel level sensor is connected to.Analog Airspeed or RSSI ports can be used for Analog input( some autopilots provide others also). Values for some autopilots are given as examples. Search wiki for "Analog pins".

Values

Value

Meaning

-1

Disabled

2

Pixhawk/Pixracer/Navio2/Pixhawk2_PM1

5

Navigator

13

Pixhawk2_PM2/CubeOrange_PM2

14

CubeOrange

16

Durandal

100

PX4-v1

BATT2_FL_FF: First order term

Note: This parameter is for advanced users

First order polynomial fit term

Range

-10 to 10

BATT2_FL_FS: Second order term

Note: This parameter is for advanced users

Second order polynomial fit term

Range

-10 to 10

BATT2_FL_FT: Third order term

Note: This parameter is for advanced users

Third order polynomial fit term

Range

-10 to 10

BATT2_FL_OFF: Offset term

Note: This parameter is for advanced users

Offset polynomial fit term

Range

-10 to 10

BATT2_MAX_VOLT: Maximum Battery Voltage

Note: This parameter is for advanced users

Maximum voltage of battery. Provides scaling of current versus voltage

Range

7 to 100

BATT2_I2C_BUS (AP_BattMonitor_INA2xx): Battery monitor I2C bus number

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C bus number

Range

0 to 3

BATT2_I2C_ADDR (AP_BattMonitor_INA2xx): Battery monitor I2C address

Note: This parameter is for advanced users
Note: Reboot required after change

Battery monitor I2C address. If this is zero then probe list of supported addresses

Range

0 to 127

BATT2_MAX_AMPS: Battery monitor max current

Note: This parameter is for advanced users

This controls the maximum current the INS2XX sensor will work with.

Range

Units

1 to 400

ampere

BATT2_SHUNT: Battery monitor shunt resistor

Note: This parameter is for advanced users

This sets the shunt resistor used in the device

Range

Units

0.0001 to 0.01

Ohm

BATT2_ESC_MASK: ESC mask

If 0 all connected ESCs will be used. If non-zero, only those selected in will be used.

Bitmask

Bit

Meaning

0

ESC 1

1

ESC 2

2

ESC 3

3

ESC 4

4

ESC 5

5

ESC 6

6

ESC 7

7

ESC 8

8

ESC 9

9

ESC 10

10

ESC 11

11

ESC 12

12

ESC 13

13

ESC 14

14

ESC 15

15

ESC 16

16

ESC 17

17

ESC 18

18

ESC 19

19

ESC 20

20

ESC 21

21

ESC 22

22

ESC 23

23

ESC 24

24

ESC 25

25

ESC 26

26

ESC 27

27

ESC 28

28

ESC 29

29

ESC 30

30

ESC 31

31

ESC 32

BATT3_ Parameters

BATT3_MONITOR: Battery monitoring

Note: Reboot required after change

Controls enabling monitoring of the battery's voltage and current

Values

Value

Meaning

0

Disabled

3

Analog Voltage Only

4

Analog Voltage and Current

5

Solo

6

Bebop

7

SMBus-Generic

8

DroneCAN-BatteryInfo

9

ESC

10

Sum Of Selected Monitors

11

FuelFlow

12

FuelLevelPWM

13

SMBUS-SUI3

14

SMBUS-SUI6

15

NeoDesign

16

SMBus-Maxell

17

Generator-Elec

18

Generator-Fuel

19

Rotoye

20

MPPT

21

INA2XX

22

LTC2946

23

Torqeedo

24

FuelLevelAnalog

25

Synthetic Current and Analog Voltage

26

INA239_SPI

27

EFI

28

AD7091R5

29

Scripting

30

INA3221

BATT3_CAPACITY: Battery capacity

Capacity of the battery in mAh when full

Increment

Units

50

milliampere hour

BATT3_WATT_MAX: Maximum allowed power (Watts)