Complete Parameter List

Full Parameter List of Copter latest V4.6.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.

ArduCopter 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

SYSID_MYGCS: My ground station number

Note: This parameter is for advanced users

Allows restricting radio overrides to only come from my ground station

Increment

Range

1

1 to 255

PILOT_THR_FILT: Throttle filter cutoff

Note: This parameter is for advanced users

Throttle filter cutoff (Hz) - active whenever altitude control is inactive - 0 to disable

Increment

Range

Units

.5

0 to 10

hertz

PILOT_TKOFF_ALT: Pilot takeoff altitude

Altitude that altitude control modes will climb to when a takeoff is triggered with the throttle stick.

Increment

Range

Units

10

0.0 to 1000.0

centimeters

PILOT_THR_BHV: Throttle stick behavior

Bitmask containing various throttle stick options. TX with sprung throttle can set PILOT_THR_BHV to "1" so motor feedback when landed starts from mid-stick instead of bottom of stick.

Bitmask

Bit

Meaning

0

Feedback from mid stick

1

High throttle cancels landing

2

Disarm on land detection

TELEM_DELAY: Telemetry startup delay

Note: This parameter is for advanced users

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

AccelZ

RTL_ALT: RTL Altitude

The minimum alt above home the vehicle will climb to before returning. If the vehicle is flying higher than this value it will return at its current altitude.

Increment

Range

Units

1

30 to 300000

centimeters

RTL_CONE_SLOPE: RTL cone slope

Defines a cone above home which determines maximum climb

Increment

Range

Values

.1

0.5 to 10.0

Value

Meaning

0

Disabled

1

Shallow

3

Steep

RTL_SPEED: RTL speed

Defines the speed in cm/s which the aircraft will attempt to maintain horizontally while flying home. If this is set to zero, WPNAV_SPEED will be used instead.

Increment

Range

Units

50

0 to 2000

centimeters per second

RTL_ALT_FINAL: RTL Final Altitude

This is the altitude the vehicle will move to as the final stage of Returning to Launch or after completing a mission. Set to zero to land.

Increment

Range

Units

1

0 to 1000

centimeters

RTL_CLIMB_MIN: RTL minimum climb

The vehicle will climb this many cm during the initial climb portion of the RTL

Increment

Range

Units

10

0 to 3000

centimeters

RTL_LOIT_TIME: RTL loiter time

Time (in milliseconds) to loiter above home before beginning final descent

Increment

Range

Units

1000

0 to 60000

milliseconds

RTL_ALT_TYPE: RTL mode altitude type

RTL altitude type. Set to 1 for Terrain following during RTL and then set WPNAV_RFND_USE=1 to use rangefinder or WPNAV_RFND_USE=0 to use Terrain database

Values

Value

Meaning

0

Relative to Home

1

Terrain

FS_GCS_ENABLE: Ground Station Failsafe Enable

Controls whether failsafe will be invoked (and what action to take) when connection with Ground station is lost for at least 5 seconds. See FS_OPTIONS param for additional actions, or for cases allowing Mission continuation, when GCS failsafe is enabled.

Values

Value

Meaning

0

Disabled/NoAction

1

RTL

2

RTL or Continue with Mission in Auto Mode (Removed in 4.0+-see FS_OPTIONS)

3

SmartRTL or RTL

4

SmartRTL or Land

5

Land

6

Auto DO_LAND_START or RTL

7

Brake or Land

GPS_HDOP_GOOD: GPS Hdop Good

Note: This parameter is for advanced users

GPS Hdop value at or below this value represent a good position. Used for pre-arm checks

Range

100 to 900

SUPER_SIMPLE: Super Simple Mode

Bitmask to enable Super Simple mode for some flight modes. Setting this to Disabled(0) will disable Super Simple Mode. The bitmask is for flight mode switch positions

Bitmask

Bit

Meaning

0

SwitchPos1

1

SwitchPos2

2

SwitchPos3

3

SwitchPos4

4

SwitchPos5

5

SwitchPos6

WP_YAW_BEHAVIOR: Yaw behaviour during missions

Determines how the autopilot controls the yaw during missions and RTL

Values

Value

Meaning

0

Never change yaw

1

Face next waypoint

2

Face next waypoint except RTL

3

Face along GPS course

LAND_SPEED: Land speed

The descent speed for the final stage of landing in cm/s

Increment

Range

Units

10

30 to 200

centimeters per second

LAND_SPEED_HIGH: Land speed high

The descent speed for the first stage of landing in cm/s. If this is zero then WPNAV_SPEED_DN is used

Increment

Range

Units

10

0 to 500

centimeters per second

PILOT_SPEED_UP: Pilot maximum vertical speed ascending

The maximum vertical ascending velocity the pilot may request in cm/s

Increment

Range

Units

10

50 to 500

centimeters per second

PILOT_ACCEL_Z: Pilot vertical acceleration

The vertical acceleration used when pilot is controlling the altitude

Increment

Range

Units

10

50 to 500

centimeters per square second

FS_THR_ENABLE: Throttle Failsafe Enable

The throttle failsafe allows you to configure a software failsafe activated by a setting on the throttle input channel

Values

Value

Meaning

0

Disabled

1

Enabled always RTL

2

Enabled Continue with Mission in Auto Mode (Removed in 4.0+)

3

Enabled always Land

4

Enabled always SmartRTL or RTL

5

Enabled always SmartRTL or Land

6

Enabled Auto DO_LAND_START or RTL

7

Enabled always Brake or Land

FS_THR_VALUE: Throttle Failsafe Value

The PWM level in microseconds on channel 3 below which throttle failsafe triggers

Increment

Range

Units

1

910 to 1100

PWM in microseconds

THR_DZ: Throttle deadzone

The deadzone above and below mid throttle in PWM microseconds. Used in AltHold, Loiter, PosHold flight modes

Increment

Range

Units

1

0 to 300

PWM in microseconds

FLTMODE1: Flight Mode 1

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is <= 1230

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE2: Flight Mode 2

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1230, <= 1360

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE3: Flight Mode 3

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1360, <= 1490

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE4: Flight Mode 4

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1490, <= 1620

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE5: Flight Mode 5

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >1620, <= 1749

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE6: Flight Mode 6

Flight mode when pwm of Flightmode channel(FLTMODE_CH) is >=1750

Values

Value

Meaning

0

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

27

Auto RTL

28

Turtle

FLTMODE_CH: Flightmode channel

Note: This parameter is for advanced users

RC Channel to use for flight mode control

Values

Value

Meaning

0

Disabled

5

Channel5

6

Channel6

7

Channel7

8

Channel8

9

Channel9

10

Channel 10

11

Channel 11

12

Channel 12

13

Channel 13

14

Channel 14

15

Channel 15

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

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

RTL

7

Circle

9

Land

11

Drift

13

Sport

14

Flip

15

AutoTune

16

PosHold

17

Brake

18

Throw

19

Avoid_ADSB

20

Guided_NoGPS

21

Smart_RTL

22

FlowHold

23

Follow

24

ZigZag

25

SystemID

26

Heli_Autorotate

SIMPLE: Simple mode bitmask

Note: This parameter is for advanced users

Bitmask which holds which flight modes use simple heading mode (eg bit 0 = 1 means Flight Mode 0 uses simple mode). The bitmask is for flightmode switch positions.

Bitmask

Bit

Meaning

0

SwitchPos1

1

SwitchPos2

2

SwitchPos3

3

SwitchPos4

4

SwitchPos5

5

SwitchPos6

LOG_BITMASK: Log bitmask

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 basiclog types by setting this to 65535.

Bitmask

Bit

Meaning

0

Fast Attitude

1

Medium Attitude

2

GPS

3

System Performance

4

Control Tuning

5

Navigation Tuning

6

RC input

7

IMU

8

Mission Commands

9

Battery Monitor

10

RC output

11

Optical Flow

12

PID

13

Compass

15

Camera

17

Motors

18

Fast IMU

19

Raw IMU

20

Video Stabilization

21

Fast harmonic notch logging

ESC_CALIBRATION: ESC Calibration

Note: This parameter is for advanced users

Controls whether ArduCopter will enter ESC calibration on the next restart. Do not adjust this parameter manually.

Values

Value

Meaning

0

Normal Start-up

1

Start-up in ESC Calibration mode if throttle high

2

Start-up in ESC Calibration mode regardless of throttle

3

Start-up and automatically calibrate ESCs

9

Disabled

TUNE: Channel 6 Tuning

Controls which parameters (normally PID gains) are being tuned with transmitter's channel 6 knob

Values

Value

Meaning

0

None

1

Stab Roll/Pitch kP

4

Rate Roll/Pitch kP

5

Rate Roll/Pitch kI

21

Rate Roll/Pitch kD

3

Stab Yaw kP

6

Rate Yaw kP

26

Rate Yaw kD

56

Rate Yaw Filter

55

Motor Yaw Headroom

14

AltHold kP

7

Throttle Rate kP

34

Throttle Accel kP

35

Throttle Accel kI

36

Throttle Accel kD

12

Loiter Pos kP

22

Velocity XY kP

28

Velocity XY kI

10

WP Speed

25

Acro Roll/Pitch deg/s

40

Acro Yaw deg/s

45

RC Feel

13

Heli Ext Gyro

38

Declination

39

Circle Rate

46

Rate Pitch kP

47

Rate Pitch kI

48

Rate Pitch kD

49

Rate Roll kP

50

Rate Roll kI

51

Rate Roll kD

52

Rate Pitch FF

53

Rate Roll FF

54

Rate Yaw FF

58

SysID Magnitude

59

PSC Angle Max

FRAME_TYPE: Frame Type (+, X, V, etc)

Note: Reboot required after change

Controls motor mixing for multicopters. Not used for Tri or Traditional Helicopters.

Values

Value

Meaning

0

Plus

1

X

2

V

3

H

4

V-Tail

5

A-Tail

10

Y6B

11

Y6F

12

BetaFlightX

13

DJIX

14

ClockwiseX

15

I

18

BetaFlightXReversed

19

Y4

DISARM_DELAY: Disarm delay

Note: This parameter is for advanced users

Delay before automatic disarm in seconds after landing touchdown detection. A value of zero disables auto disarm. If Emergency Motor stop active, delay time is half this value.

Range

Units

0 to 127

seconds

ANGLE_MAX: Angle Max

Note: This parameter is for advanced users

Maximum lean angle in all flight modes

Increment

Range

Units

10

1000 to 8000

centidegrees

PHLD_BRAKE_RATE: PosHold braking rate

Note: This parameter is for advanced users

PosHold flight mode's rotation rate during braking in deg/sec

Range

Units

4 to 12

degrees per second

PHLD_BRAKE_ANGLE: PosHold braking angle max

Note: This parameter is for advanced users

PosHold flight mode's max lean angle during braking in centi-degrees

Increment

Range

Units

10

2000 to 4500

centidegrees

LAND_REPOSITION: Land repositioning

Note: This parameter is for advanced users

Enables user input during LAND mode, the landing phase of RTL, and auto mode landings.

Values

Value

Meaning

0

No repositioning

1

Repositioning

FS_EKF_ACTION: EKF Failsafe Action

Note: This parameter is for advanced users

Controls the action that will be taken when an EKF failsafe is invoked

Values

Value

Meaning

1

Land

2

AltHold

3

Land even in Stabilize

FS_EKF_THRESH: EKF failsafe variance threshold

Note: This parameter is for advanced users

Allows setting the maximum acceptable compass, velocity, position and height variances. Used in arming check and EKF failsafe.

Values

Value

Meaning

0.6

Strict

0.8

Default

1.0

Relaxed

FS_CRASH_CHECK: Crash check enable

Note: This parameter is for advanced users

This enables automatic crash checking. When enabled the motors will disarm if a crash is detected.

Values

Value

Meaning

0

Disabled

1

Enabled

RC_SPEED: ESC Update Speed

Note: This parameter is for advanced users

This is the speed in Hertz that your ESCs will receive updates

Increment

Range

Units

1

50 to 490

hertz

ACRO_BAL_ROLL: Acro Balance Roll

Note: This parameter is for advanced users

rate at which roll angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the roll axis. A higher value causes faster decay of desired to actual attitude.

Increment

Range

0.1

0 to 3

ACRO_BAL_PITCH: Acro Balance Pitch

Note: This parameter is for advanced users

rate at which pitch angle returns to level in acro and sport mode. A higher value causes the vehicle to return to level faster. For helicopter sets the decay rate of the virtual flybar in the pitch axis. A higher value causes faster decay of desired to actual attitude.

Increment

Range

0.1

0 to 3

ACRO_TRAINER: Acro Trainer

Note: This parameter is for advanced users

Type of trainer used in acro mode

Values

Value

Meaning

0

Disabled

1

Leveling

2

Leveling and Limited

THROW_MOT_START: Start motors before throwing is detected

Used by Throw mode. Controls whether motors will run at the speed set by MOT_SPIN_MIN or will be stopped when armed and waiting for the throw.

Values

Value

Meaning

0

Stopped

1

Running

THROW_ALT_MIN: Throw mode minimum altitude

Note: This parameter is for advanced users

Minimum altitude above which Throw mode will detect a throw or a drop - 0 to disable the check

Units

meters

THROW_ALT_MAX: Throw mode maximum altitude

Note: This parameter is for advanced users

Maximum altitude under which Throw mode will detect a throw or a drop - 0 to disable the check

Units

meters

THROW_NEXTMODE: Throw mode's follow up mode

Vehicle will switch to this mode after the throw is successfully completed. Default is to stay in throw mode (18)

Values

Value

Meaning

3

Auto

4

Guided

5

LOITER

6

RTL

9

Land

17

Brake

18

Throw

THROW_TYPE: Type of Type

Used by Throw mode. Specifies whether Copter is thrown upward or dropped.

Values

Value

Meaning

0

Upward Throw

1

Drop

GND_EFFECT_COMP: Ground Effect Compensation Enable/Disable

Note: This parameter is for advanced users

Ground Effect Compensation Enable/Disable

Values

Value

Meaning

0

Disabled

1

Enabled

DEV_OPTIONS: Development options

Note: This parameter is for advanced users

Bitmask of developer options. The meanings of the bit fields in this parameter may vary at any time. Developers should check the source code for current meaning

Bitmask

Bit

Meaning

0

ADSBMavlinkProcessing

1

DevOptionVFR_HUDRelativeAlt

ACRO_THR_MID: Acro Thr Mid

Note: This parameter is for advanced users

Acro Throttle Mid

Range

0 to 1

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

FRAME_CLASS: Frame Class

Note: Reboot required after change

Controls major frame class for multicopter component

Values

Value

Meaning

0

Undefined

1

Quad

2

Hexa

3

Octa

4

OctaQuad

5

Y6

6

Heli

7

Tri

8

SingleCopter

9

CoaxCopter

10

BiCopter

11

Heli_Dual

12

DodecaHexa

13

HeliQuad

14

Deca

15

Scripting Matrix

16

6DoF Scripting

17

Dynamic Scripting Matrix

PILOT_SPEED_DN: Pilot maximum vertical speed descending

The maximum vertical descending velocity the pilot may request in cm/s. If 0 PILOT_SPEED_UP value is used.

Increment

Range

Units

10

0 to 500

centimeters per second

LAND_ALT_LOW: Land alt low

Note: This parameter is for advanced users

Altitude during Landing at which vehicle slows to LAND_SPEED

Increment

Range

Units

10

100 to 10000

centimeters

TUNE_MIN: Tuning minimum

Minimum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to

TUNE_MAX: Tuning maximum

Maximum value that the parameter currently being tuned with the transmitter's channel 6 knob will be set to

FS_VIBE_ENABLE: Vibration Failsafe enable

This enables the vibration failsafe which will use modified altitude estimation and control during high vibrations

Values

Value

Meaning

0

Disabled

1

Enabled

FS_OPTIONS: Failsafe options bitmask

Note: This parameter is for advanced users

Bitmask of additional options for battery, radio, & GCS failsafes. 0 (default) disables all options.

Bitmask

Bit

Meaning

0

Continue if in Auto on RC failsafe

1

Continue if in Auto on GCS failsafe

2

Continue if in Guided on RC failsafe

3

Continue if landing on any failsafe

4

Continue if in pilot controlled modes on GCS failsafe

5

Release Gripper

ACRO_OPTIONS: Acro mode options

Note: This parameter is for advanced users

A range of options that can be applied to change acro mode behaviour. Air-mode enables ATC_THR_MIX_MAN at all times (air-mode has no effect on helicopters). Rate Loop Only disables the use of angle stabilization and uses angular rate stabilization only.

Bitmask

Bit

Meaning

0

Air-mode

1

Rate Loop Only

AUTO_OPTIONS: Auto mode options

Note: This parameter is for advanced users

A range of options that can be applied to change auto mode behaviour. Allow Arming allows the copter to be armed in Auto. Allow Takeoff Without Raising Throttle allows takeoff without the pilot having to raise the throttle. Ignore pilot yaw overrides the pilot's yaw stick being used while in auto.

Bitmask

Bit

Meaning

0

Allow Arming

1

Allow Takeoff Without Raising Throttle

2

Ignore pilot yaw

7

Allow weathervaning

GUID_OPTIONS: Guided mode options

Note: This parameter is for advanced users

Options that can be applied to change guided mode behaviour

Bitmask

Bit

Meaning

0

Allow Arming from Transmitter

2

Ignore pilot yaw

3

SetAttitudeTarget interprets Thrust As Thrust

4

Do not stabilize PositionXY

5

Do not stabilize VelocityXY

6

Waypoint navigation used for position targets

7

Allow weathervaning

FS_GCS_TIMEOUT: GCS failsafe timeout

Timeout before triggering the GCS failsafe

Increment

Range

Units

1

2 to 120

seconds

RTL_OPTIONS: RTL mode options

Note: This parameter is for advanced users

Options that can be applied to change RTL mode behaviour

Bitmask

Bit

Meaning

2

Ignore pilot yaw

FLIGHT_OPTIONS: Flight mode options

Note: This parameter is for advanced users

Flight mode specific options

Bitmask

Bit

Meaning

0

Disable thrust loss check

1

Disable yaw imbalance warning

2

Release gripper on thrust loss

3

Require position for arming

RNGFND_FILT: Rangefinder filter

Note: Reboot required after change

Rangefinder filter to smooth distance. Set to zero to disable filtering

Increment

Range

Units

0.05

0 to 5

hertz

GUID_TIMEOUT: Guided mode timeout

Note: This parameter is for advanced users

Guided mode timeout after which vehicle will stop or return to level if no updates are received from caller. Only applicable during any combination of velocity, acceleration, angle control, and/or angular rate control

Range

Units

0.1 to 5

seconds

SURFTRAK_MODE: Surface Tracking Mode

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

set which surface to track in surface tracking

Values

Value

Meaning

0

Do not track

1

Ground

2

Ceiling

FS_DR_ENABLE: DeadReckon Failsafe Action

Failsafe action taken immediately as deadreckoning starts. Deadreckoning starts when EKF loses position and velocity source and relies only on wind estimates

Values

Value

Meaning

0

Disabled/NoAction

1

Land

2

RTL

3

SmartRTL or RTL

4

SmartRTL or Land

6

Auto DO_LAND_START or RTL

FS_DR_TIMEOUT: DeadReckon Failsafe Timeout

DeadReckoning is available for this many seconds after losing position and/or velocity source. After this timeout elapses the EKF failsafe will trigger in modes requiring a position estimate

Range

0 to 120

ACRO_RP_RATE: Acro Roll and Pitch Rate

Acro mode maximum roll and pitch rate. Higher values mean faster rate of rotation

Range

Units

1 to 1080

degrees per second

ACRO_RP_EXPO: Acro Roll/Pitch Expo

Note: This parameter is for advanced users

Acro roll/pitch Expo to allow faster rotation when stick at edges

Range

Values

-0.5 to 0.95

Value

Meaning

0

Disabled

0.1

Very Low

0.2

Low

0.3

Medium

0.4

High

0.5

Very High

ACRO_RP_RATE_TC: Acro roll/pitch rate control input time constant

Acro roll and pitch rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response

Increment

Range

Units

Values

0.01

0 to 1

seconds

Value

Meaning

0.5

Very Soft

0.2

Soft

0.15

Medium

0.1

Crisp

0.05

Very Crisp

ACRO_Y_RATE: Acro Yaw Rate

Acro mode maximum yaw rate. Higher value means faster rate of rotation

Range

Units

1 to 360

degrees per second

ACRO_Y_EXPO: Acro Yaw Expo

Note: This parameter is for advanced users

Acro yaw expo to allow faster rotation when stick at edges

Range

Values

-1.0 to 0.95

Value

Meaning

0

Disabled

0.1

Very Low

0.2

Low

0.3

Medium

0.4

High

0.5

Very High

ACRO_Y_RATE_TC: Acro yaw rate control input time constant

Acro yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response

Increment

Range

Units

Values

0.01

0 to 1

seconds

Value

Meaning

0.5

Very Soft

0.2

Soft

0.15

Medium

0.1

Crisp

0.05

Very Crisp

PILOT_Y_RATE: Pilot controlled yaw rate

Pilot controlled yaw rate max. Used in all pilot controlled modes except Acro

Range

Units

1 to 360

degrees per second

PILOT_Y_EXPO: Pilot controlled yaw expo

Note: This parameter is for advanced users

Pilot controlled yaw expo to allow faster rotation when stick at edges

Range

Values

-0.5 to 1.0

Value

Meaning

0

Disabled

0.1

Very Low

0.2

Low

0.3

Medium

0.4

High

0.5

Very High

PILOT_Y_RATE_TC: Pilot yaw rate control input time constant

Pilot yaw rate control input time constant. Low numbers lead to sharper response, higher numbers to softer response

Increment

Range

Units

Values

0.01

0 to 1

seconds

Value

Meaning

0.5

Very Soft

0.2

Soft

0.15

Medium

0.1

Crisp

0.05

Very Crisp

TKOFF_SLEW_TIME: Slew time of throttle during take-off

Time to slew the throttle from minimum to maximum while checking for a succsessful takeoff.

Range

Units

0.25 to 5.0

seconds

TKOFF_RPM_MIN: Takeoff Check RPM minimum

Takeoff is not permitted until motors report at least this RPM. Set to zero to disable check

Range

0 to 10000

PLDP_THRESH: Payload Place thrust ratio threshold

Ratio of vertical thrust during decent below which payload touchdown will trigger.

Range

0.5 to 0.9

PLDP_RNG_MAX: Payload Place maximum range finder altitude

Maximum range finder altitude in m to trigger payload touchdown, set to zero to disable.

Range

Units

0 to 100

meters

PLDP_DELAY: Payload Place climb delay

Delay after release, in seconds, before aircraft starts to climb back to starting altitude.

Range

Units

0 to 120

seconds

PLDP_SPEED_DN: Payload Place decent speed

The maximum vertical decent velocity in m/s. If 0 LAND_SPEED value is used.

Range

Units

0 to 5

meters per second

SURFTRAK_TC: Surface Tracking Filter Time Constant

Note: This parameter is for advanced users

Time to achieve 63.2% of the surface altitude measurement change. If 0 filtering is disabled

Range

Units

0 to 5

seconds

TKOFF_THR_MAX: Takeoff maximum throttle during take-off ramp up

Note: This parameter is for advanced users

Takeoff maximum throttle allowed before controllers assume the aircraft is airborne during the takeoff process.

Range

0.0 to 0.9

TKOFF_RPM_MAX: Takeoff Check RPM maximum

Takeoff is not permitted until motors report no more than this RPM. Set to zero to disable check

Range

0 to 10000

FS_EKF_FILT: EKF Failsafe filter cutoff

Note: This parameter is for advanced users

EKF Failsafe filter cutoff frequency. EKF variances are filtered using this value to avoid spurious failsafes from transient high variances. A higher value means the failsafe is more likely to trigger.

Range

Units

0 to 10

hertz

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

Stabilize

1

Acro

2

AltHold

3

Auto

4

Guided

5

Loiter

6

Circle

7

Drift

8

Sport

9

Flip

10

AutoTune

11

PosHold

12

Brake

13

Throw

14

Avoid_ADSB

15

Guided_NoGPS

16

Smart_RTL

17

FlowHold

18

Follow

19

ZigZag

20

SystemID

21

Heli_Autorotate

22

Auto RTL

23

Turtle

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_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

10

Logging Available

11

Hardware safety switch

12

GPS Configuration

13

System

14

Mission

15

Rangefinder

16

Camera

17

AuxAuth

18

VisualOdometry

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

AROT_ Parameters

AROT_ENABLE: Enable settings for RSC Setpoint

Note: This parameter is for advanced users

Allows you to enable (1) or disable (0) the autonomous autorotation capability.

Values

Value

Meaning

0

Disabled

1

Enabled

AROT_HS_P: P gain for head speed controller

Note: This parameter is for advanced users

Increase value to increase sensitivity of head speed controller during autonomous autorotation.

Increment

Range

0.01

0.3 to 1

AROT_HS_SET_PT: Target Head Speed

Note: This parameter is for advanced users

The target head speed in RPM during autorotation. Start by setting to desired hover speed and tune from there as necessary.

Increment

Range

Units

1

1000 to 2800

Revolutions Per Minute

AROT_TARG_SP: Target Glide Ground Speed

Note: This parameter is for advanced users

Target ground speed in cm/s for the autorotation controller to try and achieve/ maintain during the glide phase.

Increment

Range

Units

50

800 to 2000

centimeters per second

AROT_COL_FILT_E: Entry Phase Collective Filter

Note: This parameter is for advanced users

Cut-off frequency for collective low pass filter. For the entry phase. Acts as a following trim. Must be higher than AROT_COL_FILT_G.

Increment

Range

Units

0.01

0.2 to 0.5

hertz

AROT_COL_FILT_G: Glide Phase Collective Filter

Note: This parameter is for advanced users

Cut-off frequency for collective low pass filter. For the glide phase. Acts as a following trim. Must be lower than AROT_COL_FILT_E.

Increment

Range

Units

0.01

0.03 to 0.15

hertz

AROT_AS_ACC_MAX: Forward Acceleration Limit

Note: This parameter is for advanced users

Maximum forward acceleration to apply in speed controller.

Increment

Range

Units

10

30 to 60

centimeters per square second

AROT_BAIL_TIME: Bail Out Timer

Note: This parameter is for advanced users

Time in seconds from bail out initiated to the exit of autorotation flight mode.

Increment

Range

Units

0.1

0.5 to 4

seconds

AROT_HS_SENSOR: Main Rotor RPM Sensor

Note: This parameter is for advanced users

Allocate the RPM sensor instance to use for measuring head speed. RPM1 = 0. RPM2 = 1.

Increment

Range

Units

0.1

0.5 to 3

seconds

AROT_FW_V_P: Velocity (horizontal) P gain

Note: This parameter is for advanced users

Velocity (horizontal) P gain. Determines the proportion of the target acceleration based on the velocity error.

Increment

Range

0.1

0.1 to 6.0

AROT_FW_V_FF: Velocity (horizontal) feed forward

Note: This parameter is for advanced users

Velocity (horizontal) input filter. Corrects the target acceleration proportionally to the desired velocity.

Increment

Range

0.01

0 to 1

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

This parameter and function is not used by this vehicle. Always set to 0.

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

This parameter and function is not used by this vehicle. Always set to 0.

Units

meters per second

ARSPD_WIND_WARN: Airspeed and GPS speed difference that gives a warning

Note: This parameter is for advanced users

This parameter and function is not used by this vehicle. Always set to 0.

Units

meters per second

ARSPD_WIND_GATE: Re-enable Consistency Check Gate Size

Note: This parameter is for advanced users

This parameter and function is not used by this vehicle.

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 ASPD_FBW_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

This parameter is not used by this vehicle. Always set to 0.

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: This parameter and function is not used by this vehicle. Always set to 0.

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

This parameter is not used by this vehicle. Always set to 0.

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: This parameter and function is not used by this vehicle. Always set to 0.

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

ATC_ Parameters

ATC_SLEW_YAW: Yaw target slew rate

Note: This parameter is for advanced users

Maximum rate the yaw target can be updated in RTL and Auto flight modes

Increment

Range

Units

100

500 to 18000

centidegrees per second

ATC_ACCEL_Y_MAX: Acceleration Max for Yaw

Note: This parameter is for advanced users

Maximum acceleration in yaw axis

Increment

Range

Units

Values

1000

0 to 72000

centidegrees per square second

Value

Meaning

0

Disabled

9000

VerySlow

18000

Slow

36000

Medium

54000

Fast

ATC_RATE_FF_ENAB: Rate Feedforward Enable

Note: This parameter is for advanced users

Controls whether body-frame rate feedforward is enabled or disabled

Values

Value

Meaning

0

Disabled

1

Enabled

ATC_ACCEL_R_MAX: Acceleration Max for Roll

Note: This parameter is for advanced users

Maximum acceleration in roll axis

Increment

Range

Units

Values

1000

0 to 180000

centidegrees per square second

Value

Meaning

0

Disabled

30000

VerySlow

72000

Slow

108000

Medium

162000

Fast

ATC_ACCEL_P_MAX: Acceleration Max for Pitch

Note: This parameter is for advanced users

Maximum acceleration in pitch axis

Increment

Range

Units

Values

1000

0 to 180000

centidegrees per square second

Value

Meaning

0

Disabled

30000

VerySlow

72000

Slow

108000

Medium

162000

Fast

ATC_ANGLE_BOOST: Angle Boost

Note: This parameter is for advanced users

Angle Boost increases output throttle as the vehicle leans to reduce loss of altitude

Values

Value

Meaning

0

Disabled

1

Enabled

ATC_ANG_RLL_P: Roll axis angle controller P gain

Roll axis angle controller P gain. Converts the error between the desired roll angle and actual angle to a desired roll rate

Range

3.000 to 12.000

ATC_ANG_PIT_P: Pitch axis angle controller P gain

Pitch axis angle controller P gain. Converts the error between the desired pitch angle and actual angle to a desired pitch rate

Range

3.000 to 12.000

ATC_ANG_YAW_P: Yaw axis angle controller P gain

Yaw axis angle controller P gain. Converts the error between the desired yaw angle and actual angle to a desired yaw rate

Range

3.000 to 12.000

ATC_ANG_LIM_TC: Angle Limit (to maintain altitude) Time Constant

Note: This parameter is for advanced users

Angle Limit (to maintain altitude) Time Constant

Range

0.5 to 10.0

ATC_RATE_R_MAX: Angular Velocity Max for Roll

Note: This parameter is for advanced users

Maximum angular velocity in roll axis

Increment

Range

Units

Values

1

0 to 1080

degrees per second

Value

Meaning

0

Disabled

60

Slow

180

Medium

360

Fast

ATC_RATE_P_MAX: Angular Velocity Max for Pitch

Note: This parameter is for advanced users

Maximum angular velocity in pitch axis

Increment

Range

Units

Values

1

0 to 1080

degrees per second

Value

Meaning

0

Disabled

60

Slow

180

Medium

360

Fast

ATC_RATE_Y_MAX: Angular Velocity Max for Yaw

Note: This parameter is for advanced users

Maximum angular velocity in yaw axis

Increment

Range

Units

Values

1

0 to 1080

degrees per second

Value

Meaning

0

Disabled

60

Slow

180

Medium

360

Fast

ATC_INPUT_TC: Attitude control input time constant

Attitude control input time constant. Low numbers lead to sharper response, higher numbers to softer response

Increment

Range

Units

Values

0.01

0 to 1

seconds

Value

Meaning

0.5

Very Soft

0.2

Soft

0.15

Medium

0.1

Crisp

0.05

Very Crisp

ATC_LAND_R_MULT: Landed roll gain multiplier

Note: This parameter is for advanced users

Roll gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the roll axis.

Range

0.25 to 1.0

ATC_LAND_P_MULT: Landed pitch gain multiplier

Note: This parameter is for advanced users

Pitch gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the pitch axis.

Range

0.25 to 1.0

ATC_LAND_Y_MULT: Landed yaw gain multiplier

Note: This parameter is for advanced users

Yaw gain multiplier active when landed. A factor of 1.0 means no reduction in gain while landed. Reduce this factor to reduce ground oscitation in the yaw axis.

Range

0.25 to 1.0

ATC_RAT_RLL_P (AC_AttitudeControl_Multi): Roll axis rate controller P gain

Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate

Increment

Range

0.005

0.01 to 0.5

ATC_RAT_RLL_I (AC_AttitudeControl_Multi): Roll axis rate controller I gain

Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate

Increment

Range

0.01

0.01 to 2.0

ATC_RAT_RLL_IMAX (AC_AttitudeControl_Multi): Roll axis rate controller I gain maximum

Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_RLL_D (AC_AttitudeControl_Multi): Roll axis rate controller D gain

Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate

Increment

Range

0.001

0.0 to 0.05

ATC_RAT_RLL_FF (AC_AttitudeControl_Multi): Roll axis rate controller feed forward

Roll axis rate controller feed forward

Increment

Range

0.001

0 to 0.5

ATC_RAT_RLL_FLTT (AC_AttitudeControl_Multi): Roll axis rate controller target frequency in Hz

Roll axis rate controller target frequency in Hz

Increment

Range

Units

1

5 to 100

hertz

ATC_RAT_RLL_FLTE (AC_AttitudeControl_Multi): Roll axis rate controller error frequency in Hz

Roll axis rate controller error frequency in Hz

Increment

Range

Units

1

0 to 100

hertz

ATC_RAT_RLL_FLTD (AC_AttitudeControl_Multi): Roll axis rate controller derivative frequency in Hz

Roll axis rate controller derivative frequency in Hz

Increment

Range

Units

1

5 to 100

hertz

ATC_RAT_RLL_SMAX (AC_AttitudeControl_Multi): Roll slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_RLL_PDMX: Roll axis rate controller PD sum maximum

Roll axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output

Increment

Range

0.01

0 to 1

ATC_RAT_RLL_D_FF (AC_AttitudeControl_Multi): Roll Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_RLL_NTF (AC_AttitudeControl_Multi): Roll Target notch filter index

Note: This parameter is for advanced users

Roll Target notch filter index

Range

1 to 8

ATC_RAT_RLL_NEF (AC_AttitudeControl_Multi): Roll Error notch filter index

Note: This parameter is for advanced users

Roll Error notch filter index

Range

1 to 8

ATC_RAT_PIT_P (AC_AttitudeControl_Multi): Pitch axis rate controller P gain

Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate output

Increment

Range

0.005

0.01 to 0.50

ATC_RAT_PIT_I (AC_AttitudeControl_Multi): Pitch axis rate controller I gain

Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate

Increment

Range

0.01

0.01 to 2.0

ATC_RAT_PIT_IMAX (AC_AttitudeControl_Multi): Pitch axis rate controller I gain maximum

Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_PIT_D (AC_AttitudeControl_Multi): Pitch axis rate controller D gain

Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate

Increment

Range

0.001

0.0 to 0.05

ATC_RAT_PIT_FF (AC_AttitudeControl_Multi): Pitch axis rate controller feed forward

Pitch axis rate controller feed forward

Increment

Range

0.001

0 to 0.5

ATC_RAT_PIT_FLTT (AC_AttitudeControl_Multi): Pitch axis rate controller target frequency in Hz

Pitch axis rate controller target frequency in Hz

Increment

Range

Units

1

5 to 100

hertz

ATC_RAT_PIT_FLTE (AC_AttitudeControl_Multi): Pitch axis rate controller error frequency in Hz

Pitch axis rate controller error frequency in Hz

Increment

Range

Units

1

0 to 100

hertz

ATC_RAT_PIT_FLTD (AC_AttitudeControl_Multi): Pitch axis rate controller derivative frequency in Hz

Pitch axis rate controller derivative frequency in Hz

Increment

Range

Units

1

5 to 100

hertz

ATC_RAT_PIT_SMAX (AC_AttitudeControl_Multi): Pitch slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_PIT_PDMX: Pitch axis rate controller PD sum maximum

Pitch axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output

Increment

Range

0.01

0 to 1

ATC_RAT_PIT_D_FF (AC_AttitudeControl_Multi): Pitch Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_PIT_NTF (AC_AttitudeControl_Multi): Pitch Target notch filter index

Note: This parameter is for advanced users

Pitch Target notch filter index

Range

1 to 8

ATC_RAT_PIT_NEF (AC_AttitudeControl_Multi): Pitch Error notch filter index

Note: This parameter is for advanced users

Pitch Error notch filter index

Range

1 to 8

ATC_RAT_YAW_P (AC_AttitudeControl_Multi): Yaw axis rate controller P gain

Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate

Increment

Range

0.005

0.10 to 2.50

ATC_RAT_YAW_I (AC_AttitudeControl_Multi): Yaw axis rate controller I gain

Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate

Increment

Range

0.01

0.010 to 1.0

ATC_RAT_YAW_IMAX (AC_AttitudeControl_Multi): Yaw axis rate controller I gain maximum

Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_YAW_D (AC_AttitudeControl_Multi): Yaw axis rate controller D gain

Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate

Increment

Range

0.001

0.000 to 0.02

ATC_RAT_YAW_FF (AC_AttitudeControl_Multi): Yaw axis rate controller feed forward

Yaw axis rate controller feed forward

Increment

Range

0.001

0 to 0.5

ATC_RAT_YAW_FLTT (AC_AttitudeControl_Multi): Yaw axis rate controller target frequency in Hz

Yaw axis rate controller target frequency in Hz

Increment

Range

Units

1

1 to 50

hertz

ATC_RAT_YAW_FLTE (AC_AttitudeControl_Multi): Yaw axis rate controller error frequency in Hz

Yaw axis rate controller error frequency in Hz

Increment

Range

Units

1

0 to 20

hertz

ATC_RAT_YAW_FLTD (AC_AttitudeControl_Multi): Yaw axis rate controller derivative frequency in Hz

Yaw axis rate controller derivative frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_YAW_SMAX (AC_AttitudeControl_Multi): Yaw slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_YAW_PDMX: Yaw axis rate controller PD sum maximum

Yaw axis rate controller PD sum maximum. The maximum/minimum value that the sum of the P and D term can output

Increment

Range

0.01

0 to 1

ATC_RAT_YAW_D_FF (AC_AttitudeControl_Multi): Yaw Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_YAW_NTF (AC_AttitudeControl_Multi): Yaw Target notch filter index

Note: This parameter is for advanced users

Yaw Target notch filter index

Range

Units

1 to 8

hertz

ATC_RAT_YAW_NEF (AC_AttitudeControl_Multi): Yaw Error notch filter index

Note: This parameter is for advanced users

Yaw Error notch filter index

Range

1 to 8

ATC_THR_MIX_MIN: Throttle Mix Minimum

Note: This parameter is for advanced users

Throttle vs attitude control prioritisation used when landing (higher values mean we prioritise attitude control over throttle)

Range

0.1 to 0.25

ATC_THR_MIX_MAX: Throttle Mix Maximum

Note: This parameter is for advanced users

Throttle vs attitude control prioritisation used during active flight (higher values mean we prioritise attitude control over throttle)

Range

0.5 to 0.9

ATC_THR_MIX_MAN: Throttle Mix Manual

Note: This parameter is for advanced users

Throttle vs attitude control prioritisation used during manual flight (higher values mean we prioritise attitude control over throttle)

Range

0.1 to 0.9

ATC_THR_G_BOOST: Throttle-gain boost

Note: This parameter is for advanced users

Throttle-gain boost ratio. A value of 0 means no boosting is applied, a value of 1 means full boosting is applied. Describes the ratio increase that is applied to angle P and PD on pitch and roll.

Range

0 to 1

ATC_HOVR_ROL_TRM: Hover Roll Trim

Note: This parameter is for advanced users

Trim the hover roll angle to counter tail rotor thrust in a hover

Increment

Range

Units

10

0 to 1000

centidegrees

ATC_RAT_RLL_P (AC_AttitudeControl_Heli): Roll axis rate controller P gain

Roll axis rate controller P gain. Corrects in proportion to the difference between the desired roll rate vs actual roll rate

Increment

Range

0.005

0.0 to 0.35

ATC_RAT_RLL_I (AC_AttitudeControl_Heli): Roll axis rate controller I gain

Roll axis rate controller I gain. Corrects long-term difference in desired roll rate vs actual roll rate

Increment

Range

0.01

0.0 to 0.6

ATC_RAT_RLL_IMAX (AC_AttitudeControl_Heli): Roll axis rate controller I gain maximum

Roll axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_RLL_ILMI: Roll axis rate controller I-term leak minimum

Note: This parameter is for advanced users

Point below which I-term will not leak down

Range

0 to 1

ATC_RAT_RLL_D (AC_AttitudeControl_Heli): Roll axis rate controller D gain

Roll axis rate controller D gain. Compensates for short-term change in desired roll rate vs actual roll rate

Increment

Range

0.001

0.0 to 0.03

ATC_RAT_RLL_FF (AC_AttitudeControl_Heli): Roll axis rate controller feed forward

Roll axis rate controller feed forward

Increment

Range

0.001

0.05 to 0.5

ATC_RAT_RLL_FLTT (AC_AttitudeControl_Heli): Roll axis rate controller target frequency in Hz

Roll axis rate controller target frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_RLL_FLTE (AC_AttitudeControl_Heli): Roll axis rate controller error frequency in Hz

Roll axis rate controller error frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_RLL_FLTD (AC_AttitudeControl_Heli): Roll axis rate controller derivative frequency in Hz

Roll axis rate controller derivative frequency in Hz

Increment

Range

Units

1

0 to 50

hertz

ATC_RAT_RLL_SMAX (AC_AttitudeControl_Heli): Roll slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_RLL_D_FF (AC_AttitudeControl_Heli): Roll Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_RLL_NTF (AC_AttitudeControl_Heli): Roll Target notch filter index

Note: This parameter is for advanced users

Roll Target notch filter index

Range

1 to 8

ATC_RAT_RLL_NEF (AC_AttitudeControl_Heli): Roll Error notch filter index

Note: This parameter is for advanced users

Roll Error notch filter index

Range

1 to 8

ATC_RAT_PIT_P (AC_AttitudeControl_Heli): Pitch axis rate controller P gain

Pitch axis rate controller P gain. Corrects in proportion to the difference between the desired pitch rate vs actual pitch rate

Increment

Range

0.005

0.0 to 0.35

ATC_RAT_PIT_I (AC_AttitudeControl_Heli): Pitch axis rate controller I gain

Pitch axis rate controller I gain. Corrects long-term difference in desired pitch rate vs actual pitch rate

Increment

Range

0.01

0.0 to 0.6

ATC_RAT_PIT_IMAX (AC_AttitudeControl_Heli): Pitch axis rate controller I gain maximum

Pitch axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_PIT_ILMI: Pitch axis rate controller I-term leak minimum

Note: This parameter is for advanced users

Point below which I-term will not leak down

Range

0 to 1

ATC_RAT_PIT_D (AC_AttitudeControl_Heli): Pitch axis rate controller D gain

Pitch axis rate controller D gain. Compensates for short-term change in desired pitch rate vs actual pitch rate

Increment

Range

0.001

0.0 to 0.03

ATC_RAT_PIT_FF (AC_AttitudeControl_Heli): Pitch axis rate controller feed forward

Pitch axis rate controller feed forward

Increment

Range

0.001

0.05 to 0.5

ATC_RAT_PIT_FLTT (AC_AttitudeControl_Heli): Pitch axis rate controller target frequency in Hz

Pitch axis rate controller target frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_PIT_FLTE (AC_AttitudeControl_Heli): Pitch axis rate controller error frequency in Hz

Pitch axis rate controller error frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_PIT_FLTD (AC_AttitudeControl_Heli): Pitch axis rate controller derivative frequency in Hz

Pitch axis rate controller derivative frequency in Hz

Increment

Range

Units

1

0 to 50

hertz

ATC_RAT_PIT_SMAX (AC_AttitudeControl_Heli): Pitch slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_PIT_D_FF (AC_AttitudeControl_Heli): Pitch Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_PIT_NTF (AC_AttitudeControl_Heli): Pitch Target notch filter index

Note: This parameter is for advanced users

Pitch Target notch filter index

Range

1 to 8

ATC_RAT_PIT_NEF (AC_AttitudeControl_Heli): Pitch Error notch filter index

Note: This parameter is for advanced users

Pitch Error notch filter index

Range

1 to 8

ATC_RAT_YAW_P (AC_AttitudeControl_Heli): Yaw axis rate controller P gain

Yaw axis rate controller P gain. Corrects in proportion to the difference between the desired yaw rate vs actual yaw rate

Increment

Range

0.005

0.180 to 0.60

ATC_RAT_YAW_I (AC_AttitudeControl_Heli): Yaw axis rate controller I gain

Yaw axis rate controller I gain. Corrects long-term difference in desired yaw rate vs actual yaw rate

Increment

Range

0.01

0.01 to 0.2

ATC_RAT_YAW_IMAX (AC_AttitudeControl_Heli): Yaw axis rate controller I gain maximum

Yaw axis rate controller I gain maximum. Constrains the maximum that the I term will output

Increment

Range

0.01

0 to 1

ATC_RAT_YAW_ILMI: Yaw axis rate controller I-term leak minimum

Note: This parameter is for advanced users

Point below which I-term will not leak down

Range

0 to 1

ATC_RAT_YAW_D (AC_AttitudeControl_Heli): Yaw axis rate controller D gain

Yaw axis rate controller D gain. Compensates for short-term change in desired yaw rate vs actual yaw rate

Increment

Range

0.001

0.000 to 0.02

ATC_RAT_YAW_FF (AC_AttitudeControl_Heli): Yaw axis rate controller feed forward

Yaw axis rate controller feed forward

Increment

Range

0.001

0 to 0.5

ATC_RAT_YAW_FLTT (AC_AttitudeControl_Heli): Yaw axis rate controller target frequency in Hz

Yaw axis rate controller target frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_YAW_FLTE (AC_AttitudeControl_Heli): Yaw axis rate controller error frequency in Hz

Yaw axis rate controller error frequency in Hz

Increment

Range

Units

1

5 to 50

hertz

ATC_RAT_YAW_FLTD (AC_AttitudeControl_Heli): Yaw axis rate controller derivative frequency in Hz

Yaw axis rate controller derivative frequency in Hz

Increment

Range

Units

1

0 to 50

hertz

ATC_RAT_YAW_SMAX (AC_AttitudeControl_Heli): Yaw slew rate limit

Note: This parameter is for advanced users

Sets an upper limit on the slew rate produced by the combined P and D gains. If the amplitude of the control action produced by the rate feedback exceeds this value, then the D+P gain is reduced to respect the limit. This limits the amplitude of high frequency oscillations caused by an excessive gain. The limit should be set to no more than 25% of the actuators maximum slew rate to allow for load effects. Note: The gain will not be reduced to less than 10% of the nominal value. A value of zero will disable this feature.

Increment

Range

0.5

0 to 200

ATC_RAT_YAW_D_FF (AC_AttitudeControl_Heli): Yaw Derivative FeedForward Gain

Note: This parameter is for advanced users

FF D Gain which produces an output that is proportional to the rate of change of the target

Increment

Range

0.0001

0 to 0.02

ATC_RAT_YAW_NTF (AC_AttitudeControl_Heli): Yaw Target notch filter index

Note: This parameter is for advanced users

Yaw Target notch filter index

Range

Units

1 to 8

hertz

ATC_RAT_YAW_NEF (AC_AttitudeControl_Heli): Yaw Error notch filter index

Note: This parameter is for advanced users

Yaw Error notch filter index

Range

1 to 8

ATC_PIRO_COMP: Piro Comp Enable

Note: This parameter is for advanced users

Pirouette compensation enabled

Values

Value

Meaning

0

Disabled

1

Enabled

AUTOTUNE_ Parameters

AUTOTUNE_AXES (AC_AutoTune_Multi): Autotune axis bitmask

1-byte bitmap of axes to autotune

Bitmask

Bit

Meaning

0

Roll

1

Pitch

2

Yaw

3

YawD

AUTOTUNE_AGGR: Autotune aggressiveness

Autotune aggressiveness. Defines the bounce back used to detect size of the D term.

Range

0.05 to 0.10

AUTOTUNE_MIN_D: AutoTune minimum D

Defines the minimum D gain

Range

0.0001 to 0.005

AUTOTUNE_AXES (AC_AutoTune_Heli): Autotune axis bitmask

1-byte bitmap of axes to autotune

Bitmask

Bit

Meaning

0

Roll

1

Pitch

2

Yaw

AUTOTUNE_SEQ: AutoTune Sequence Bitmask

2-byte bitmask to select what tuning should be performed. Max gain automatically performed if Rate D is selected. Values: 7:All,1:VFF Only,2:Rate D/Rate P Only(incl max gain),4:Angle P Only,8:Max Gain Only,16:Tune Check,3:VFF and Rate D/Rate P(incl max gain),5:VFF and Angle P,6:Rate D/Rate P(incl max gain) and angle P

Bitmask

Bit

Meaning

0

VFF

1

Rate D/Rate P(incl max gain)

2

Angle P

3

Max Gain Only

4

Tune Check

AUTOTUNE_FRQ_MIN: AutoTune minimum sweep frequency

Defines the start frequency for sweeps and dwells

Range

10 to 30

AUTOTUNE_FRQ_MAX: AutoTune maximum sweep frequency

Defines the end frequency for sweeps and dwells

Range

50 to 120

AUTOTUNE_GN_MAX: AutoTune maximum response gain

Defines the response gain (output/input) to tune

Range

1 to 2.5

AUTOTUNE_VELXY_P: AutoTune velocity xy P gain

Velocity xy P gain used to hold position during Max Gain, Rate P, and Rate D frequency sweeps

Range

0 to 1

AUTOTUNE_ACC_MAX: AutoTune maximum allowable angular acceleration

maximum angular acceleration in deg/s/s allowed during autotune maneuvers

Range

1 to 4000

AUTOTUNE_RAT_MAX: Autotune maximum allowable angular rate

maximum angular rate in deg/s allowed during autotune maneuvers

Range

0 to 500

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

AVOID_ Parameters

AVOID_ENABLE: Avoidance control enable/disable

Enabled/disable avoidance input sources

Bitmask

Bit

Meaning

0

UseFence

1

UseProximitySensor

2

UseBeaconFence

AVOID_ANGLE_MAX: Avoidance max lean angle in non-GPS flight modes

Max lean angle used to avoid obstacles while in non-GPS modes

Increment

Range

Units

10

0 to 4500

centidegrees

AVOID_DIST_MAX: Avoidance distance maximum in non-GPS flight modes

Distance from object at which obstacle avoidance will begin in non-GPS modes

Range

Units

1 to 30

meters

AVOID_MARGIN: Avoidance distance margin in GPS modes

Vehicle will attempt to stay at least this distance (in meters) from objects while in GPS modes

Range

Units

1 to 10

meters

AVOID_BEHAVE: Avoidance behaviour

Avoidance behaviour (slide or stop)

Values

Value

Meaning

0

Slide

1

Stop

AVOID_BACKUP_SPD: Avoidance maximum horizontal backup speed

Maximum speed that will be used to back away from obstacles horizontally in position control modes (m/s). Set zero to disable horizontal backup.

Range

Units

0 to 2

meters per second

AVOID_ALT_MIN: Avoidance minimum altitude

Minimum altitude above which proximity based avoidance will start working. This requires a valid downward facing rangefinder reading to work. Set zero to disable

Range

Units

0 to 6

meters

AVOID_ACCEL_MAX: Avoidance maximum acceleration

Maximum acceleration with which obstacles will be avoided with. Set zero to disable acceleration limits

Range

Units

0 to 9

meters per square second

AVOID_BACKUP_DZ: Avoidance deadzone between stopping and backing away from obstacle

Distance beyond AVOID_MARGIN parameter, after which vehicle will backaway from obstacles. Increase this parameter if you see vehicle going back and forth in front of obstacle.

Range

Units

0 to 2

meters

AVOID_BACKZ_SPD: Avoidance maximum vertical backup speed

Maximum speed that will be used to back away from obstacles vertically in height control modes (m/s). Set zero to disable vertical backup.

Range

Units

0 to 2

meters per second

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