1
0
Fork 0
mirror of https://github.com/iNavFlight/inav.git synced 2025-07-12 19:10:27 +03:00
inav/docs/Settings.md
breadoven ab3411ad4e
Merge pull request #10903 from breadoven/abo_fw_alt_cont_use_pos
Option to use position for fixed wing nav altitude control
2025-07-09 17:24:52 +01:00

138 KiB

CLI Variable Reference

Note: this document is autogenerated. Do not edit it manually.

3d_deadband_high

High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)

Default Min Max
1514 PWM_RANGE_MIN PWM_RANGE_MAX

3d_deadband_low

Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)

Default Min Max
1406 PWM_RANGE_MIN PWM_RANGE_MAX

3d_deadband_throttle

Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter.

Default Min Max
50 0 200

3d_neutral

Neutral (stop) throttle value for 3D mode

Default Min Max
1460 PWM_RANGE_MIN PWM_RANGE_MAX

acc_event_threshold_high

Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off.

Default Min Max
0 0 65535

acc_event_threshold_low

Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off.

Default Min Max
0 0 900

acc_event_threshold_neg_x

Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off.

Default Min Max
0 0 65535

acc_hardware

Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info

Default Min Max
AUTO

acc_lpf_hz

Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value.

Default Min Max
15 0 200

acc_lpf_type

Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds.

Default Min Max
BIQUAD

acc_notch_cutoff

Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz)

Default Min Max
1 1 255

acc_notch_hz

Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is center frequency (Hz)

Default Min Max
0 0 255

acc_temp_correction

Accelerometer temperature correction factor to compensate for acceleromter drift with changes in acceleromter temperature [cm/s2 per Degs C]. Internally limited to between -50 and 50. Typical setting for MPU6000 acceleromter is around 2.5. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm.

Default Min Max
0 -50 51

accgain_x

Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.

Default Min Max
4096 1 8192

accgain_y

Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.

Default Min Max
4096 1 8192

accgain_z

Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.

Default Min Max
4096 1 8192

acczero_x

Calculated value after '6 position avanced calibration'. See Wiki page.

Default Min Max
0 -32768 32767

acczero_y

Calculated value after '6 position avanced calibration'. See Wiki page.

Default Min Max
0 -32768 32767

acczero_z

Calculated value after '6 position avanced calibration'. See Wiki page.

Default Min Max
0 -32768 32767

ahrs_acc_ignore_rate

Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy

Default Min Max
15 0 30

ahrs_acc_ignore_slope

Half-width of the interval to gradually reduce accelerometer weight. Centered at imu_acc_ignore_rate (exactly 50% weight)

Default Min Max
5 0 10

ahrs_dcm_ki

Inertial Measurement Unit KI Gain for accelerometer measurements

Default Min Max
50 65535

ahrs_dcm_ki_mag

Inertial Measurement Unit KI Gain for compass measurements

Default Min Max
50 65535

ahrs_dcm_kp

Inertial Measurement Unit KP Gain for accelerometer measurements

Default Min Max
2000 65535

ahrs_dcm_kp_mag

Inertial Measurement Unit KP Gain for compass measurements

Default Min Max
2000 65535

ahrs_gps_yaw_weight

Arhs gps yaw weight when mag is avaliable, 0 means no gps yaw, 100 means equal weight as compass

Default Min Max
100 0 500

ahrs_gps_yaw_windcomp

Wind compensation in heading estimation from gps groundcourse(fixed wing only)

Default Min Max
ON OFF ON

ahrs_inertia_comp_method

Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop

Default Min Max
ADAPTIVE

airmode_throttle_threshold

Defines airmode THROTTLE activation threshold when airmode_type THROTTLE_THRESHOLD is used

Default Min Max
1150 1000 2000

airmode_type

Defines the Airmode state handling type. Default STICK_CENTER is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). THROTTLE_THRESHOLD is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above airmode_throttle_threshold and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to THROTTLE_THRESHOLD since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use STICK_CENTER_ONCE or STICK_CENTER modes.

Default Min Max
STICK_CENTER

airspeed_adc_channel

ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0

Default Min Max
target default ADC_CHN_NONE ADC_CHN_MAX

align_board_pitch

Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc

Default Min Max
0 -1800 3600

align_board_roll

Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc

Default Min Max
0 -1800 3600

align_board_yaw

Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc

Default Min Max
0 -1800 3600

align_mag

When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP.

Default Min Max
DEFAULT

align_mag_pitch

Same as align_mag_roll, but for the pitch axis.

Default Min Max
0 -1800 3600

align_mag_roll

Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw.

Default Min Max
0 -1800 3600

align_mag_yaw

Same as align_mag_roll, but for the yaw axis.

Default Min Max
0 -1800 3600

align_opflow

Optical flow module alignment (default CW0_DEG_FLIP)

Default Min Max
CW0FLIP

alt_hold_deadband

Defines the deadband of throttle during alt_hold [r/c points]

Default Min Max
50 10 250

antigravity_accelerator

Multiplier for Antigravity gain. The bigger is the difference between actual and filtered throttle input, the bigger Antigravity gain

Default Min Max
1 1 20

antigravity_cutoff_lpf_hz

Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain

Default Min Max
15 1 30

antigravity_gain

Max Antigravity gain. 1 means Antigravity is disabled, 2 means Iterm is allowed to double during rapid throttle movements

Default Min Max
1 1 20

applied_defaults

Internal (configurator) hint. Should not be changed manually

Default Min Max
0 0 99

baro_cal_tolerance

Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm].

Default Min Max
150 0 1000

baro_hardware

Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info

Default Min Max
AUTO

baro_temp_correction

Baro temperature correction factor to compensate for Baro altitude drift with changes in Baro temperature [cm/Degs C]. Internally limited to between -50 and 50. Typical setting for BMP280 Baro is around 20. Setting to 51 initiates auto calibration which ends after 5 minutes or on first Arm.

Default Min Max
0 -50 51

bat_cells

Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected.

Default Min Max
0 0 12

bat_voltage_src

Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are RAW and SAG_COMP

Default Min Max
RAW

battery_capacity

Set the battery capacity in mAh or mWh (see battery_capacity_unit). Used to calculate the remaining battery capacity.

Default Min Max
0 0 4294967295

battery_capacity_critical

If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps.

Default Min Max
0 0 4294967295

battery_capacity_unit

Unit used for battery_capacity, battery_capacity_warning and battery_capacity_critical [MAH/MWH] (milliAmpere hour / milliWatt hour).

Default Min Max
MAH

battery_capacity_warning

If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink.

Default Min Max
0 0 4294967295

beeper_pwm_mode

Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode

Default Min Max
OFF OFF ON

blackbox_device

Selection of where to write blackbox data

Default Min Max
target default

blackbox_rate_denom

Blackbox logging rate denominator. See blackbox_rate_num.

Default Min Max
1 1 65535

blackbox_rate_num

Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations

Default Min Max
1 1 65535

controlrate_profile

Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile

Default Min Max
0 0 3

cruise_power

Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit

Default Min Max
0 0 4294967295

current_adc_channel

ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled

Default Min Max
target default ADC_CHN_NONE ADC_CHN_MAX

current_meter_offset

This sets the output offset voltage of the current sensor in millivolts.

Default Min Max
target default -32768 32767

current_meter_scale

This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt.

Default Min Max
target default -10000 10000

current_meter_type

ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position.

Default Min Max
ADC

d_boost_gyro_delta_lpf_hz

Cutoff frequency for the low pass filter applied to the gyro delta signal used for D-term boost. Lower value will produce a smoother D-term boost signal, but it will be more delayed.

Default Min Max
80 10 250

d_boost_max

D-term multiplier when rapid external conditions are detected. Lower values give sharper response to stick input, higher values give smoother response by scaling D-gains up.

Default Min Max
1.25 1 3

d_boost_max_at_acceleration

Acceleration threshold for D-term multiplier. When acceleration is above this value, D-term multiplier is set to d_boost_max

Default Min Max
7500 1000 16000

d_boost_min

D-term multiplier when pilot provides rapid stick input. Lower values give sharper response to stick input, higher values give smoother response.

Default Min Max
0.5 0 1

deadband

These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle.

Default Min Max
2 0 32

debug_mode

Defines debug values exposed in debug variables (developer / debugging setting)

Default Min Max
NONE

disarm_always

When you switch to Disarm, do so regardless of throttle position. If this Setting is OFF. It will only disarm only when the throttle is low. This is similar to the previous disarm_kill_switch option. Default setting is the same as the old default behaviour.

Default Min Max
ON OFF ON

OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON

Default Min Max
OFF OFF ON

dji_cn_alternating_duration

Alternating duration of craft name elements, in tenths of a second

Default Min Max
30 1 150

dji_esc_temp_source

Re-purpose the ESC temperature field for IMU/BARO temperature

Default Min Max
ESC

dji_message_speed_source

Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR

Default Min Max
3D

dji_rssi_source

Source of the DJI RSSI field: RSSI, CRSF_LQ

Default Min Max
RSSI

dji_use_adjustments

Show inflight adjustments in craft name field

Default Min Max
OFF OFF ON

dji_use_name_for_messages

Re-purpose the craft name field for messages.

Default Min Max
ON OFF ON

dshot_beeper_enabled

Whether using DShot motors as beepers is enabled

Default Min Max
ON OFF ON

dshot_beeper_tone

Sets the DShot beeper tone

Default Min Max
1 1 5

dterm_lpf_hz

Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value

Default Min Max
110 0 500

dterm_lpf_type

Defines the type of stage 1 D-term LPF filter. Possible values: PT1, BIQUAD, PT2, PT3.

Default Min Max
PT2

dynamic_gyro_notch_3d_q

Q factor for 3D dynamic notches

Default Min Max
200 1 1000

dynamic_gyro_notch_enabled

Enable/disable dynamic gyro notch also known as Matrix Filter

Default Min Max
ON OFF ON

dynamic_gyro_notch_min_hz

Minimum frequency for dynamic notches. Default value of 150 works best with 5" multirotors. Should be lowered with increased size of propellers. Values around 100 work fine on 7" drones. 10" can go down to 60 - 70

Default Min Max
50 30 250

dynamic_gyro_notch_mode

Gyro dynamic notch type

Default Min Max
2D

dynamic_gyro_notch_q

Q factor for dynamic notches

Default Min Max
120 1 1000

enable_broken_o4_workaround

DJI O4 release firmware has a broken MSP DisplayPort implementation. This enables a workaround to restore ARM detection.

Default Min Max
OFF OFF ON

esc_sensor_listen_only

Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case

Default Min Max
OFF OFF ON

ez_aggressiveness

EzTune aggressiveness

Default Min Max
100 0 200

ez_axis_ratio

EzTune axis ratio

Default Min Max
110 25 175

ez_damping

EzTune damping

Default Min Max
100 0 200

ez_enabled

Enables EzTune feature

Default Min Max
OFF OFF ON

ez_expo

EzTune expo

Default Min Max
100 0 200

ez_filter_hz

EzTune filter cutoff frequency

Default Min Max
110 20 300

ez_rate

EzTune rate

Default Min Max
100 0 200

ez_response

EzTune response

Default Min Max
100 0 200

ez_snappiness

EzTune snappiness

Default Min Max
0 0 100

ez_stability

EzTune stability

Default Min Max
100 0 200

failsafe_delay

Time in deciseconds to wait before activating failsafe when signal is lost. See Failsafe documentation.

Default Min Max
5 0 200

failsafe_fw_pitch_angle

Amount of dive/climb when LAND (or old SET-THR) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb

Default Min Max
100 -800 800

failsafe_fw_roll_angle

Amount of banking when LAND (or old SET-THR) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll

Default Min Max
-200 -800 800

failsafe_fw_yaw_rate

Requested yaw rate to execute when LAND (or old SET-THR) failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn

Default Min Max
-45 -1000 1000

failsafe_gps_fix_estimation_delay

Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation.

Default Min Max
7 -1 600

failsafe_lights

Enable or disable the lights when the FAILSAFE flight mode is enabled. The target needs to be compiled with USE_LIGHTS [ON/OFF].

Default Min Max
ON OFF ON

failsafe_lights_flash_on_time

Flash lights ON time in milliseconds when failsafe_lights is ON and FAILSAFE flight mode is enabled. [20-65535].

Default Min Max
100 20 65535

failsafe_lights_flash_period

Time in milliseconds between two flashes when failsafe_lights is ON and FAILSAFE flight mode is enabled [40-65535].

Default Min Max
1000 40 65535

failsafe_min_distance

If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken.

Default Min Max
0 0 65000

failsafe_min_distance_procedure

What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See Failsafe documentation.

Default Min Max
DROP

failsafe_mission_delay

Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end.

Default Min Max
0 -1 600

failsafe_off_delay

Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See Failsafe documentation.

Default Min Max
200 0 200

failsafe_procedure

What failsafe procedure to initiate in Stage 2. See Failsafe documentation.

Default Min Max
LAND

failsafe_recovery_delay

Time in deciseconds to wait before aborting failsafe when signal is recovered. See Failsafe documentation.

Default Min Max
5 0 200

failsafe_stick_threshold

Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe.

Default Min Max
50 0 500

failsafe_throttle

Throttle level used for landing when failsafe is enabled. See Failsafe documentation.

Default Min Max
1000 PWM_RANGE_MIN PWM_RANGE_MAX

failsafe_throttle_low_delay

If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout

Default Min Max
0 0 300

fixed_wing_auto_arm

Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured.

Default Min Max
OFF OFF ON

flaperon_throw_offset

Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (FEATURE FLAPS) when FLAPERON mode is activated.

Default Min Max
200 FLAPERON_THROW_MIN FLAPERON_THROW_MAX

fpv_mix_degrees

The tilt angle of the FPV camera in degrees, used by the FPV ANGLE MIX mode

Default Min Max
0 0 50

frsky_pitch_roll

S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data

Default Min Max
OFF OFF ON

frsky_use_legacy_gps_mode_sensor_ids

S.Port telemetry: If ON, send the legacy telemetry IDs for modes (Tmp1) and GNSS (Tmp2). These are old IDs, deprecated, and will be removed in INAV 10.0. Tools and scripts using these IDs should be updated to use the new IDs of 470 for Modes and 480 for GNSS. Default: 'OFF'

Default Min Max
OFF OFF ON

fw_autotune_max_rate_deflection

The target percentage of maximum mixer output used for determining the rates in AUTO and LIMIT.

Default Min Max
90 50 100

fw_autotune_min_stick

Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input.

Default Min Max
50 0 100

fw_autotune_rate_adjustment

AUTO and LIMIT adjust the rates to match the capabilities of the airplane, with LIMIT they are never increased above the starting rates setting. FIXED does not adjust the rates. Rates are not changed when tuning in ANGLE mode.

Default Min Max
AUTO

fw_d_level

Fixed-wing attitude stabilisation HORIZON transition point

Default Min Max
75 0 255

fw_d_pitch

Fixed wing rate stabilisation D-gain for PITCH

Default Min Max
0 0 255

fw_d_roll

Fixed wing rate stabilisation D-gain for ROLL

Default Min Max
0 0 255

fw_d_yaw

Fixed wing rate stabilisation D-gain for YAW

Default Min Max
0 0 255

fw_ff_pitch

Fixed-wing rate stabilisation FF-gain for PITCH

Default Min Max
50 0 255

fw_ff_roll

Fixed-wing rate stabilisation FF-gain for ROLL

Default Min Max
50 0 255

fw_ff_yaw

Fixed-wing rate stabilisation FF-gain for YAW

Default Min Max
60 0 255

fw_i_level

Fixed-wing attitude stabilisation low-pass filter cutoff

Default Min Max
5 0 255

fw_i_pitch

Fixed-wing rate stabilisation I-gain for PITCH

Default Min Max
7 0 255

fw_i_roll

Fixed-wing rate stabilisation I-gain for ROLL

Default Min Max
7 0 255

fw_i_yaw

Fixed-wing rate stabilisation I-gain for YAW

Default Min Max
10 0 255

fw_iterm_lock_engage_threshold

Defines error rate (in percents of max rate) when Iterm Lock is engaged when sticks are release. Iterm Lock will stay active until error drops below this number

Default Min Max
10 5 25

fw_iterm_lock_rate_threshold

Defines the steepness of the attenuation curve. Higher values result in flatter attenuation. Lower values force full attenuation with lower stick deflection

Default Min Max
40 10 100

fw_iterm_lock_time_max_ms

Defines max time in milliseconds for how long ITerm Lock will depress Iterm after sticks are release

Default Min Max
500 100 1000

fw_level_pitch_gain

I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations

Default Min Max
5 0 20

fw_level_pitch_trim

Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level

Default Min Max
0 -10 10

fw_loiter_direction

Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick.

Default Min Max
RIGHT

fw_min_throttle_down_pitch

Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)

Default Min Max
0 0 450

fw_p_level

Fixed-wing attitude stabilisation P-gain

Default Min Max
20 0 255

fw_p_pitch

Fixed-wing rate stabilisation P-gain for PITCH

Default Min Max
5 0 255

fw_p_roll

Fixed-wing rate stabilisation P-gain for ROLL

Default Min Max
5 0 255

fw_p_yaw

Fixed-wing rate stabilisation P-gain for YAW

Default Min Max
6 0 255

fw_reference_airspeed

Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present.

Default Min Max
1500 300 6000

fw_tpa_time_constant

TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. See PID Attenuation and scaling Wiki for full details.

Default Min Max
1500 0 5000

fw_turn_assist_pitch_gain

Gain required to keep constant pitch angle during coordinated turns (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of fw_reference_airspeed parameter

Default Min Max
1 0 2

fw_turn_assist_yaw_gain

Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of fw_reference_airspeed parameter

Default Min Max
1 0 2

fw_yaw_iterm_freeze_bank_angle

Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled.

Default Min Max
0 0 90

geozone_avoid_altitude_range

Altitude range in which an attempt is made to avoid a geozone upwards

Default Min Max
5000 0 1000000

geozone_detection_distance

Distance from which a geozone is detected

Default Min Max
50000 0 1000000

geozone_mr_stop_distance

Distance in which multirotors stops before the border

Default Min Max
15000 0 100000

geozone_no_way_home_action

Action if RTH with active geozones is unable to calculate a course to home

Default Min Max
RTH

geozone_safe_altitude_distance

Vertical distance that must be maintained to the upper and lower limits of the zone.

Default Min Max
1000 0 10000

geozone_safehome_as_inclusive

Treat nearest safehome as inclusive geozone

Default Min Max
OFF OFF ON

geozone_safehome_zone_action

Fence action for safehome zone

Default Min Max
NONE

gimbal_pan_channel

Gimbal pan rc channel index. 0 is no channel.

Default Min Max
0 0 32

gimbal_pan_trim

Trim gimbal pan center position.

Default Min Max
0 -500 500

gimbal_roll_channel

Gimbal roll rc channel index. 0 is no channel.

Default Min Max
0 0 32

gimbal_roll_trim

Trim gimbal roll center position.

Default Min Max
0 -500 500

gimbal_sensitivity

Gimbal sensitivity is similar to gain and will affect how quickly the gimbal will react.

Default Min Max
0 -16 15

gimbal_serial_single_uart

Gimbal serial and headtracker device share same UART. FC RX goes to headtracker device, FC TX goes to gimbal.

Default Min Max
OFF OFF ON

gimbal_tilt_channel

Gimbal tilt rc channel index. 0 is no channel.

Default Min Max
0 0 32

gimbal_tilt_trim

Trim gimbal tilt center position.

Default Min Max
0 -500 500

gps_auto_baud

Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS

Default Min Max
ON OFF ON

gps_auto_baud_max_supported

Max baudrate supported by GPS unit. This is used during autobaud. M8 supports up to 460400, M10 supports up to 921600 and 230400 is the value used before INAV 7.0

Default Min Max
230400

gps_auto_config

Enable automatic configuration of UBlox GPS receivers.

Default Min Max
ON OFF ON

gps_dyn_model

GPS navigation model: Pedestrian, Automotive, Air<1g, Air<2g, Air<4g. Default is AIR_2G. Use pedestrian/Automotive with caution, can cause flyaways with fast flying.

Default Min Max
AIR_2G

gps_min_sats

Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count.

Default Min Max
6 5 10

gps_provider

Which GPS protocol to be used.

Default Min Max
UBLOX

gps_sbas_mode

Which SBAS mode to be used

Default Min Max
NONE

gps_ublox_nav_hz

Navigation update rate for UBLOX receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer.

Default Min Max
10 5 200

gps_ublox_use_beidou

Enable use of Beidou satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps hardware support [OFF/ON].

Default Min Max
OFF OFF ON

gps_ublox_use_galileo

Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON].

Default Min Max
OFF OFF ON

gps_ublox_use_glonass

Enable use of Glonass satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps haardware support [OFF/ON].

Default Min Max
OFF OFF ON

ground_test_mode

For developer ground test use. Disables motors, sets heading status = Trusted on FW.

Default Min Max
OFF OFF ON

gyro_adaptive_filter_hpf_hz

High pass filter cutoff frequency

Default Min Max
10 1 50

gyro_adaptive_filter_integrator_threshold_high

High threshold for adaptive filter integrator

Default Min Max
4 1 10

gyro_adaptive_filter_integrator_threshold_low

Low threshold for adaptive filter integrator

Default Min Max
-2 -10 0

gyro_adaptive_filter_max_hz

Maximum frequency for adaptive filter

Default Min Max
150 0 505

gyro_adaptive_filter_min_hz

Minimum frequency for adaptive filter

Default Min Max
50 0 250

gyro_adaptive_filter_std_lpf_hz

Standard deviation low pass filter cutoff frequency

Default Min Max
2 0 10

gyro_adaptive_filter_target

Target value for adaptive filter

Default Min Max
3.5 1 6

gyro_anti_aliasing_lpf_hz

Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz

Default Min Max
250 1000

gyro_dyn_lpf_curve_expo

Expo value for the throttle-to-frequency mapping for Dynamic LPF

Default Min Max
5 1 10

gyro_dyn_lpf_max_hz

Maximum frequency of the gyro Dynamic LPF

Default Min Max
500 40 1000

gyro_dyn_lpf_min_hz

Minimum frequency of the gyro Dynamic LPF

Default Min Max
200 40 400

gyro_filter_mode

Specifies the type of the software LPF of the gyro signals.

Default Min Max
STATIC

gyro_lulu_enabled

Enable/disable gyro LULU filter

Default Min Max
OFF OFF ON

gyro_lulu_sample_count

Gyro lulu sample count, in number of samples.

Default Min Max
3 1 15

gyro_main_lpf_hz

Software based gyro main lowpass filter. Value is cutoff frequency (Hz)

Default Min Max
60 0 500

gyro_to_use

On multi-gyro targets, allows to choose which gyro to use. 0 = first gyro, 1 = second gyro

Default Min Max
0 0 2

gyro_zero_x

Calculated gyro zero calibration of axis X

Default Min Max
0 -32768 32767

gyro_zero_y

Calculated gyro zero calibration of axis Y

Default Min Max
0 -32768 32767

gyro_zero_z

Calculated gyro zero calibration of axis Z

Default Min Max
0 -32768 32767

has_flaps

Defines is UAV is capable of having flaps. If ON and AIRPLANE platform_type is used, FLAPERON flight mode will be available for the pilot

Default Min Max
OFF OFF ON

heading_hold_rate_limit

This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes.

Default Min Max
90 HEADING_HOLD_RATE_LIMIT_MIN HEADING_HOLD_RATE_LIMIT_MAX

headtracker_pan_ratio

Head pan movement vs camera movement ratio

Default Min Max
1 0 5

headtracker_roll_ratio

Head roll movement vs camera movement ratio

Default Min Max
1 0 5

headtracker_tilt_ratio

Head tilt movement vs camera movement ratio

Default Min Max
1 0 5

headtracker_type

Type of headtrackr dervice

Default Min Max
NONE

hott_alarm_sound_interval

Battery alarm delay in seconds for Hott telemetry

Default Min Max
5 0 120

i2c_speed

This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)

Default Min Max
400KHZ

ibus_telemetry_type

Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details.

Default Min Max
0 0 255

idle_power

Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit

Default Min Max
0 0 65535

inav_allow_dead_reckoning

Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation

Default Min Max
OFF OFF ON

inav_allow_gps_fix_estimation

Defines if inav will estimate GPS fix with magnetometer and barometer on GPS outages. Enables navigation and RTH without GPS fix on fixed wing. Also see failsafe_gps_fix_estimation_delay.

Default Min Max
OFF OFF ON

inav_auto_mag_decl

Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored.

Default Min Max
ON OFF ON

inav_baro_epv

Uncertainty value for barometric sensor [cm]

Default Min Max
100 0 9999

inav_default_alt_sensor

Sets the default altitude sensor to use. Settings GPS and BARO always use both sensors unless there is an altitude error between the sensors that exceeds a set limit. In this case only the selected sensor will be used while the altitude error limit is exceeded. GPS error limit = 2 * inav_max_eph_epv. BARO error limit = 4 * inav_baro_epv. Settings GPS_ONLY and BARO_ONLY will use only the selected sensor even if the other sensor is working. The other sensor will only be used as a backup if the selected sensor is no longer available to use.

Default Min Max
GPS

inav_gravity_cal_tolerance

Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value.

Default Min Max
5 0 255

inav_max_eph_epv

Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]

Default Min Max
1000 0 9999

inav_max_surface_altitude

Max allowed altitude for surface following mode. [cm]

Default Min Max
200 0 1000

inav_reset_altitude

Defines when relative estimated altitude is reset to zero. Variants - NEVER (once reference is acquired it's used regardless); FIRST_ARM (keep altitude at zero until firstly armed), EACH_ARM (altitude is reset to zero on each arming)

Default Min Max
FIRST_ARM

inav_reset_home

Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM

Default Min Max
FIRST_ARM

inav_w_acc_bias

Weight for accelerometer drift estimation

Default Min Max
0.01 0 1

inav_w_xy_flow_p

Weight of optical flow measurements in estimated UAV position.

Default Min Max
1.0 0 100

inav_w_xy_flow_v

Weight of optical flow measurements in estimated UAV speed.

Default Min Max
2.0 0 100

inav_w_xy_gps_p

Weight of GPS coordinates in estimated UAV position and speed.

Default Min Max
1.0 0 10

inav_w_xy_gps_v

Weight of GPS velocity data in estimated UAV speed

Default Min Max
2.0 0 10

inav_w_xy_res_v

Decay coefficient for estimated velocity when GPS reference for position is lost

Default Min Max
0.5 0 10

inav_w_z_baro_p

Weight of barometer measurements in estimated altitude and climb rate. Setting is used on both airplanes and multirotors.

Default Min Max
0.35 0 10

inav_w_z_baro_v

Weight of barometer climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors.

Default Min Max
0.1 0 10

inav_w_z_gps_p

Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors.

Default Min Max
0.2 0 10

inav_w_z_gps_v

Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors.

Default Min Max
0.1 0 10

inav_w_z_res_v

Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost

Default Min Max
0.5 0 10

inav_w_z_surface_p

Weight of rangefinder measurements in estimated altitude. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled

Default Min Max
3.5 0 100

inav_w_z_surface_v

Weight of rangefinder measurements in estimated climb rate. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled

Default Min Max
6.1 0 100

init_gyro_cal

If defined to 'OFF', it will ignore the gyroscope calibration done at each startup. Instead, the gyroscope last calibration from when you calibrated will be used. It also means you don't have to keep the UAV stationary during a startup.

Default Min Max
ON OFF ON

ins_gravity_cmss

Calculated 1G of Acc axis Z to use in INS

Default Min Max
0.0 0 2000

iterm_windup

Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)

Default Min Max
50 0 90

led_pin_pwm_mode

PWM mode of LED pin.

Default Min Max
SHARED_LOW

limit_attn_filter_cutoff

Throttle attenuation PI control output filter cutoff frequency

Default Min Max
1.2 100

limit_burst_current

Burst current limit (dA): the current which is allowed during limit_burst_current_time after which limit_cont_current will be enforced, set to 0 to disable

Default Min Max
0 4000

limit_burst_current_falldown_time

Time slice at the end of the burst time during which the current limit will be ramped down from limit_burst_current back down to limit_cont_current

Default Min Max
0 3000

limit_burst_current_time

Allowed current burst time (ds) during which limit_burst_current is allowed and after which limit_cont_current will be enforced

Default Min Max
0 3000

limit_burst_power

Burst power limit (dW): the current which is allowed during limit_burst_power_time after which limit_cont_power will be enforced, set to 0 to disable

Default Min Max
0 40000

limit_burst_power_falldown_time

Time slice at the end of the burst time during which the power limit will be ramped down from limit_burst_power back down to limit_cont_power

Default Min Max
0 3000

limit_burst_power_time

Allowed power burst time (ds) during which limit_burst_power is allowed and after which limit_cont_power will be enforced

Default Min Max
0 3000

limit_cont_current

Continous current limit (dA), set to 0 to disable

Default Min Max
0 4000

limit_cont_power

Continous power limit (dW), set to 0 to disable

Default Min Max
0 40000

limit_pi_i

Throttle attenuation PI control I term

Default Min Max
100 10000

limit_pi_p

Throttle attenuation PI control P term

Default Min Max
100 10000

log_level

Defines serial debugging log level. See docs/development/serial_printf_debugging.md for usage.

Default Min Max
ERROR

log_topics

Defines serial debugging log topic. See docs/development/serial_printf_debugging.md for usage.

Default Min Max
0 0 4294967295

looptime

This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible.

Default Min Max
500 9000

ltm_update_rate

Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details.

Default Min Max
NORMAL

mag_calibration_time

Adjust how long time the Calibration of mag will last.

Default Min Max
30 20 120

mag_declination

Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix.

Default Min Max
0 -18000 18000

mag_hardware

Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info

Default Min Max
AUTO

mag_to_use

Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target

Default Min Max
0 0 1

maggain_x

Magnetometer calibration X gain. If 1024, no calibration or calibration failed

Default Min Max
1024 -32768 32767

maggain_y

Magnetometer calibration Y gain. If 1024, no calibration or calibration failed

Default Min Max
1024 -32768 32767

maggain_z

Magnetometer calibration Z gain. If 1024, no calibration or calibration failed

Default Min Max
1024 -32768 32767

magzero_x

Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed.

Default Min Max
0 -32768 32767

magzero_y

Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed.

Default Min Max
0 -32768 32767

magzero_z

Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed.

Default Min Max
0 -32768 32767

manual_pitch_rate

Servo travel multiplier for the PITCH axis in MANUAL flight mode [0-100]%

Default Min Max
100 0 100

manual_rc_expo

Exposition value used for the PITCH/ROLL axes by the MANUAL flight mode [0-100]

Default Min Max
35 0 100

manual_rc_yaw_expo

Exposition value used for the YAW axis by the MANUAL flight mode [0-100]

Default Min Max
20 0 100

manual_roll_rate

Servo travel multiplier for the ROLL axis in MANUAL flight mode [0-100]%

Default Min Max
100 0 100

manual_yaw_rate

Servo travel multiplier for the YAW axis in MANUAL flight mode [0-100]%

Default Min Max
100 0 100

Rate of the extended status message for MAVLink telemetry

Default Min Max
2 0 255

Rate of the extra1 message for MAVLink telemetry

Default Min Max
2 0 255

Rate of the extra2 message for MAVLink telemetry

Default Min Max
2 0 255

Rate of the extra3 message for MAVLink telemetry

Default Min Max
1 0 255

Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits.

Default Min Max
33 0 100

Rate of the position message for MAVLink telemetry

Default Min Max
2 0 255

Mavlink radio type. Affects how RSSI and LQ are reported on OSD.

Default Min Max
GENERIC

Rate of the RC channels message for MAVLink telemetry

Default Min Max
1 0 255

Version of MAVLink to use

Default Min Max
2 1 2

max_angle_inclination_pit

Maximum inclination in level (angle) mode (PITCH axis). 100=10°

Default Min Max
450 100 900

max_angle_inclination_rll

Maximum inclination in level (angle) mode (ROLL axis). 100=10°

Default Min Max
450 100 900

max_check

These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value.

Default Min Max
1900 PWM_RANGE_MIN PWM_RANGE_MAX

mc_cd_lpf_hz

Cutoff frequency for Control Derivative. This controls the cutoff for the LPF that is applied to the CD (Feed Forward) signal to the PID controller. Lower value will produce a smoother CD gain to the controller, but it will be more delayed. Higher values will produce CD gain that may have more noise in the signal depending on your RC link but wil be less delayed.

Default Min Max
30 0 200

mc_cd_pitch

Multicopter Control Derivative gain for PITCH (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough.

Default Min Max
60 0 255

mc_cd_roll

Multicopter Control Derivative gain for ROLL (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough.

Default Min Max
60 0 255

mc_cd_yaw

Multicopter Control Derivative gain for YAW (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough.

Default Min Max
60 0 255

mc_d_level

Multicopter attitude stabilisation HORIZON transition point

Default Min Max
75 0 255

mc_d_pitch

Multicopter rate stabilisation D-gain for PITCH

Default Min Max
23 0 255

mc_d_roll

Multicopter rate stabilisation D-gain for ROLL

Default Min Max
23 0 255

mc_d_yaw

Multicopter rate stabilisation D-gain for YAW

Default Min Max
0 0 255

mc_i_level

Multicopter attitude stabilisation low-pass filter cutoff

Default Min Max
15 0 255

mc_i_pitch

Multicopter rate stabilisation I-gain for PITCH

Default Min Max
30 0 255

mc_i_roll

Multicopter rate stabilisation I-gain for ROLL

Default Min Max
30 0 255

mc_i_yaw

Multicopter rate stabilisation I-gain for YAW

Default Min Max
45 0 255

mc_iterm_relax

Iterm relax type. When enabled, Iterm will be relaxed when stick is centered. This will help to reduce bounceback and followthrough on multirotors. It is recommended to enable this feature on all multirotors.

Default Min Max
RP

mc_iterm_relax_cutoff

Iterm relax cutoff frequency.

Default Min Max
15 1 100

mc_p_level

Multicopter attitude stabilisation P-gain

Default Min Max
20 0 255

mc_p_pitch

Multicopter rate stabilisation P-gain for PITCH

Default Min Max
40 0 255

mc_p_roll

Multicopter rate stabilisation P-gain for ROLL

Default Min Max
40 0 255

mc_p_yaw

Multicopter rate stabilisation P-gain for YAW

Default Min Max
85 0 255

min_check

These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value.

Default Min Max
1100 PWM_RANGE_MIN PWM_RANGE_MAX

min_command

This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once.

Default Min Max
1000 0 PWM_RANGE_MAX

mixer_automated_switch

If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type

Default Min Max
OFF OFF ON

mixer_pid_profile_linking

If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup.

Default Min Max
OFF OFF ON

mixer_switch_trans_timer

If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch.

Default Min Max
0 0 200

mode_range_logic_operator

Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode.

Default Min Max
OR

model_preview_type

ID of mixer preset applied in a Configurator. Do not modify manually. Used only for backup/restore reasons.

Default Min Max
-1 -1 32767

motor_direction_inverted

Use if you need to inverse yaw motor direction.

Default Min Max
OFF OFF ON

motor_poles

The number of motor poles. Required to compute motor RPM

Default Min Max
14 4 255

motor_pwm_protocol

Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED

Default Min Max
ONESHOT125

motor_pwm_rate

Output frequency (in Hz) for motor pins. Applies only to brushed motors.

Default Min Max
16000 50 32000

motorstop_on_low

If enabled, motor will stop when throttle is low on this mixer_profile

Default Min Max
ON OFF ON

msp_override_channels

Mask of RX channels that may be overridden by MSP SET_RAW_RC. Note that this requires the MSP RC Override flight mode.

Default Min Max
0 0 4294967295

name

Craft name

Default Min Max
empty MAX_NAME_LENGTH

nav_auto_disarm_delay

Delay before craft disarms when nav_disarm_on_landing is set (ms)

Default Min Max
1000 100 10000

nav_auto_speed

Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]

Default Min Max
500 10 2000

nav_cruise_yaw_rate

Max YAW rate when NAV COURSE HOLD/CRUISE mode is enabled. Set to 0 to disable on fixed wing (Note: On multirotor setting to 0 will disable Course Hold/Cruise mode completely) [dps]

Default Min Max
60 0 120

nav_disarm_on_landing

If set to ON, INAV disarms the FC after landing

Default Min Max
ON OFF ON

nav_emerg_landing_speed

Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]

Default Min Max
500 100 2000

nav_extra_arming_safety

If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used

Default Min Max
ALLOW_BYPASS

nav_fw_allow_manual_thr_increase

Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing

Default Min Max
OFF OFF ON

nav_fw_alt_control_response

Adjusts the deceleration response of fixed wing altitude control as the target altitude is approached. Decrease value to help avoid overshooting the target altitude.

Default Min Max
40 5 100

nav_fw_alt_use_position

Use position for fixed wing altitude control rather than velocity (default method).

Default Min Max
OFF OFF ON

nav_fw_auto_climb_rate

Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]

Default Min Max
500 10 2000

nav_fw_bank_angle

Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll

Default Min Max
35 5 80

nav_fw_climb_angle

Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit

Default Min Max
20 5 80

nav_fw_control_smoothness

How smoothly the autopilot controls the airplane to correct the navigation error

Default Min Max
0 0 9

nav_fw_cruise_speed

Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s

Default Min Max
0 0 65535

nav_fw_cruise_thr

Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )

Default Min Max
1400 1000 2000

nav_fw_dive_angle

Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit

Default Min Max
15 5 80

nav_fw_heading_p

P gain of Heading Hold controller (Fixedwing)

Default Min Max
60 0 255

nav_fw_land_approach_length

Length of the final approach

Default Min Max
35000 100 100000

nav_fw_land_dive_angle

Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees

Default Min Max
2 -20 20

nav_fw_land_final_approach_pitch2throttle_mod

Modifier for pitch to throttle ratio at final approach. In Percent.

Default Min Max
100 100 400

nav_fw_land_flare_alt

Initial altitude of the flare phase

Default Min Max
150 0 10000

nav_fw_land_flare_pitch

Pitch value for flare phase. In degrees

Default Min Max
8 -15 45

nav_fw_land_glide_alt

Initial altitude of the glide phase

Default Min Max
200 100 5000

nav_fw_land_glide_pitch

Pitch value for glide phase. In degrees.

Default Min Max
0 -15 45

nav_fw_land_max_tailwind

Max. tailwind (in cm/s) if no landing direction with downwind is available

Default Min Max
140 0 3000

nav_fw_launch_accel

Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s

Default Min Max
1863 1350 20000

nav_fw_launch_climb_angle

Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit

Default Min Max
18 5 45

nav_fw_launch_detect_time

Time for which thresholds have to breached to consider launch happened [ms]

Default Min Max
40 10 1000

nav_fw_launch_end_time

Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]

Default Min Max
3000 0 5000

nav_fw_launch_idle_motor_delay

Delay between raising throttle and motor starting at idle throttle (ms)

Default Min Max
0 0 60000

nav_fw_launch_idle_thr

Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)

Default Min Max
1000 1000 2000

nav_fw_launch_land_abort_deadband

Launch and landing abort stick deadband in [r/c points], applied after r/c deadband and expo. The Roll/Pitch stick needs to be deflected beyond this deadband to abort the launch or landing.

Default Min Max
100 2 250

nav_fw_launch_manual_throttle

Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised).

Default Min Max
OFF OFF ON

nav_fw_launch_max_altitude

Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000].

Default Min Max
0 0 60000

nav_fw_launch_max_angle

Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]

Default Min Max
45 5 180

nav_fw_launch_min_time

Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000].

Default Min Max
0 0 60000

nav_fw_launch_motor_delay

Delay between detected launch and launch sequence start and throttling up (ms)

Default Min Max
500 0 5000

nav_fw_launch_spinup_time

Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller

Default Min Max
100 0 1000

nav_fw_launch_thr

Launch throttle - throttle to be set during launch sequence (pwm units)

Default Min Max
1700 1000 2000

nav_fw_launch_timeout

Maximum time for launch sequence to continue after throwing. After this time LAUNCH mode will end and regular flight mode will take over (ms)

Default Min Max
5000 60000

nav_fw_launch_velocity

Forward velocity threshold for swing-launch detection [cm/s]

Default Min Max
300 100 10000

nav_fw_launch_wiggle_to_wake_idle

Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails.

Default Min Max
0 0 2

nav_fw_loiter_radius

PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]

Default Min Max
7500 0 30000

nav_fw_manual_climb_rate

Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]

Default Min Max
300 10 2500

nav_fw_max_thr

Maximum throttle for flying wing in GPS assisted modes

Default Min Max
1700 1000 2000

nav_fw_min_thr

Minimum throttle for flying wing in GPS assisted modes

Default Min Max
1200 1000 2000

nav_fw_pitch2thr

Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)

Default Min Max
10 0 100

nav_fw_pitch2thr_smoothing

How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh.

Default Min Max
6 0 9

nav_fw_pitch2thr_threshold

Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]

Default Min Max
50 0 900

nav_fw_pos_hdg_d

D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)

Default Min Max
0 0 255

nav_fw_pos_hdg_i

I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)

Default Min Max
2 0 255

nav_fw_pos_hdg_p

P gain of heading PID controller. (Fixedwing, rovers, boats)

Default Min Max
30 0 255

nav_fw_pos_hdg_pidsum_limit

Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)

Default Min Max
350 PID_SUM_LIMIT_MIN PID_SUM_LIMIT_MAX

nav_fw_pos_xy_d

D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero

Default Min Max
8 0 255

nav_fw_pos_xy_i

I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero

Default Min Max
5 0 255

nav_fw_pos_xy_p

P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH

Default Min Max
75 0 255

nav_fw_pos_z_d

D gain of altitude PID controller (Fixedwing)

Default Min Max
10 0 255

nav_fw_pos_z_ff

FF gain of altitude PID controller. Not used if nav_fw_alt_use_position is set ON (Fixedwing)

Default Min Max
30 0 255

nav_fw_pos_z_i

I gain of altitude PID controller (Fixedwing)

Default Min Max
5 0 255

nav_fw_pos_z_p

P gain of altitude PID controller (Fixedwing)

Default Min Max
30 0 255

nav_fw_soaring_motor_stop

Stops motor when Soaring mode enabled.

Default Min Max
OFF OFF ON

nav_fw_soaring_pitch_deadband

Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within deadband allowing pitch to free float whilst soaring.

Default Min Max
5 0 15

nav_fw_wp_tracking_accuracy

Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Setting adjusts tracking deadband distance fom waypoint courseline [m]. Tracking isn't actively controlled within the deadband providing smoother flight adjustments but less accurate tracking. A 2m deadband should work OK in most cases. Setting to 0 disables waypoint tracking accuracy.

Default Min Max
0 0 10

nav_fw_wp_tracking_max_angle

Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved.

Default Min Max
60 30 80

nav_fw_wp_turn_smoothing

Smooths turns during WP missions by switching to a loiter turn at waypoints. When set to ON the craft will reach the waypoint during the turn. When set to ON-CUT the craft will turn inside the waypoint without actually reaching it (cuts the corner).

Default Min Max
OFF

nav_fw_yaw_deadband

Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course

Default Min Max
0 0 90

nav_land_detect_sensitivity

Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases.

Default Min Max
5 1 15

nav_land_maxalt_vspd

Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]

Default Min Max
200 100 2000

nav_land_minalt_vspd

Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]

Default Min Max
50 50 500

nav_land_slowdown_maxalt

Defines at what altitude the descent velocity should start to ramp down from nav_land_maxalt_vspd to nav_land_minalt_vspd during the RTH landing phase [cm]

Default Min Max
2000 500 4000

nav_land_slowdown_minalt

Defines at what altitude the descent velocity should start to be nav_land_minalt_vspd [cm]

Default Min Max
500 50 1000

nav_landing_bump_detection

Allows immediate landing detection based on G bump at touchdown when set to ON. Requires a barometer and GPS and currently only works for multirotors (Note: will work during Failsafe without need for a GPS).

Default Min Max
OFF OFF ON

nav_manual_speed

Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]

Default Min Max
750 10 2000

nav_max_altitude

Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled

Default Min Max
0 0 65000

nav_max_auto_speed

Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]

Default Min Max
1000 10 2000

nav_max_terrain_follow_alt

Max allowed above the ground altitude for terrain following mode [cm]

Default Min Max
100 1000

nav_mc_althold_throttle

If set to STICK the FC remembers the throttle stick position when enabling ALTHOLD and treats it as the neutral midpoint for holding altitude. If set to MID_STICK or HOVER the neutral midpoint is set to the mid stick position or the hover throttle position respectively.

Default Min Max
STICK

nav_mc_auto_climb_rate

Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]

Default Min Max
500 10 2000

nav_mc_bank_angle

Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude

Default Min Max
35 15 45

nav_mc_braking_bank_angle

max angle that MR is allowed to bank in BOOST mode

Default Min Max
40 15 60

nav_mc_braking_boost_disengage_speed

BOOST will be disabled when speed goes below this value

Default Min Max
100 0 1000

nav_mc_braking_boost_factor

acceleration factor for BOOST phase

Default Min Max
100 0 200

nav_mc_braking_boost_speed_threshold

BOOST can be enabled when speed is above this value

Default Min Max
150 100 1000

nav_mc_braking_boost_timeout

how long in ms BOOST phase can happen

Default Min Max
750 0 5000

nav_mc_braking_disengage_speed

braking is disabled when speed goes below this value

Default Min Max
75 0 1000

nav_mc_braking_speed_threshold

min speed in cm/s above which braking can happen

Default Min Max
100 0 1000

nav_mc_braking_timeout

timeout in ms for braking

Default Min Max
2000 100 5000

nav_mc_heading_p

P gain of Heading Hold controller (Multirotor)

Default Min Max
60 0 255

nav_mc_hover_thr

Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering.

Default Min Max
1300 1000 2000

nav_mc_inverted_crash_detection

Setting a value > 0 enables inverted crash detection for multirotors. It will auto disarm in situations where the multirotor has crashed inverted on the ground and can't be manually disarmed due to loss of control or for some other reason. When enabled this setting defines the additional number of seconds before disarm beyond a minimum fixed time delay of 3s. Requires a barometer to work.

Default Min Max
0 0 15

nav_mc_manual_climb_rate

Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]

Default Min Max
200 10 2000

nav_mc_pos_deceleration_time

Used for stoping distance calculation. Stop position is computed as speed * nav_mc_pos_deceleration_time from the place where sticks are released. Braking mode overrides this setting

Default Min Max
120 0 255

nav_mc_pos_expo

Expo for PosHold control

Default Min Max
10 0 255

nav_mc_pos_xy_p

Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity

Default Min Max
65 0 255

nav_mc_pos_z_p

P gain of altitude PID controller (Multirotor)

Default Min Max
50 0 255

nav_mc_vel_xy_d

D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target.

Default Min Max
100 0 255

nav_mc_vel_xy_dterm_attenuation

Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating.

Default Min Max
90 0 100

nav_mc_vel_xy_dterm_attenuation_end

A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum

Default Min Max
60 0 100

nav_mc_vel_xy_dterm_attenuation_start

A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins

Default Min Max
10 0 100

nav_mc_vel_xy_dterm_lpf_hz

D-term low pass filter cutoff frequency for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating.

Default Min Max
2 0 100

nav_mc_vel_xy_ff

FF gain of Position-Rate (Velocity to Acceleration)

Default Min Max
40 0 255

nav_mc_vel_xy_i

I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot

Default Min Max
15 0 255

nav_mc_vel_xy_p

P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations

Default Min Max
40 0 255

nav_mc_vel_z_d

D gain of velocity PID controller

Default Min Max
10 0 255

nav_mc_vel_z_i

I gain of velocity PID controller

Default Min Max
50 0 255

nav_mc_vel_z_p

P gain of velocity PID controller

Default Min Max
100 0 255

nav_mc_wp_slowdown

When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes.

Default Min Max
ON OFF ON

nav_min_ground_speed

Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s.

Default Min Max
7 6 50

nav_min_rth_distance

Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase.

Default Min Max
500 0 5000

nav_mission_planner_reset

With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling the mode switch ON-OFF-ON.

Default Min Max
ON OFF ON

nav_overrides_motor_stop

When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV

Default Min Max
ALL_NAV

nav_position_timeout

If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)

Default Min Max
5 0 10

nav_rth_abort_threshold

RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. Set to 0 to disable. [cm]

Default Min Max
50000 0 65000

nav_rth_allow_landing

If set to ON drone will land as a last phase of RTH.

Default Min Max
ALWAYS

nav_rth_alt_control_override

If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the RTH climb phase using full pitch or roll stick held for > 1 second. RTH altitude is reset to the current altitude using pitch down stick. RTH CLIMB FIRST is overridden using right roll stick so craft turns and heads directly to home (CLIMB FIRST override only works for fixed wing)

Default Min Max
OFF OFF ON

nav_rth_alt_mode

Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details

Default Min Max
AT_LEAST

nav_rth_altitude

Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)

Default Min Max
1000 65000

nav_rth_climb_first

If set to ON or ON_FW_SPIRAL aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF aircraft will turn and head home immediately climbing on the way. For a fixed wing ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate, turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor)

Default Min Max
ON

nav_rth_climb_first_stage_altitude

The altitude [cm] at which climb first will transition to turn first. How the altitude is used, is determined by nav_rth_climb_first_stage_mode. Default=0; feature disabled.

Default Min Max
0 65000

nav_rth_climb_first_stage_mode

This determines how rth_climb_first_stage_altitude is used. Default is AT_LEAST.

Default Min Max
AT_LEAST

nav_rth_climb_ignore_emerg

If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status.

Default Min Max
OFF OFF ON

nav_rth_fs_landing_delay

If landing is active on Failsafe and this is above 0. The aircraft will hover or loiter for X seconds before performing the landing. If the battery enters the warning or critical levels, the land will proceed. Default = 0 [seconds]

Default Min Max
0 0 1800

nav_rth_home_altitude

Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at nav_rth_altitude (default) [cm]

Default Min Max
0 65000

nav_rth_linear_descent_start_distance

The distance [m] away from home to start the linear descent. 0 = immediately (original linear descent behaviour)

Default Min Max
0 0 10000

nav_rth_tail_first

If set to ON drone will return tail-first. Obviously meaningless for airplanes.

Default Min Max
OFF OFF ON

nav_rth_trackback_distance

Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m].

Default Min Max
500 50 2000

nav_rth_trackback_mode

Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only.

Default Min Max
OFF

nav_rth_use_linear_descent

If enabled, the aircraft will gradually descent to the nav_rth_home_altitude en route. The distance from home to start the descent can be set with nav_rth_linear_descent_start_distance.

Default Min Max
OFF OFF ON

nav_use_fw_yaw_control

Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats

Default Min Max
OFF OFF ON

nav_user_control_mode

Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction.

Default Min Max
ATTI

nav_wp_enforce_altitude

Forces craft to achieve the set WP altitude as well as position before moving to next WP. Position is held and altitude adjusted as required before moving on. 0 = disabled, otherwise setting defines altitude capture tolerance [cm], e.g. 100 means required altitude is achieved when within 100cm of waypoint altitude setting.

Default Min Max
0 0 2000

nav_wp_load_on_boot

If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup.

Default Min Max
OFF OFF ON

nav_wp_max_safe_distance

First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check.

Default Min Max
100 0 1500

nav_wp_mission_restart

Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint.

Default Min Max
RESUME

nav_wp_multi_mission_index

Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions.

Default Min Max
1 1 9

nav_wp_radius

Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius

Default Min Max
100 10 10000

opflow_hardware

Selection of OPFLOW hardware.

Default Min Max
NONE

opflow_scale

Optical flow module scale factor

Default Min Max
10.5 0 10000

osd_adsb_distance_alert

Distance inside which ADSB data flashes for proximity warning

Default Min Max
3000 1 64000

osd_adsb_distance_warning

Distance in meters of ADSB aircraft that is displayed

Default Min Max
20000 1 64000

osd_adsb_ignore_plane_above_me_limit

Ignore adsb planes above, limit, 0 disabled (meters)

Default Min Max
0 0 64000

osd_ahi_bordered

Shows a border/corners around the AHI region (pixel OSD only)

Default Min Max
OFF OFF ON

osd_ahi_camera_uptilt_comp

When set to ON, the AHI position is adjusted by osd_camera_uptilt. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to OFF, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using osd_horizon_offset (osd_ahi_vertical_offset for pixel-OSD).

Default Min Max
OFF OFF ON

osd_ahi_height

AHI height in pixels (pixel OSD only)

Default Min Max
162 255

osd_ahi_max_pitch

Max pitch, in degrees, for OSD artificial horizon

Default Min Max
20 10 90

osd_ahi_pitch_interval

Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD)

Default Min Max
0 0 30

osd_ahi_reverse_roll

Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement.

Default Min Max
OFF OFF ON

osd_ahi_style

Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD.

Default Min Max
DEFAULT

osd_ahi_vertical_offset

AHI vertical offset from center (pixel OSD only)

Default Min Max
-18 -128 127

osd_ahi_width

AHI width in pixels (pixel OSD only)

Default Min Max
132 255

osd_airspeed_alarm_max

Airspeed above which the airspeed OSD element will start blinking (cm/s)

Default Min Max
0 0 27000

osd_airspeed_alarm_min

Airspeed under which the airspeed OSD element will start blinking (cm/s)

Default Min Max
0 0 27000

osd_alt_alarm

Value above which to make the OSD relative altitude indicator blink (meters)

Default Min Max
100 0 10000

osd_arm_screen_display_time

Amount of time to display the arm screen [ms]

Default Min Max
1500 1000 5000

osd_baro_temp_alarm_max

Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
600 -550 1250

osd_baro_temp_alarm_min

Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
-200 -550 1250

osd_camera_fov_h

Horizontal field of view for the camera in degres

Default Min Max
135 60 150

osd_camera_fov_v

Vertical field of view for the camera in degres

Default Min Max
85 30 120

osd_camera_uptilt

Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled).

Default Min Max
0 -40 80

osd_coordinate_digits

Number of digits for the coordinates displayed in the OSD [8-11].

Default Min Max
9 8 11

osd_crosshairs_style

To set the visual type for the crosshair

Default Min Max
DEFAULT

osd_crsf_lq_format

To select LQ format

Default Min Max
TYPE1

osd_current_alarm

Value above which the OSD current consumption element will start blinking. Measured in full Amperes.

Default Min Max
0 0 255

osd_decimals_altitude

Number of decimals for the altitude displayed in the OSD [3-5].

Default Min Max
3 3 5

osd_decimals_distance

Number of decimals for distance displayed in the OSD [3-5]. This includes distance from home, total distance, and distance remaining.

Default Min Max
3 3 5

osd_dist_alarm

Value above which to make the OSD distance from home indicator blink (meters)

Default Min Max
1000 0 50000

osd_esc_rpm_precision

Number of characters used to display the RPM value.

Default Min Max
3 3 6

osd_esc_temp_alarm_max

Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
900 -550 1500

osd_esc_temp_alarm_min

Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
-200 -550 1500

osd_estimations_wind_compensation

Use wind estimation for remaining flight time/distance estimation

Default Min Max
ON OFF ON

osd_estimations_wind_mps

Wind speed estimation in m/s

Default Min Max
OFF OFF ON

osd_failsafe_switch_layout

If enabled the OSD automatically switches to the first layout during failsafe

Default Min Max
OFF OFF ON

osd_force_grid

Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)

Default Min Max
OFF OFF ON

osd_gforce_alarm

Value above which the OSD g force indicator will blink (g)

Default Min Max
5 0 20

osd_gforce_axis_alarm_max

Value above which the OSD axis g force indicators will blink (g)

Default Min Max
5 -20 20

osd_gforce_axis_alarm_min

Value under which the OSD axis g force indicators will blink (g)

Default Min Max
-5 -20 20

osd_highlight_djis_missing_font_symbols

Show question marks where there is no symbol in the DJI font to represent the INAV OSD element's symbol. When off, blank spaces will be used. Only relevent for DJICOMPAT modes.

Default Min Max
ON OFF ON

osd_home_position_arm_screen

Should home position coordinates be displayed on the arming screen.

Default Min Max
ON OFF ON

osd_horizon_offset

To vertically adjust the whole OSD and AHI and scrolling bars

Default Min Max
0 -2 2

osd_hud_homepoint

To 3D-display the home point location in the hud

Default Min Max
OFF OFF ON

osd_hud_homing

To display little arrows around the crossair showing where the home point is in the hud

Default Min Max
OFF OFF ON

osd_hud_margin_h

Left and right margins for the hud area

Default Min Max
3 0 4

osd_hud_margin_v

Top and bottom margins for the hud area

Default Min Max
3 1 3

osd_hud_radar_alt_difference_display_time

Time in seconds to display the altitude difference in radar

Default Min Max
3 0 10

osd_hud_radar_disp

Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc

Default Min Max
0 0 4

osd_hud_radar_distance_display_time

Time in seconds to display the distance in radar

Default Min Max
3 1 10

osd_hud_radar_range_max

In meters, radar aircrafts further away than this will not be displayed in the hud

Default Min Max
4000 100 9990

osd_hud_radar_range_min

In meters, radar aircrafts closer than this will not be displayed in the hud

Default Min Max
3 1 30

osd_hud_wp_disp

How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)

Default Min Max
0 0 3

osd_imu_temp_alarm_max

Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
600 -550 1250

osd_imu_temp_alarm_min

Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)

Default Min Max
-200 -550 1250

osd_inav_to_pilot_logo_spacing

The space between the INAV and pilot logos, if osd_use_pilot_logo is ON. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen.

Default Min Max
8 0 20

osd_joystick_down

PWM value for DOWN key

Default Min Max
0 0 100

osd_joystick_enabled

Enable OSD Joystick emulation

Default Min Max
OFF OFF ON

osd_joystick_enter

PWM value for ENTER key

Default Min Max
75 0 100

osd_joystick_left

PWM value for LEFT key

Default Min Max
63 0 100

osd_joystick_right

PWM value for RIGHT key

Default Min Max
28 0 100

osd_joystick_up

PWM value for UP key

Default Min Max
48 0 100

osd_left_sidebar_scroll

Scroll type for the left sidebar

Default Min Max
NONE

osd_left_sidebar_scroll_step

How many units each sidebar step represents. 0 means the default value for the scroll type.

Default Min Max
0 255

LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%

Default Min Max
70 0 100

osd_mah_precision

Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity

Default Min Max
4 3 6

osd_main_voltage_decimals

Number of decimals for the battery voltages displayed in the OSD [1-2].

Default Min Max
1 1 2

osd_msp_displayport_fullframe_interval

Full Frame redraw interval for MSP DisplayPort [deciseconds]. This is how often a full frame update is sent to the DisplayPort, to cut down on OSD artifacting. The default value should be fine for most pilots. Though long range pilots may benefit from increasing the refresh time, especially near the edge of range. -1 = disabled (legacy mode) | 0 = every frame (not recommended) | default = 10 (1 second)

Default Min Max
10 -1 600

osd_neg_alt_alarm

Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)

Default Min Max
5 0 10000

osd_pan_servo_index

Index of the pan servo, used to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos.

Default Min Max
0 0 16

osd_pan_servo_indicator_show_degrees

Show the degress of offset from centre on the pan servo OSD display element.

Default Min Max
OFF OFF ON

osd_pan_servo_offcentre_warning

Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. 0 means the warning is disabled.

Default Min Max
10 0 45

osd_pan_servo_pwm2centideg

Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs 18 for this setting. Change sign to inverse direction.

Default Min Max
0 -36 36

osd_plus_code_digits

Numer of plus code digits before shortening with osd_plus_code_short. Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm.

Default Min Max
11 10 13

osd_plus_code_short

Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates.

Default Min Max
0

osd_radar_peers_display_time

Time in seconds to display next peer

Default Min Max
3 1 10

osd_right_sidebar_scroll

Scroll type for the right sidebar

Default Min Max
NONE

osd_right_sidebar_scroll_step

Same as left_sidebar_scroll_step, but for the right sidebar

Default Min Max
0 255

osd_row_shiftdown

Number of rows to shift the OSD display (increase if top rows are cut off)

Default Min Max
0 0 1

osd_rssi_alarm

Value below which to make the OSD RSSI indicator blink

Default Min Max
20 0 100

osd_rssi_dbm_alarm

RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm

Default Min Max
0 -130 0

osd_rssi_dbm_max

RSSI dBm upper end of curve. Perfect rssi (max) = 100%

Default Min Max
-30 -50 0

osd_rssi_dbm_min

RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%

Default Min Max
-120 -130 0

osd_sidebar_height

Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)

Default Min Max
3 0 5

osd_sidebar_horizontal_offset

Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.

Default Min Max
0 -128 127

osd_sidebar_scroll_arrows

Show arrows for scrolling the sidebars

Default Min Max
OFF OFF ON

osd_snr_alarm

Value below which Crossfire SNR Alarm pops-up. (dB)

Default Min Max
4 -20 99

osd_speed_source

Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR

Default Min Max
GROUND

osd_stats_energy_unit

Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)

Default Min Max
MAH

osd_stats_page_auto_swap_time

Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0.

Default Min Max
3 0 10

osd_stats_show_metric_efficiency

Enabling this option will show metric efficiency statistics on the post flight stats screen. In addition to the efficiency statistics in your chosen units.

Default Min Max
OFF OFF ON

osd_switch_indicator_one_channel

RC Channel to use for OSD switch indicator 1.

Default Min Max
5 5 MAX_SUPPORTED_RC_CHANNEL_COUNT

osd_switch_indicator_one_name

Character to use for OSD switch incicator 1.

Default Min Max
GEAR 5

osd_switch_indicator_three_channel

RC Channel to use for OSD switch indicator 3.

Default Min Max
5 5 MAX_SUPPORTED_RC_CHANNEL_COUNT

osd_switch_indicator_three_name

Character to use for OSD switch incicator 3.

Default Min Max
LIGT 5

osd_switch_indicator_two_channel

RC Channel to use for OSD switch indicator 2.

Default Min Max
5 5 MAX_SUPPORTED_RC_CHANNEL_COUNT

osd_switch_indicator_two_name

Character to use for OSD switch incicator 2.

Default Min Max
CAM 5

osd_switch_indicator_zero_channel

RC Channel to use for OSD switch indicator 0.

Default Min Max
5 5 MAX_SUPPORTED_RC_CHANNEL_COUNT

osd_switch_indicator_zero_name

Character to use for OSD switch incicator 0.

Default Min Max
FLAP 5

osd_switch_indicators_align_left

Align text to left of switch indicators

Default Min Max
ON OFF ON

osd_system_msg_display_time

System message display cycle time for multiple messages (milliseconds).

Default Min Max
1000 500 5000

osd_telemetry

To enable OSD telemetry for antenna tracker. Possible values are OFF, ON and TEST

Default Min Max
OFF

osd_temp_label_align

Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are LEFT and RIGHT

Default Min Max
LEFT

osd_time_alarm

Value above which to make the OSD flight time indicator blink (minutes)

Default Min Max
10 0 600

osd_units

IMPERIAL, METRIC, UK

Default Min Max
METRIC

Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511

Default Min Max
OFF OFF ON

osd_video_system

Video system used. Possible values are AUTO, PAL, NTSC, HDZERO, 'DJIWTF', 'AVATAR' and BF43COMPAT

Default Min Max
AUTO

pid_iterm_limit_percent

Limits max/min I-term value in stabilization PID controller. It solves the problem of servo saturation before take-off/throwing the airplane into the air. Or multirotors with low authority. By default, error accumulated in I-term can not exceed 33% of total pid throw (around 165us on deafult pidsum_limit of pitch/roll). Set 0 to disable completely.

Default Min Max
33 0 200

pid_type

Allows to set type of PID controller used in control loop. Possible values: NONE, PID, PIFF, AUTO. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use PIFF and multirotors PID

Default Min Max
AUTO

pilot_name

Pilot name

Default Min Max
empty MAX_NAME_LENGTH

pinio_box1

Mode assignment for PINIO#1

Default Min Max
BOX_PERMANENT_ID_NONE 0 255

pinio_box2

Mode assignment for PINIO#1

Default Min Max
BOX_PERMANENT_ID_NONE 0 255

pinio_box3

Mode assignment for PINIO#1

Default Min Max
BOX_PERMANENT_ID_NONE 0 255

pinio_box4

Mode assignment for PINIO#1

Default Min Max
BOX_PERMANENT_ID_NONE 0 255

pitch_rate

Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure.

Default Min Max
20 4 180

pitot_hardware

Selection of pitot hardware.

Default Min Max
NONE

pitot_lpf_milli_hz

Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay

Default Min Max
350 0 10000

pitot_scale

Pitot tube scale factor

Default Min Max
1.0 0 100

platform_type

Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented

Default Min Max
MULTIROTOR

pos_hold_deadband

Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes.

Default Min Max
10 2 250

prearm_timeout

Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout.

Default Min Max
10000 0 10000

rangefinder_hardware

Selection of rangefinder hardware.

Default Min Max
NONE

rangefinder_median_filter

3-point median filtering for rangefinder readouts

Default Min Max
OFF OFF ON

rate_accel_limit_roll_pitch

Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting.

Default Min Max
0 500000

rate_accel_limit_yaw

Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting.

Default Min Max
10000 500000

rate_dynamics_center_correction

The center stick correction for Rate Dynamics

Default Min Max
10 10 95

rate_dynamics_center_sensitivity

The center stick sensitivity for Rate Dynamics

Default Min Max
100 25 175

rate_dynamics_center_weight

The center stick weight for Rate Dynamics

Default Min Max
0 0 95

rate_dynamics_end_correction

The end stick correction for Rate Dynamics

Default Min Max
10 10 95

rate_dynamics_end_sensitivity

The end stick sensitivity for Rate Dynamics

Default Min Max
100 25 175

rate_dynamics_end_weight

The end stick weight for Rate Dynamics

Default Min Max
0 0 95

rc_expo

Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but MANUAL)

Default Min Max
70 0 100

rc_filter_auto

When enabled, INAV will set RC filtering based on refresh rate and smoothing factor.

Default Min Max
ON OFF ON

rc_filter_lpf_hz

RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values

Default Min Max
50 15 250

rc_filter_smoothing_factor

The RC filter smoothing factor. The higher the value, the more smoothing but also the more delay in response. Value 1 sets the filter at half the refresh rate. Value 100 sets the filter to aprox. 10% of the RC refresh rate

Default Min Max
30 1 100

rc_yaw_expo

Exposition value used for the YAW axis by all the stabilized flights modes (all but MANUAL)

Default Min Max
20 0 100

reboot_character

Special character used to trigger reboot

Default Min Max
82 48 126

receiver_type

Selection of receiver (RX) type. Additional configuration of a serialrx_provider and a UART will be needed for SERIAL

Default Min Max
target default

report_cell_voltage

S.Port and IBUS telemetry: Send the average cell voltage if set to ON

Default Min Max
OFF OFF ON

roll_rate

Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure.

Default Min Max
20 4 180

rpm_gyro_filter_enabled

Enables gyro RPM filtere. Set to ON only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV

Default Min Max
OFF OFF ON

rpm_gyro_harmonics

Number of harmonic frequences to be covered by gyro RPM filter. Default value of 1 usually works just fine

Default Min Max
1 1 3

rpm_gyro_min_hz

The lowest frequency for gyro RPM filtere. Default 150 is fine for 5" mini-quads. On 7-inch drones you can lower even down to 60-70

Default Min Max
100 30 200

rpm_gyro_q

Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting

Default Min Max
500 1 3000

rssi_adc_channel

ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled

Default Min Max
target default ADC_CHN_NONE ADC_CHN_MAX

rssi_channel

RX channel containing the RSSI signal

Default Min Max
0 0 MAX_SUPPORTED_RC_CHANNEL_COUNT

rssi_max

The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min.

Default Min Max
100 RSSI_VISIBLE_VALUE_MIN RSSI_VISIBLE_VALUE_MAX

rssi_min

The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI).

Default Min Max
0 RSSI_VISIBLE_VALUE_MIN RSSI_VISIBLE_VALUE_MAX

rssi_source

Source of RSSI input. Possible values: NONE, AUTO, ADC, CHANNEL, PROTOCOL, MSP

Default Min Max
AUTO

rth_energy_margin

Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation

Default Min Max
5 0 100

rx_max_usec

Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc.

Default Min Max
2115 PWM_PULSE_MIN PWM_PULSE_MAX

rx_min_usec

Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc.

Default Min Max
885 PWM_PULSE_MIN PWM_PULSE_MAX

safehome_max_distance

In order for a safehome to be used, it must be less than this distance (in cm) from the arming point.

Default Min Max
20000 0 65000

safehome_usage_mode

Used to control when safehomes will be used. Possible values are OFF, RTH and RTH_FS. See Safehome documentation for more information.

Default Min Max
RTH

sbus_sync_interval

SBUS sync interval in us. Default value is 3000us. Lower values may cause issues with some receivers.

Default Min Max
3000 500 10000

sdcard_detect_inverted

This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value.

Default Min Max
target default

serialrx_halfduplex

Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire.

Default Min Max
AUTO

serialrx_inverted

Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY).

Default Min Max
OFF OFF ON

serialrx_provider

When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section.

Default Min Max
target default

servo_autotrim_rotation_limit

Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using feature FW_AUTOTRIM.

Default Min Max
15 1 60

servo_center_pulse

Servo midpoint

Default Min Max
1500 PWM_RANGE_MIN PWM_RANGE_MAX

servo_lpf_hz

Selects the servo PWM output cutoff frequency. Value is in [Hz]

Default Min Max
20 0 400

servo_protocol

An option to chose the protocol/option that would be used to output servo data. Possible options PWM (FC servo outputs), SBUS (S.Bus protocol output via a configured serial port)

Default Min Max
PWM

servo_pwm_rate

Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz.

Default Min Max
50 50 498

setpoint_kalman_enabled

Enable Kalman filter on the gyro data

Default Min Max
ON OFF ON

setpoint_kalman_q

Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds

Default Min Max
100 1 1000

sim_ground_station_number

Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module.

Default Min Max
empty

sim_low_altitude

Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in sim_transmit_flags.

Default Min Max
-32767 -32768 32767

sim_pin

PIN code for the SIM module

Default Min Max
0000

sim_transmit_flags

Bitmask specifying text message transmit condition flags for the SIM module. 1: continuous transmission, 2: continuous transmission in failsafe mode, 4: continuous transmission when GPS signal quality is low, 8: acceleration events, 16: continuous transmission when altitude is below sim_low_altitude

Default Min Max
SIM_TX_FLAG_FAILSAFE 63

sim_transmit_interval

Text message transmission interval in seconds for SIM module. Minimum value: 10

Default Min Max
60 SIM_MIN_TRANSMIT_INTERVAL 65535

small_angle

If the aircraft tilt angle exceed this value the copter will refuse to arm.

Default Min Max
25 0 180

smartport_fuel_unit

S.Port telemetry only: Unit of the value sent with the FUEL ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]

Default Min Max
MAH

smartport_master_halfduplex

// TODO

Default Min Max
ON OFF ON

smartport_master_inverted

// TODO

Default Min Max
OFF OFF ON

smith_predictor_delay

Expected delay of the gyro signal. In milliseconds

Default Min Max
0 0 8

smith_predictor_lpf_hz

Cutoff frequency for the Smith Predictor Low Pass Filter

Default Min Max
50 1 500

smith_predictor_strength

The strength factor of a Smith Predictor of PID measurement. In percents

Default Min Max
0.5 0 1

spektrum_sat_bind

0 = disabled. Used to bind the spektrum satellite to RX

Default Min Max
SPEKTRUM_SAT_BIND_DISABLED SPEKTRUM_SAT_BIND_DISABLED SPEKTRUM_SAT_BIND_MAX

srxl2_baud_fast

// TODO

Default Min Max
ON OFF ON

srxl2_unit_id

// TODO

Default Min Max
1 0 15

stats

General switch of the statistics recording feature (a.k.a. odometer)

Default Min Max
OFF OFF ON

stats_total_dist

Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled.

Default Min Max
0 2147483647

stats_total_energy

Total energy consumption [in mWh]. The value is updated on every disarm when "stats" are enabled.

Default Min Max
0 2147483647

stats_total_time

Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled.

Default Min Max
0 2147483647

switch_disarm_delay

Delay before disarming when requested by switch (ms) [0-1000]

Default Min Max
250 0 1000

tailsitter_orientation_offset

Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode

Default Min Max
OFF OFF ON

telemetry_halfduplex

S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details

Default Min Max
ON OFF ON

telemetry_inverted

Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used.

Default Min Max
OFF OFF ON

telemetry_switch

Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed.

Default Min Max
OFF OFF ON

thr_comp_weight

Weight used for the throttle compensation based on battery voltage. See the battery documentation

Default Min Max
1 0 2

thr_expo

Throttle exposition value

Default Min Max
0 0 100

thr_mid

Throttle value when the stick is set to mid-position. Used in the throttle curve calculation.

Default Min Max
50 0 100

throttle_idle

The percentage of the throttle range (max_throttle - min_command) above min_command used for minimum / idle throttle.

Default Min Max
8 0 30

throttle_scale

Throttle scaling factor. 1 means no throttle scaling. 0.5 means throttle scaled down by 50%

Default Min Max
1.0 0 1

throttle_tilt_comp_str

Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled.

Default Min Max
0 0 100

tpa_breakpoint

See tpa_rate.

Default Min Max
1500 PWM_RANGE_MIN PWM_RANGE_MAX

tpa_on_yaw

Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors.

Default Min Max
OFF OFF ON

tpa_rate

Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate.

Default Min Max
0 0 100

tri_unarmed_servo

On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF.

Default Min Max
ON OFF ON

turtle_mode_power_factor

Turtle mode power factor

Default Min Max
55 0 100

tz_automatic_dst

Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via tz_offset.

Default Min Max
OFF

tz_offset

Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs

Default Min Max
0 -720 840

vbat_adc_channel

ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled

Default Min Max
target default ADC_CHN_NONE ADC_CHN_MAX

vbat_cell_detect_voltage

Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units.

Default Min Max
425 100 500

vbat_max_cell_voltage

Maximum voltage per cell in 0.01V units, default is 4.20V

Default Min Max
420 100 500

vbat_meter_type

Vbat voltage source. Possible values: NONE, ADC, ESC. ESC required ESC telemetry enebled and running

Default Min Max
ADC

vbat_min_cell_voltage

Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)

Default Min Max
330 100 500

vbat_scale

Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli.

Default Min Max
target default 0 65535

vbat_warning_cell_voltage

Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)

Default Min Max
350 100 500

vtx_band

Configure the VTX band. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race.

Default Min Max
1 VTX_SETTINGS_MIN_BAND VTX_SETTINGS_MAX_BAND

vtx_channel

Channel to use within the configured vtx_band. Valid values are [1, 8].

Default Min Max
1 VTX_SETTINGS_MIN_CHANNEL VTX_SETTINGS_MAX_CHANNEL

vtx_frequency_group

VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz.

Default Min Max
FREQUENCYGROUP_5G8 0 2

vtx_halfduplex

Use half duplex UART to communicate with the VTX, using only a TX pin in the FC.

Default Min Max
ON OFF ON

vtx_low_power_disarm

When the craft is disarmed, set the VTX to its lowest power. ON will set the power to its minimum value on startup, increase it to vtx_power when arming and change it back to its lowest setting after disarming. UNTIL_FIRST_ARM will start with minimum power, but once the craft is armed it will increase to vtx_power and it will never decrease until the craft is power cycled.

Default Min Max
OFF

vtx_max_power_override

Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities

Default Min Max
0 0 10000

vtx_pit_mode_chan

Pit mode channel.

Default Min Max
1 VTX_SETTINGS_MIN_CHANNEL VTX_SETTINGS_MAX_CHANNEL

vtx_power

VTX RF power level to use. The exact number of mw depends on the VTX hardware.

Default Min Max
1 VTX_SETTINGS_MIN_POWER VTX_SETTINGS_MAX_POWER

vtx_smartaudio_alternate_softserial_method

Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier.

Default Min Max
ON OFF ON

vtx_smartaudio_early_akk_workaround

Enable workaround for early AKK SAudio-enabled VTX bug.

Default Min Max
ON OFF ON

vtx_smartaudio_stopbits

Set stopbit count for serial (TBS Sixty9 SmartAudio 2.1 require value of 1 bit)

Default Min Max
2 1 2

vtx_softserial_shortstop

Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes.

Default Min Max
OFF OFF ON

yaw_deadband

These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle.

Default Min Max
2 0 100

yaw_lpf_hz

Yaw P term low pass filter cutoff frequency. Should be disabled (set to 0) on small multirotors (7 inches and below)

Default Min Max
0 0 200

yaw_rate

Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure.

Default Min Max
20 1 180