h7: enable DPS310
[inav.git] / docs / Settings.md
blobde9cc0ea45a70aaab86bde13c8422da0ecd9798b
1 # CLI Variable Reference
3 > Note: this document is autogenerated. Do not edit it manually.
5 ### 3d_deadband_high
7 High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)
9 | Default | Min | Max |
10 | --- | --- | --- |
11 | 1514 | PWM_RANGE_MIN | PWM_RANGE_MAX |
13 ---
15 ### 3d_deadband_low
17 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)
19 | Default | Min | Max |
20 | --- | --- | --- |
21 | 1406 | PWM_RANGE_MIN | PWM_RANGE_MAX |
23 ---
25 ### 3d_deadband_throttle
27 Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter.
29 | Default | Min | Max |
30 | --- | --- | --- |
31 | 50 | 0 | 200 |
33 ---
35 ### 3d_neutral
37 Neutral (stop) throttle value for 3D mode
39 | Default | Min | Max |
40 | --- | --- | --- |
41 | 1460 | PWM_RANGE_MIN | PWM_RANGE_MAX |
43 ---
45 ### acc_event_threshold_high
47 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.
49 | Default | Min | Max |
50 | --- | --- | --- |
51 | 0 | 0 | 65535 |
53 ---
55 ### acc_event_threshold_low
57 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.
59 | Default | Min | Max |
60 | --- | --- | --- |
61 | 0 | 0 | 900 |
63 ---
65 ### acc_event_threshold_neg_x
67 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.
69 | Default | Min | Max |
70 | --- | --- | --- |
71 | 0 | 0 | 65535 |
73 ---
75 ### acc_hardware
77 Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info
79 | Default | Min | Max |
80 | --- | --- | --- |
81 | AUTO |  |  |
83 ---
85 ### acc_lpf_hz
87 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.
89 | Default | Min | Max |
90 | --- | --- | --- |
91 | 15 | 0 | 200 |
93 ---
95 ### acc_lpf_type
97 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.
99 | Default | Min | Max |
100 | --- | --- | --- |
101 | BIQUAD |  |  |
105 ### acc_notch_cutoff
107 _// TODO_
109 | Default | Min | Max |
110 | --- | --- | --- |
111 | 1 | 1 | 255 |
115 ### acc_notch_hz
117 _// TODO_
119 | Default | Min | Max |
120 | --- | --- | --- |
121 | 0 | 0 | 255 |
125 ### accgain_x
127 Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.
129 | Default | Min | Max |
130 | --- | --- | --- |
131 | 4096 | 1 | 8192 |
135 ### accgain_y
137 Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.
139 | Default | Min | Max |
140 | --- | --- | --- |
141 | 4096 | 1 | 8192 |
145 ### accgain_z
147 Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page.
149 | Default | Min | Max |
150 | --- | --- | --- |
151 | 4096 | 1 | 8192 |
155 ### acczero_x
157 Calculated value after '6 position avanced calibration'. See Wiki page.
159 | Default | Min | Max |
160 | --- | --- | --- |
161 | 0 | -32768 | 32767 |
165 ### acczero_y
167 Calculated value after '6 position avanced calibration'. See Wiki page.
169 | Default | Min | Max |
170 | --- | --- | --- |
171 | 0 | -32768 | 32767 |
175 ### acczero_z
177 Calculated value after '6 position avanced calibration'. See Wiki page.
179 | Default | Min | Max |
180 | --- | --- | --- |
181 | 0 | -32768 | 32767 |
185 ### airmode_throttle_threshold
187 Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used
189 | Default | Min | Max |
190 | --- | --- | --- |
191 | 1300 | 1000 | 2000 |
195 ### airmode_type
197 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.
199 | Default | Min | Max |
200 | --- | --- | --- |
201 | STICK_CENTER |  |  |
205 ### airspeed_adc_channel
207 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
209 | Default | Min | Max |
210 | --- | --- | --- |
211 | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX |
215 ### align_acc
217 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.
219 | Default | Min | Max |
220 | --- | --- | --- |
221 | DEFAULT |  |  |
225 ### align_board_pitch
227 Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc
229 | Default | Min | Max |
230 | --- | --- | --- |
231 | 0 | -1800 | 3600 |
235 ### align_board_roll
237 Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc
239 | Default | Min | Max |
240 | --- | --- | --- |
241 | 0 | -1800 | 3600 |
245 ### align_board_yaw
247 Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc
249 | Default | Min | Max |
250 | --- | --- | --- |
251 | 0 | -1800 | 3600 |
255 ### align_gyro
257 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.
259 | Default | Min | Max |
260 | --- | --- | --- |
261 | DEFAULT |  |  |
265 ### align_mag
267 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.
269 | Default | Min | Max |
270 | --- | --- | --- |
271 | DEFAULT |  |  |
275 ### align_mag_pitch
277 Same as align_mag_roll, but for the pitch axis.
279 | Default | Min | Max |
280 | --- | --- | --- |
281 | 0 | -1800 | 3600 |
285 ### align_mag_roll
287 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.
289 | Default | Min | Max |
290 | --- | --- | --- |
291 | 0 | -1800 | 3600 |
295 ### align_mag_yaw
297 Same as align_mag_roll, but for the yaw axis.
299 | Default | Min | Max |
300 | --- | --- | --- |
301 | 0 | -1800 | 3600 |
305 ### align_opflow
307 Optical flow module alignment (default CW0_DEG_FLIP)
309 | Default | Min | Max |
310 | --- | --- | --- |
311 | CW0FLIP |  |  |
315 ### alt_hold_deadband
317 Defines the deadband of throttle during alt_hold [r/c points]
319 | Default | Min | Max |
320 | --- | --- | --- |
321 | 50 | 10 | 250 |
325 ### antigravity_accelerator
327 _// TODO_
329 | Default | Min | Max |
330 | --- | --- | --- |
331 | 1 | 1 | 20 |
335 ### antigravity_cutoff_lpf_hz
337 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
339 | Default | Min | Max |
340 | --- | --- | --- |
341 | 15 | 1 | 30 |
345 ### antigravity_gain
347 Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements
349 | Default | Min | Max |
350 | --- | --- | --- |
351 | 1 | 1 | 20 |
355 ### applied_defaults
357 Internal (configurator) hint. Should not be changed manually
359 | Default | Min | Max |
360 | --- | --- | --- |
361 | 0 | 0 | 3 |
365 ### baro_cal_tolerance
367 Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm].
369 | Default | Min | Max |
370 | --- | --- | --- |
371 | 150 | 0 | 1000 |
375 ### baro_hardware
377 Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info
379 | Default | Min | Max |
380 | --- | --- | --- |
381 | AUTO |  |  |
385 ### baro_median_filter
387 3-point median filtering for barometer readouts. No reason to change this setting
389 | Default | Min | Max |
390 | --- | --- | --- |
391 | ON |  |  |
395 ### bat_cells
397 Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected.
399 | Default | Min | Max |
400 | --- | --- | --- |
401 | 0 | 0 | 12 |
405 ### bat_voltage_src
407 Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`
409 | Default | Min | Max |
410 | --- | --- | --- |
411 | RAW |  |  |
415 ### battery_capacity
417 Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity.
419 | Default | Min | Max |
420 | --- | --- | --- |
421 | 0 | 0 | 4294967295 |
425 ### battery_capacity_critical
427 If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps.
429 | Default | Min | Max |
430 | --- | --- | --- |
431 | 0 | 0 | 4294967295 |
435 ### battery_capacity_unit
437 Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour).
439 | Default | Min | Max |
440 | --- | --- | --- |
441 | MAH |  |  |
445 ### battery_capacity_warning
447 If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink.
449 | Default | Min | Max |
450 | --- | --- | --- |
451 | 0 | 0 | 4294967295 |
455 ### blackbox_device
457 Selection of where to write blackbox data
459 | Default | Min | Max |
460 | --- | --- | --- |
461 | _target default_ |  |  |
465 ### blackbox_rate_denom
467 Blackbox logging rate denominator. See blackbox_rate_num.
469 | Default | Min | Max |
470 | --- | --- | --- |
471 | 1 | 1 | 65535 |
475 ### blackbox_rate_num
477 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
479 | Default | Min | Max |
480 | --- | --- | --- |
481 | 1 | 1 | 65535 |
485 ### control_deadband
487 Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered.
489 | Default | Min | Max |
490 | --- | --- | --- |
491 | 10 | 2 | 250 |
495 ### cpu_underclock
497 This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz
499 | Default | Min | Max |
500 | --- | --- | --- |
501 | OFF |  |  |
505 ### cruise_power
507 Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit
509 | Default | Min | Max |
510 | --- | --- | --- |
511 | 0 | 0 | 4294967295 |
515 ### current_adc_channel
517 ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled
519 | Default | Min | Max |
520 | --- | --- | --- |
521 | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX |
525 ### current_meter_offset
527 This sets the output offset voltage of the current sensor in millivolts.
529 | Default | Min | Max |
530 | --- | --- | --- |
531 | _target default_ | -32768 | 32767 |
535 ### current_meter_scale
537 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.
539 | Default | Min | Max |
540 | --- | --- | --- |
541 | _target default_ | -10000 | 10000 |
545 ### current_meter_type
547 ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position.
549 | Default | Min | Max |
550 | --- | --- | --- |
551 | ADC |  |  |
555 ### d_boost_factor
557 _// TODO_
559 | Default | Min | Max |
560 | --- | --- | --- |
561 | 1.25 | 1 | 3 |
565 ### d_boost_gyro_delta_lpf_hz
567 _// TODO_
569 | Default | Min | Max |
570 | --- | --- | --- |
571 | 80 | 10 | 250 |
575 ### d_boost_max_at_acceleration
577 _// TODO_
579 | Default | Min | Max |
580 | --- | --- | --- |
581 | 7500 | 1000 | 16000 |
585 ### deadband
587 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.
589 | Default | Min | Max |
590 | --- | --- | --- |
591 | 5 | 0 | 32 |
595 ### debug_mode
597 Defines debug values exposed in debug variables (developer / debugging setting)
599 | Default | Min | Max |
600 | --- | --- | --- |
601 | NONE |  |  |
605 ### disarm_kill_switch
607 Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel.
609 | Default | Min | Max |
610 | --- | --- | --- |
611 | ON |  |  |
615 ### display_force_sw_blink
617 OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON
619 | Default | Min | Max |
620 | --- | --- | --- |
621 | OFF |  |  |
625 ### dji_esc_temp_source
627 Re-purpose the ESC temperature field for IMU/BARO temperature
629 | Default | Min | Max |
630 | --- | --- | --- |
631 | ESC |  |  |
635 ### dji_use_name_for_messages
637 Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance
639 | Default | Min | Max |
640 | --- | --- | --- |
641 | ON |  |  |
645 ### dji_workarounds
647 Enables workarounds for different versions of MSP protocol used
649 | Default | Min | Max |
650 | --- | --- | --- |
651 | 1 | 0 | 255 |
655 ### dshot_beeper_enabled
657 Whether using DShot motors as beepers is enabled
659 | Default | Min | Max |
660 | --- | --- | --- |
661 | ON |  |  |
665 ### dshot_beeper_tone
667 Sets the DShot beeper tone
669 | Default | Min | Max |
670 | --- | --- | --- |
671 | 1 | 1 | 5 |
675 ### dterm_lpf2_hz
677 Cutoff frequency for stage 2 D-term low pass filter
679 | Default | Min | Max |
680 | --- | --- | --- |
681 | 0 | 0 | 500 |
685 ### dterm_lpf2_type
687 Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
689 | Default | Min | Max |
690 | --- | --- | --- |
691 | BIQUAD |  |  |
695 ### dterm_lpf_hz
697 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
699 | Default | Min | Max |
700 | --- | --- | --- |
701 | 40 | 0 | 500 |
705 ### dterm_lpf_type
707 Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
709 | Default | Min | Max |
710 | --- | --- | --- |
711 | BIQUAD |  |  |
715 ### dynamic_gyro_notch_enabled
717 Enable/disable dynamic gyro notch also known as Matrix Filter
719 | Default | Min | Max |
720 | --- | --- | --- |
721 | OFF |  |  |
725 ### dynamic_gyro_notch_min_hz
727 Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70`
729 | Default | Min | Max |
730 | --- | --- | --- |
731 | 150 | 30 | 1000 |
735 ### dynamic_gyro_notch_q
737 Q factor for dynamic notches
739 | Default | Min | Max |
740 | --- | --- | --- |
741 | 120 | 1 | 1000 |
745 ### dynamic_gyro_notch_range
747 Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers
749 | Default | Min | Max |
750 | --- | --- | --- |
751 | MEDIUM |  |  |
755 ### eleres_freq
757 _// TODO_
759 | Default | Min | Max |
760 | --- | --- | --- |
761 | 435 | 415 | 450 |
765 ### eleres_loc_delay
767 _// TODO_
769 | Default | Min | Max |
770 | --- | --- | --- |
771 | 240 | 30 | 1800 |
775 ### eleres_loc_en
777 _// TODO_
779 | Default | Min | Max |
780 | --- | --- | --- |
781 | OFF |  |  |
785 ### eleres_loc_power
787 _// TODO_
789 | Default | Min | Max |
790 | --- | --- | --- |
791 | 7 | 0 | 7 |
795 ### eleres_signature
797 _// TODO_
799 | Default | Min | Max |
800 | --- | --- | --- |
801 | 0 |  | 4294967295 |
805 ### eleres_telemetry_en
807 _// TODO_
809 | Default | Min | Max |
810 | --- | --- | --- |
811 | OFF |  |  |
815 ### eleres_telemetry_power
817 _// TODO_
819 | Default | Min | Max |
820 | --- | --- | --- |
821 | 7 | 0 | 7 |
825 ### esc_sensor_listen_only
827 Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case
829 | Default | Min | Max |
830 | --- | --- | --- |
831 | OFF |  |  |
835 ### failsafe_delay
837 Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay).
839 | Default | Min | Max |
840 | --- | --- | --- |
841 | 5 | 0 | 200 |
845 ### failsafe_fw_pitch_angle
847 Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb
849 | Default | Min | Max |
850 | --- | --- | --- |
851 | 100 | -800 | 800 |
855 ### failsafe_fw_roll_angle
857 Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll
859 | Default | Min | Max |
860 | --- | --- | --- |
861 | -200 | -800 | 800 |
865 ### failsafe_fw_yaw_rate
867 Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn
869 | Default | Min | Max |
870 | --- | --- | --- |
871 | -45 | -1000 | 1000 |
875 ### failsafe_lights
877 Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF].
879 | Default | Min | Max |
880 | --- | --- | --- |
881 | ON |  |  |
885 ### failsafe_lights_flash_on_time
887 Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535].
889 | Default | Min | Max |
890 | --- | --- | --- |
891 | 100 | 20 | 65535 |
895 ### failsafe_lights_flash_period
897 Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535].
899 | Default | Min | Max |
900 | --- | --- | --- |
901 | 1000 | 40 | 65535 |
905 ### failsafe_min_distance
907 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.
909 | Default | Min | Max |
910 | --- | --- | --- |
911 | 0 | 0 | 65000 |
915 ### failsafe_min_distance_procedure
917 What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle).
919 | Default | Min | Max |
920 | --- | --- | --- |
921 | DROP |  |  |
925 ### failsafe_mission
927 If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode
929 | Default | Min | Max |
930 | --- | --- | --- |
931 | ON |  |  |
935 ### failsafe_off_delay
937 Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay).
939 | Default | Min | Max |
940 | --- | --- | --- |
941 | 200 | 0 | 200 |
945 ### failsafe_procedure
947 What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle).
949 | Default | Min | Max |
950 | --- | --- | --- |
951 | SET-THR |  |  |
955 ### failsafe_recovery_delay
957 Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay).
959 | Default | Min | Max |
960 | --- | --- | --- |
961 | 5 | 0 | 200 |
965 ### failsafe_stick_threshold
967 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.
969 | Default | Min | Max |
970 | --- | --- | --- |
971 | 50 | 0 | 500 |
975 ### failsafe_throttle
977 Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle).
979 | Default | Min | Max |
980 | --- | --- | --- |
981 | 1000 | PWM_RANGE_MIN | PWM_RANGE_MAX |
985 ### failsafe_throttle_low_delay
987 If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout
989 | Default | Min | Max |
990 | --- | --- | --- |
991 | 0 | 0 | 300 |
995 ### fixed_wing_auto_arm
997 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.
999 | Default | Min | Max |
1000 | --- | --- | --- |
1001 | OFF |  |  |
1005 ### flaperon_throw_offset
1007 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.
1009 | Default | Min | Max |
1010 | --- | --- | --- |
1011 | 200 | FLAPERON_THROW_MIN | FLAPERON_THROW_MAX |
1015 ### fpv_mix_degrees
1017 _// TODO_
1019 | Default | Min | Max |
1020 | --- | --- | --- |
1021 | 0 | 0 | 50 |
1025 ### frsky_coordinates_format
1027 D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA
1029 | Default | Min | Max |
1030 | --- | --- | --- |
1031 | 0 | 0 | FRSKY_FORMAT_NMEA |
1035 ### frsky_default_latitude
1037 D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired.
1039 | Default | Min | Max |
1040 | --- | --- | --- |
1041 | 0 | -90 | 90 |
1045 ### frsky_default_longitude
1047 D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired.
1049 | Default | Min | Max |
1050 | --- | --- | --- |
1051 | 0 | -180 | 180 |
1055 ### frsky_pitch_roll
1057 S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data
1059 | Default | Min | Max |
1060 | --- | --- | --- |
1061 | OFF |  |  |
1065 ### frsky_unit
1067 Not used? [METRIC/IMPERIAL]
1069 | Default | Min | Max |
1070 | --- | --- | --- |
1071 | METRIC |  |  |
1075 ### frsky_vfas_precision
1077 D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method
1079 | Default | Min | Max |
1080 | --- | --- | --- |
1081 | 0 | FRSKY_VFAS_PRECISION_LOW | FRSKY_VFAS_PRECISION_HIGH |
1085 ### fw_autotune_ff_to_i_tc
1087 FF to I time (defines time for I to reach the same level of response as FF) [ms]
1089 | Default | Min | Max |
1090 | --- | --- | --- |
1091 | 600 | 100 | 5000 |
1095 ### fw_autotune_ff_to_p_gain
1097 FF to P gain (strength relationship) [%]
1099 | Default | Min | Max |
1100 | --- | --- | --- |
1101 | 10 | 0 | 100 |
1105 ### fw_autotune_max_rate_deflection
1107 The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`.
1109 | Default | Min | Max |
1110 | --- | --- | --- |
1111 | 90 | 50 | 100 |
1115 ### fw_autotune_min_stick
1117 Minimum stick input [%] to consider overshoot/undershoot detection
1119 | Default | Min | Max |
1120 | --- | --- | --- |
1121 | 50 | 0 | 100 |
1125 ### fw_autotune_p_to_d_gain
1127 P to D gain (strength relationship) [%]
1129 | Default | Min | Max |
1130 | --- | --- | --- |
1131 | 0 | 0 | 200 |
1135 ### fw_autotune_rate_adjustment
1137 `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.
1139 | Default | Min | Max |
1140 | --- | --- | --- |
1141 | AUTO |  |  |
1145 ### fw_d_level
1147 Fixed-wing attitude stabilisation HORIZON transition point
1149 | Default | Min | Max |
1150 | --- | --- | --- |
1151 | 75 | 0 | 255 |
1155 ### fw_d_pitch
1157 Fixed wing rate stabilisation D-gain for PITCH
1159 | Default | Min | Max |
1160 | --- | --- | --- |
1161 | 0 | 0 | 255 |
1165 ### fw_d_roll
1167 Fixed wing rate stabilisation D-gain for ROLL
1169 | Default | Min | Max |
1170 | --- | --- | --- |
1171 | 0 | 0 | 255 |
1175 ### fw_d_yaw
1177 Fixed wing rate stabilisation D-gain for YAW
1179 | Default | Min | Max |
1180 | --- | --- | --- |
1181 | 0 | 0 | 255 |
1185 ### fw_ff_pitch
1187 Fixed-wing rate stabilisation FF-gain for PITCH
1189 | Default | Min | Max |
1190 | --- | --- | --- |
1191 | 50 | 0 | 255 |
1195 ### fw_ff_roll
1197 Fixed-wing rate stabilisation FF-gain for ROLL
1199 | Default | Min | Max |
1200 | --- | --- | --- |
1201 | 50 | 0 | 255 |
1205 ### fw_ff_yaw
1207 Fixed-wing rate stabilisation FF-gain for YAW
1209 | Default | Min | Max |
1210 | --- | --- | --- |
1211 | 60 | 0 | 255 |
1215 ### fw_i_level
1217 Fixed-wing attitude stabilisation low-pass filter cutoff
1219 | Default | Min | Max |
1220 | --- | --- | --- |
1221 | 5 | 0 | 255 |
1225 ### fw_i_pitch
1227 Fixed-wing rate stabilisation I-gain for PITCH
1229 | Default | Min | Max |
1230 | --- | --- | --- |
1231 | 7 | 0 | 255 |
1235 ### fw_i_roll
1237 Fixed-wing rate stabilisation I-gain for ROLL
1239 | Default | Min | Max |
1240 | --- | --- | --- |
1241 | 7 | 0 | 255 |
1245 ### fw_i_yaw
1247 Fixed-wing rate stabilisation I-gain for YAW
1249 | Default | Min | Max |
1250 | --- | --- | --- |
1251 | 10 | 0 | 255 |
1255 ### fw_iterm_limit_stick_position
1257 Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side
1259 | Default | Min | Max |
1260 | --- | --- | --- |
1261 | 0.5 | 0 | 1 |
1265 ### fw_iterm_throw_limit
1267 Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely.
1269 | Default | Min | Max |
1270 | --- | --- | --- |
1271 | 165 | FW_ITERM_THROW_LIMIT_MIN | FW_ITERM_THROW_LIMIT_MAX |
1275 ### fw_level_pitch_gain
1277 I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations
1279 | Default | Min | Max |
1280 | --- | --- | --- |
1281 | 5 | 0 | 20 |
1285 ### fw_level_pitch_trim
1287 Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level
1289 | Default | Min | Max |
1290 | --- | --- | --- |
1291 | 0 | -10 | 10 |
1295 ### fw_loiter_direction
1297 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.
1299 | Default | Min | Max |
1300 | --- | --- | --- |
1301 | RIGHT |  |  |
1305 ### fw_min_throttle_down_pitch
1307 Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)
1309 | Default | Min | Max |
1310 | --- | --- | --- |
1311 | 0 | 0 | 450 |
1315 ### fw_p_level
1317 Fixed-wing attitude stabilisation P-gain
1319 | Default | Min | Max |
1320 | --- | --- | --- |
1321 | 20 | 0 | 255 |
1325 ### fw_p_pitch
1327 Fixed-wing rate stabilisation P-gain for PITCH
1329 | Default | Min | Max |
1330 | --- | --- | --- |
1331 | 5 | 0 | 255 |
1335 ### fw_p_roll
1337 Fixed-wing rate stabilisation P-gain for ROLL
1339 | Default | Min | Max |
1340 | --- | --- | --- |
1341 | 5 | 0 | 255 |
1345 ### fw_p_yaw
1347 Fixed-wing rate stabilisation P-gain for YAW
1349 | Default | Min | Max |
1350 | --- | --- | --- |
1351 | 6 | 0 | 255 |
1355 ### fw_reference_airspeed
1357 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.
1359 | Default | Min | Max |
1360 | --- | --- | --- |
1361 | 1500 | 300 | 6000 |
1365 ### fw_tpa_time_constant
1367 TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups
1369 | Default | Min | Max |
1370 | --- | --- | --- |
1371 | 0 | 0 | 5000 |
1375 ### fw_turn_assist_pitch_gain
1377 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
1379 | Default | Min | Max |
1380 | --- | --- | --- |
1381 | 1 | 0 | 2 |
1385 ### fw_turn_assist_yaw_gain
1387 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
1389 | Default | Min | Max |
1390 | --- | --- | --- |
1391 | 1 | 0 | 2 |
1395 ### fw_yaw_iterm_freeze_bank_angle
1397 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.
1399 | Default | Min | Max |
1400 | --- | --- | --- |
1401 | 0 | 0 | 90 |
1405 ### gps_auto_baud
1407 Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports
1409 | Default | Min | Max |
1410 | --- | --- | --- |
1411 | ON |  |  |
1415 ### gps_auto_config
1417 Enable automatic configuration of UBlox GPS receivers.
1419 | Default | Min | Max |
1420 | --- | --- | --- |
1421 | ON |  |  |
1425 ### gps_dyn_model
1427 GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying.
1429 | Default | Min | Max |
1430 | --- | --- | --- |
1431 | AIR_1G |  |  |
1435 ### gps_min_sats
1437 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.
1439 | Default | Min | Max |
1440 | --- | --- | --- |
1441 | 6 | 5 | 10 |
1445 ### gps_provider
1447 Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N).
1449 | Default | Min | Max |
1450 | --- | --- | --- |
1451 | UBLOX |  |  |
1455 ### gps_sbas_mode
1457 Which SBAS mode to be used
1459 | Default | Min | Max |
1460 | --- | --- | --- |
1461 | NONE |  |  |
1465 ### gps_ublox_use_galileo
1467 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].
1469 | Default | Min | Max |
1470 | --- | --- | --- |
1471 | OFF |  |  |
1475 ### gyro_abg_alpha
1477 Alpha factor for Gyro Alpha-Beta-Gamma filter
1479 | Default | Min | Max |
1480 | --- | --- | --- |
1481 | 0 | 0 | 1 |
1485 ### gyro_abg_boost
1487 Boost factor for Gyro Alpha-Beta-Gamma filter
1489 | Default | Min | Max |
1490 | --- | --- | --- |
1491 | 0.35 | 0 | 2 |
1495 ### gyro_abg_half_life
1497 Sample half-life for Gyro Alpha-Beta-Gamma filter
1499 | Default | Min | Max |
1500 | --- | --- | --- |
1501 | 0.5 | 0 | 10 |
1505 ### gyro_anti_aliasing_lpf_hz
1507 Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz
1509 | Default | Min | Max |
1510 | --- | --- | --- |
1511 | 250 |  | 1000 |
1515 ### gyro_anti_aliasing_lpf_type
1517 Specifies the type of the software LPF of the gyro signals.
1519 | Default | Min | Max |
1520 | --- | --- | --- |
1521 | PT1 |  |  |
1525 ### gyro_dyn_lpf_curve_expo
1527 Expo value for the throttle-to-frequency mapping for Dynamic LPF
1529 | Default | Min | Max |
1530 | --- | --- | --- |
1531 | 5 | 1 | 10 |
1535 ### gyro_dyn_lpf_max_hz
1537 Maximum frequency of the gyro Dynamic LPF
1539 | Default | Min | Max |
1540 | --- | --- | --- |
1541 | 500 | 40 | 1000 |
1545 ### gyro_dyn_lpf_min_hz
1547 Minimum frequency of the gyro Dynamic LPF
1549 | Default | Min | Max |
1550 | --- | --- | --- |
1551 | 200 | 40 | 400 |
1555 ### gyro_hardware_lpf
1557 Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first.
1559 | Default | Min | Max |
1560 | --- | --- | --- |
1561 | 256HZ |  |  |
1565 ### gyro_main_lpf_hz
1567 Software based gyro main lowpass filter. Value is cutoff frequency (Hz)
1569 | Default | Min | Max |
1570 | --- | --- | --- |
1571 | 60 | 0 | 500 |
1575 ### gyro_main_lpf_type
1577 Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation.
1579 | Default | Min | Max |
1580 | --- | --- | --- |
1581 | BIQUAD |  |  |
1585 ### gyro_notch_cutoff
1587 _// TODO_
1589 | Default | Min | Max |
1590 | --- | --- | --- |
1591 | 1 | 1 | 500 |
1595 ### gyro_notch_hz
1597 _// TODO_
1599 | Default | Min | Max |
1600 | --- | --- | --- |
1601 | 0 |  | 500 |
1605 ### gyro_to_use
1607 _// TODO_
1609 | Default | Min | Max |
1610 | --- | --- | --- |
1611 | 0 | 0 | 1 |
1615 ### gyro_use_dyn_lpf
1617 Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position.
1619 | Default | Min | Max |
1620 | --- | --- | --- |
1621 | OFF |  |  |
1625 ### has_flaps
1627 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
1629 | Default | Min | Max |
1630 | --- | --- | --- |
1631 | OFF |  |  |
1635 ### heading_hold_rate_limit
1637 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.
1639 | Default | Min | Max |
1640 | --- | --- | --- |
1641 | 90 | HEADING_HOLD_RATE_LIMIT_MIN | HEADING_HOLD_RATE_LIMIT_MAX |
1645 ### hott_alarm_sound_interval
1647 Battery alarm delay in seconds for Hott telemetry
1649 | Default | Min | Max |
1650 | --- | --- | --- |
1651 | 5 | 0 | 120 |
1655 ### i2c_speed
1657 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)
1659 | Default | Min | Max |
1660 | --- | --- | --- |
1661 | 400KHZ |  |  |
1665 ### ibus_telemetry_type
1667 Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details.
1669 | Default | Min | Max |
1670 | --- | --- | --- |
1671 | 0 | 0 | 255 |
1675 ### idle_power
1677 Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit
1679 | Default | Min | Max |
1680 | --- | --- | --- |
1681 | 0 | 0 | 65535 |
1685 ### imu2_align_pitch
1687 Pitch alignment for Secondary IMU. 1/10 of a degree
1689 | Default | Min | Max |
1690 | --- | --- | --- |
1691 | 0 | -1800 | 3600 |
1695 ### imu2_align_roll
1697 Roll alignment for Secondary IMU. 1/10 of a degree
1699 | Default | Min | Max |
1700 | --- | --- | --- |
1701 | 0 | -1800 | 3600 |
1705 ### imu2_align_yaw
1707 Yaw alignment for Secondary IMU. 1/10 of a degree
1709 | Default | Min | Max |
1710 | --- | --- | --- |
1711 | 0 | -1800 | 3600 |
1715 ### imu2_gain_acc_x
1717 Secondary IMU ACC calibration data
1719 | Default | Min | Max |
1720 | --- | --- | --- |
1721 | 0 | -32768 | 32767 |
1725 ### imu2_gain_acc_y
1727 Secondary IMU ACC calibration data
1729 | Default | Min | Max |
1730 | --- | --- | --- |
1731 | 0 | -32768 | 32767 |
1735 ### imu2_gain_acc_z
1737 Secondary IMU ACC calibration data
1739 | Default | Min | Max |
1740 | --- | --- | --- |
1741 | 0 | -32768 | 32767 |
1745 ### imu2_gain_mag_x
1747 Secondary IMU MAG calibration data
1749 | Default | Min | Max |
1750 | --- | --- | --- |
1751 | 0 | -32768 | 32767 |
1755 ### imu2_gain_mag_y
1757 Secondary IMU MAG calibration data
1759 | Default | Min | Max |
1760 | --- | --- | --- |
1761 | 0 | -32768 | 32767 |
1765 ### imu2_gain_mag_z
1767 Secondary IMU MAG calibration data
1769 | Default | Min | Max |
1770 | --- | --- | --- |
1771 | 0 | -32768 | 32767 |
1775 ### imu2_hardware
1777 Selection of a Secondary IMU hardware type. NONE disables this functionality
1779 | Default | Min | Max |
1780 | --- | --- | --- |
1781 | NONE |  |  |
1785 ### imu2_radius_acc
1787 Secondary IMU MAG calibration data
1789 | Default | Min | Max |
1790 | --- | --- | --- |
1791 | 0 | -32768 | 32767 |
1795 ### imu2_radius_mag
1797 Secondary IMU MAG calibration data
1799 | Default | Min | Max |
1800 | --- | --- | --- |
1801 | 0 | -32768 | 32767 |
1805 ### imu2_use_for_osd_ahi
1807 If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon
1809 | Default | Min | Max |
1810 | --- | --- | --- |
1811 | OFF |  |  |
1815 ### imu2_use_for_osd_heading
1817 If set to ON, Secondary IMU data will be used for Analog OSD heading
1819 | Default | Min | Max |
1820 | --- | --- | --- |
1821 | OFF |  |  |
1825 ### imu2_use_for_stabilized
1827 If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH)
1829 | Default | Min | Max |
1830 | --- | --- | --- |
1831 | OFF |  |  |
1835 ### imu_acc_ignore_rate
1837 Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes
1839 | Default | Min | Max |
1840 | --- | --- | --- |
1841 | 0 | 0 | 20 |
1845 ### imu_acc_ignore_slope
1847 Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)
1849 | Default | Min | Max |
1850 | --- | --- | --- |
1851 | 0 | 0 | 5 |
1855 ### imu_dcm_ki
1857 Inertial Measurement Unit KI Gain for accelerometer measurements
1859 | Default | Min | Max |
1860 | --- | --- | --- |
1861 | 50 |  | 65535 |
1865 ### imu_dcm_ki_mag
1867 Inertial Measurement Unit KI Gain for compass measurements
1869 | Default | Min | Max |
1870 | --- | --- | --- |
1871 | 0 |  | 65535 |
1875 ### imu_dcm_kp
1877 Inertial Measurement Unit KP Gain for accelerometer measurements
1879 | Default | Min | Max |
1880 | --- | --- | --- |
1881 | 2500 |  | 65535 |
1885 ### imu_dcm_kp_mag
1887 Inertial Measurement Unit KP Gain for compass measurements
1889 | Default | Min | Max |
1890 | --- | --- | --- |
1891 | 10000 |  | 65535 |
1895 ### inav_allow_dead_reckoning
1897 Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation
1899 | Default | Min | Max |
1900 | --- | --- | --- |
1901 | OFF |  |  |
1905 ### inav_auto_mag_decl
1907 Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored.
1909 | Default | Min | Max |
1910 | --- | --- | --- |
1911 | ON |  |  |
1915 ### inav_baro_epv
1917 Uncertainty value for barometric sensor [cm]
1919 | Default | Min | Max |
1920 | --- | --- | --- |
1921 | 100 | 0 | 9999 |
1925 ### inav_gravity_cal_tolerance
1927 Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value.
1929 | Default | Min | Max |
1930 | --- | --- | --- |
1931 | 5 | 0 | 255 |
1935 ### inav_max_eph_epv
1937 Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]
1939 | Default | Min | Max |
1940 | --- | --- | --- |
1941 | 1000 | 0 | 9999 |
1945 ### inav_max_surface_altitude
1947 Max allowed altitude for surface following mode. [cm]
1949 | Default | Min | Max |
1950 | --- | --- | --- |
1951 | 200 | 0 | 1000 |
1955 ### inav_reset_altitude
1957 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)
1959 | Default | Min | Max |
1960 | --- | --- | --- |
1961 | FIRST_ARM |  |  |
1965 ### inav_reset_home
1967 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
1969 | Default | Min | Max |
1970 | --- | --- | --- |
1971 | FIRST_ARM |  |  |
1975 ### inav_use_gps_no_baro
1977 _// TODO_
1979 | Default | Min | Max |
1980 | --- | --- | --- |
1981 | OFF |  |  |
1985 ### inav_use_gps_velned
1987 Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance.
1989 | Default | Min | Max |
1990 | --- | --- | --- |
1991 | ON |  |  |
1995 ### inav_w_acc_bias
1997 Weight for accelerometer drift estimation
1999 | Default | Min | Max |
2000 | --- | --- | --- |
2001 | 0.01 | 0 | 1 |
2005 ### inav_w_xy_flow_p
2007 _// TODO_
2009 | Default | Min | Max |
2010 | --- | --- | --- |
2011 | 1.0 | 0 | 100 |
2015 ### inav_w_xy_flow_v
2017 _// TODO_
2019 | Default | Min | Max |
2020 | --- | --- | --- |
2021 | 2.0 | 0 | 100 |
2025 ### inav_w_xy_gps_p
2027 Weight of GPS coordinates in estimated UAV position and speed.
2029 | Default | Min | Max |
2030 | --- | --- | --- |
2031 | 1.0 | 0 | 10 |
2035 ### inav_w_xy_gps_v
2037 Weight of GPS velocity data in estimated UAV speed
2039 | Default | Min | Max |
2040 | --- | --- | --- |
2041 | 2.0 | 0 | 10 |
2045 ### inav_w_xy_res_v
2047 Decay coefficient for estimated velocity when GPS reference for position is lost
2049 | Default | Min | Max |
2050 | --- | --- | --- |
2051 | 0.5 | 0 | 10 |
2055 ### inav_w_xyz_acc_p
2057 _// TODO_
2059 | Default | Min | Max |
2060 | --- | --- | --- |
2061 | 1.0 | 0 | 1 |
2065 ### inav_w_z_baro_p
2067 Weight of barometer measurements in estimated altitude and climb rate
2069 | Default | Min | Max |
2070 | --- | --- | --- |
2071 | 0.35 | 0 | 10 |
2075 ### inav_w_z_gps_p
2077 Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes
2079 | Default | Min | Max |
2080 | --- | --- | --- |
2081 | 0.2 | 0 | 10 |
2085 ### inav_w_z_gps_v
2087 Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero
2089 | Default | Min | Max |
2090 | --- | --- | --- |
2091 | 0.1 | 0 | 10 |
2095 ### inav_w_z_res_v
2097 Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost
2099 | Default | Min | Max |
2100 | --- | --- | --- |
2101 | 0.5 | 0 | 10 |
2105 ### inav_w_z_surface_p
2107 _// TODO_
2109 | Default | Min | Max |
2110 | --- | --- | --- |
2111 | 3.5 | 0 | 100 |
2115 ### inav_w_z_surface_v
2117 _// TODO_
2119 | Default | Min | Max |
2120 | --- | --- | --- |
2121 | 6.1 | 0 | 100 |
2125 ### iterm_windup
2127 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)
2129 | Default | Min | Max |
2130 | --- | --- | --- |
2131 | 50 | 0 | 90 |
2135 ### ledstrip_visual_beeper
2137 _// TODO_
2139 | Default | Min | Max |
2140 | --- | --- | --- |
2141 | OFF |  |  |
2145 ### limit_attn_filter_cutoff
2147 Throttle attenuation PI control output filter cutoff frequency
2149 | Default | Min | Max |
2150 | --- | --- | --- |
2151 | 1.2 |  | 100 |
2155 ### limit_burst_current
2157 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
2159 | Default | Min | Max |
2160 | --- | --- | --- |
2161 | 0 |  | 4000 |
2165 ### limit_burst_current_falldown_time
2167 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`
2169 | Default | Min | Max |
2170 | --- | --- | --- |
2171 | 0 |  | 3000 |
2175 ### limit_burst_current_time
2177 Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced
2179 | Default | Min | Max |
2180 | --- | --- | --- |
2181 | 0 |  | 3000 |
2185 ### limit_burst_power
2187 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
2189 | Default | Min | Max |
2190 | --- | --- | --- |
2191 | 0 |  | 40000 |
2195 ### limit_burst_power_falldown_time
2197 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`
2199 | Default | Min | Max |
2200 | --- | --- | --- |
2201 | 0 |  | 3000 |
2205 ### limit_burst_power_time
2207 Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced
2209 | Default | Min | Max |
2210 | --- | --- | --- |
2211 | 0 |  | 3000 |
2215 ### limit_cont_current
2217 Continous current limit (dA), set to 0 to disable
2219 | Default | Min | Max |
2220 | --- | --- | --- |
2221 | 0 |  | 4000 |
2225 ### limit_cont_power
2227 Continous power limit (dW), set to 0 to disable
2229 | Default | Min | Max |
2230 | --- | --- | --- |
2231 | 0 |  | 40000 |
2235 ### limit_pi_i
2237 Throttle attenuation PI control I term
2239 | Default | Min | Max |
2240 | --- | --- | --- |
2241 | 100 |  | 10000 |
2245 ### limit_pi_p
2247 Throttle attenuation PI control P term
2249 | Default | Min | Max |
2250 | --- | --- | --- |
2251 | 100 |  | 10000 |
2255 ### log_level
2257 Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage.
2259 | Default | Min | Max |
2260 | --- | --- | --- |
2261 | ERROR |  |  |
2265 ### log_topics
2267 Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage.
2269 | Default | Min | Max |
2270 | --- | --- | --- |
2271 | 0 | 0 | 4294967295 |
2275 ### looptime
2277 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.
2279 | Default | Min | Max |
2280 | --- | --- | --- |
2281 | 1000 |  | 9000 |
2285 ### ltm_update_rate
2287 Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details.
2289 | Default | Min | Max |
2290 | --- | --- | --- |
2291 | NORMAL |  |  |
2295 ### mag_calibration_time
2297 Adjust how long time the Calibration of mag will last.
2299 | Default | Min | Max |
2300 | --- | --- | --- |
2301 | 30 | 20 | 120 |
2305 ### mag_declination
2307 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.
2309 | Default | Min | Max |
2310 | --- | --- | --- |
2311 | 0 | -18000 | 18000 |
2315 ### mag_hardware
2317 Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info
2319 | Default | Min | Max |
2320 | --- | --- | --- |
2321 | AUTO |  |  |
2325 ### mag_to_use
2327 Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target
2329 | Default | Min | Max |
2330 | --- | --- | --- |
2331 | 0 | 0 | 1 |
2335 ### maggain_x
2337 Magnetometer calibration X gain. If 1024, no calibration or calibration failed
2339 | Default | Min | Max |
2340 | --- | --- | --- |
2341 | 1024 | -32768 | 32767 |
2345 ### maggain_y
2347 Magnetometer calibration Y gain. If 1024, no calibration or calibration failed
2349 | Default | Min | Max |
2350 | --- | --- | --- |
2351 | 1024 | -32768 | 32767 |
2355 ### maggain_z
2357 Magnetometer calibration Z gain. If 1024, no calibration or calibration failed
2359 | Default | Min | Max |
2360 | --- | --- | --- |
2361 | 1024 | -32768 | 32767 |
2365 ### magzero_x
2367 Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed.
2369 | Default | Min | Max |
2370 | --- | --- | --- |
2371 | 0 | -32768 | 32767 |
2375 ### magzero_y
2377 Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed.
2379 | Default | Min | Max |
2380 | --- | --- | --- |
2381 | 0 | -32768 | 32767 |
2385 ### magzero_z
2387 Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed.
2389 | Default | Min | Max |
2390 | --- | --- | --- |
2391 | 0 | -32768 | 32767 |
2395 ### manual_pitch_rate
2397 Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%
2399 | Default | Min | Max |
2400 | --- | --- | --- |
2401 | 100 | 0 | 100 |
2405 ### manual_rc_expo
2407 Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]
2409 | Default | Min | Max |
2410 | --- | --- | --- |
2411 | 70 | 0 | 100 |
2415 ### manual_rc_yaw_expo
2417 Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]
2419 | Default | Min | Max |
2420 | --- | --- | --- |
2421 | 20 | 0 | 100 |
2425 ### manual_roll_rate
2427 Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%
2429 | Default | Min | Max |
2430 | --- | --- | --- |
2431 | 100 | 0 | 100 |
2435 ### manual_yaw_rate
2437 Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%
2439 | Default | Min | Max |
2440 | --- | --- | --- |
2441 | 100 | 0 | 100 |
2445 ### mavlink_ext_status_rate
2447 _// TODO_
2449 | Default | Min | Max |
2450 | --- | --- | --- |
2451 | 2 | 0 | 255 |
2455 ### mavlink_extra1_rate
2457 _// TODO_
2459 | Default | Min | Max |
2460 | --- | --- | --- |
2461 | 10 | 0 | 255 |
2465 ### mavlink_extra2_rate
2467 _// TODO_
2469 | Default | Min | Max |
2470 | --- | --- | --- |
2471 | 2 | 0 | 255 |
2475 ### mavlink_extra3_rate
2477 _// TODO_
2479 | Default | Min | Max |
2480 | --- | --- | --- |
2481 | 1 | 0 | 255 |
2485 ### mavlink_pos_rate
2487 _// TODO_
2489 | Default | Min | Max |
2490 | --- | --- | --- |
2491 | 2 | 0 | 255 |
2495 ### mavlink_rc_chan_rate
2497 _// TODO_
2499 | Default | Min | Max |
2500 | --- | --- | --- |
2501 | 5 | 0 | 255 |
2505 ### mavlink_version
2507 Version of MAVLink to use
2509 | Default | Min | Max |
2510 | --- | --- | --- |
2511 | 2 | 1 | 2 |
2515 ### max_angle_inclination_pit
2517 Maximum inclination in level (angle) mode (PITCH axis). 100=10°
2519 | Default | Min | Max |
2520 | --- | --- | --- |
2521 | 300 | 100 | 900 |
2525 ### max_angle_inclination_rll
2527 Maximum inclination in level (angle) mode (ROLL axis). 100=10°
2529 | Default | Min | Max |
2530 | --- | --- | --- |
2531 | 300 | 100 | 900 |
2535 ### max_check
2537 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.
2539 | Default | Min | Max |
2540 | --- | --- | --- |
2541 | 1900 | PWM_RANGE_MIN | PWM_RANGE_MAX |
2545 ### max_throttle
2547 This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000.
2549 | Default | Min | Max |
2550 | --- | --- | --- |
2551 | 1850 | PWM_RANGE_MIN | PWM_RANGE_MAX |
2555 ### mc_cd_lpf_hz
2557 Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky
2559 | Default | Min | Max |
2560 | --- | --- | --- |
2561 | 30 | 0 | 200 |
2565 ### mc_cd_pitch
2567 Multicopter Control Derivative gain for PITCH
2569 | Default | Min | Max |
2570 | --- | --- | --- |
2571 | 60 | 0 | 255 |
2575 ### mc_cd_roll
2577 Multicopter Control Derivative gain for ROLL
2579 | Default | Min | Max |
2580 | --- | --- | --- |
2581 | 60 | 0 | 255 |
2585 ### mc_cd_yaw
2587 Multicopter Control Derivative gain for YAW
2589 | Default | Min | Max |
2590 | --- | --- | --- |
2591 | 60 | 0 | 255 |
2595 ### mc_d_level
2597 Multicopter attitude stabilisation HORIZON transition point
2599 | Default | Min | Max |
2600 | --- | --- | --- |
2601 | 75 | 0 | 255 |
2605 ### mc_d_pitch
2607 Multicopter rate stabilisation D-gain for PITCH
2609 | Default | Min | Max |
2610 | --- | --- | --- |
2611 | 23 | 0 | 255 |
2615 ### mc_d_roll
2617 Multicopter rate stabilisation D-gain for ROLL
2619 | Default | Min | Max |
2620 | --- | --- | --- |
2621 | 23 | 0 | 255 |
2625 ### mc_d_yaw
2627 Multicopter rate stabilisation D-gain for YAW
2629 | Default | Min | Max |
2630 | --- | --- | --- |
2631 | 0 | 0 | 255 |
2635 ### mc_i_level
2637 Multicopter attitude stabilisation low-pass filter cutoff
2639 | Default | Min | Max |
2640 | --- | --- | --- |
2641 | 15 | 0 | 255 |
2645 ### mc_i_pitch
2647 Multicopter rate stabilisation I-gain for PITCH
2649 | Default | Min | Max |
2650 | --- | --- | --- |
2651 | 30 | 0 | 255 |
2655 ### mc_i_roll
2657 Multicopter rate stabilisation I-gain for ROLL
2659 | Default | Min | Max |
2660 | --- | --- | --- |
2661 | 30 | 0 | 255 |
2665 ### mc_i_yaw
2667 Multicopter rate stabilisation I-gain for YAW
2669 | Default | Min | Max |
2670 | --- | --- | --- |
2671 | 45 | 0 | 255 |
2675 ### mc_iterm_relax
2677 _// TODO_
2679 | Default | Min | Max |
2680 | --- | --- | --- |
2681 | RP |  |  |
2685 ### mc_iterm_relax_cutoff
2687 _// TODO_
2689 | Default | Min | Max |
2690 | --- | --- | --- |
2691 | 15 | 1 | 100 |
2695 ### mc_p_level
2697 Multicopter attitude stabilisation P-gain
2699 | Default | Min | Max |
2700 | --- | --- | --- |
2701 | 20 | 0 | 255 |
2705 ### mc_p_pitch
2707 Multicopter rate stabilisation P-gain for PITCH
2709 | Default | Min | Max |
2710 | --- | --- | --- |
2711 | 40 | 0 | 255 |
2715 ### mc_p_roll
2717 Multicopter rate stabilisation P-gain for ROLL
2719 | Default | Min | Max |
2720 | --- | --- | --- |
2721 | 40 | 0 | 255 |
2725 ### mc_p_yaw
2727 Multicopter rate stabilisation P-gain for YAW
2729 | Default | Min | Max |
2730 | --- | --- | --- |
2731 | 85 | 0 | 255 |
2735 ### min_check
2737 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.
2739 | Default | Min | Max |
2740 | --- | --- | --- |
2741 | 1100 | PWM_RANGE_MIN | PWM_RANGE_MAX |
2745 ### min_command
2747 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.
2749 | Default | Min | Max |
2750 | --- | --- | --- |
2751 | 1000 | 0 | PWM_RANGE_MAX |
2755 ### mode_range_logic_operator
2757 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.
2759 | Default | Min | Max |
2760 | --- | --- | --- |
2761 | OR |  |  |
2765 ### model_preview_type
2767 ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons.
2769 | Default | Min | Max |
2770 | --- | --- | --- |
2771 | -1 | -1 | 32767 |
2775 ### moron_threshold
2777 When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered.
2779 | Default | Min | Max |
2780 | --- | --- | --- |
2781 | 32 |  | 128 |
2785 ### motor_accel_time
2787 Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]
2789 | Default | Min | Max |
2790 | --- | --- | --- |
2791 | 0 | 0 | 1000 |
2795 ### motor_decel_time
2797 Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]
2799 | Default | Min | Max |
2800 | --- | --- | --- |
2801 | 0 | 0 | 1000 |
2805 ### motor_direction_inverted
2807 Use if you need to inverse yaw motor direction.
2809 | Default | Min | Max |
2810 | --- | --- | --- |
2811 | OFF |  |  |
2815 ### motor_poles
2817 The number of motor poles. Required to compute motor RPM
2819 | Default | Min | Max |
2820 | --- | --- | --- |
2821 | 14 | 4 | 255 |
2825 ### motor_pwm_protocol
2827 Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED
2829 | Default | Min | Max |
2830 | --- | --- | --- |
2831 | ONESHOT125 |  |  |
2835 ### motor_pwm_rate
2837 Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000.
2839 | Default | Min | Max |
2840 | --- | --- | --- |
2841 | 400 | 50 | 32000 |
2845 ### msp_override_channels
2847 Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode.
2849 | Default | Min | Max |
2850 | --- | --- | --- |
2851 | 0 | 0 | 65535 |
2855 ### name
2857 Craft name
2859 | Default | Min | Max |
2860 | --- | --- | --- |
2861 | _empty_ |  |  |
2865 ### nav_auto_climb_rate
2867 Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]
2869 | Default | Min | Max |
2870 | --- | --- | --- |
2871 | 500 | 10 | 2000 |
2875 ### nav_auto_speed
2877 Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]
2879 | Default | Min | Max |
2880 | --- | --- | --- |
2881 | 300 | 10 | 2000 |
2885 ### nav_disarm_on_landing
2887 If set to ON, iNav disarms the FC after landing
2889 | Default | Min | Max |
2890 | --- | --- | --- |
2891 | OFF |  |  |
2895 ### nav_emerg_landing_speed
2897 Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]
2899 | Default | Min | Max |
2900 | --- | --- | --- |
2901 | 500 | 100 | 2000 |
2905 ### nav_extra_arming_safety
2907 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
2909 | Default | Min | Max |
2910 | --- | --- | --- |
2911 | ON |  |  |
2915 ### nav_fw_allow_manual_thr_increase
2917 Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing
2919 | Default | Min | Max |
2920 | --- | --- | --- |
2921 | OFF |  |  |
2925 ### nav_fw_bank_angle
2927 Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll
2929 | Default | Min | Max |
2930 | --- | --- | --- |
2931 | 35 | 5 | 80 |
2935 ### nav_fw_climb_angle
2937 Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit
2939 | Default | Min | Max |
2940 | --- | --- | --- |
2941 | 20 | 5 | 80 |
2945 ### nav_fw_control_smoothness
2947 How smoothly the autopilot controls the airplane to correct the navigation error
2949 | Default | Min | Max |
2950 | --- | --- | --- |
2951 | 0 | 0 | 9 |
2955 ### nav_fw_cruise_speed
2957 Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s
2959 | Default | Min | Max |
2960 | --- | --- | --- |
2961 | 0 | 0 | 65535 |
2965 ### nav_fw_cruise_thr
2967 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 )
2969 | Default | Min | Max |
2970 | --- | --- | --- |
2971 | 1400 | 1000 | 2000 |
2975 ### nav_fw_cruise_yaw_rate
2977 Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]
2979 | Default | Min | Max |
2980 | --- | --- | --- |
2981 | 20 | 0 | 60 |
2985 ### nav_fw_dive_angle
2987 Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit
2989 | Default | Min | Max |
2990 | --- | --- | --- |
2991 | 15 | 5 | 80 |
2995 ### nav_fw_heading_p
2997 P gain of Heading Hold controller (Fixedwing)
2999 | Default | Min | Max |
3000 | --- | --- | --- |
3001 | 60 | 0 | 255 |
3005 ### nav_fw_land_dive_angle
3007 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
3009 | Default | Min | Max |
3010 | --- | --- | --- |
3011 | 2 | -20 | 20 |
3015 ### nav_fw_launch_accel
3017 Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s
3019 | Default | Min | Max |
3020 | --- | --- | --- |
3021 | 1863 | 1000 | 20000 |
3025 ### nav_fw_launch_climb_angle
3027 Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit
3029 | Default | Min | Max |
3030 | --- | --- | --- |
3031 | 18 | 5 | 45 |
3035 ### nav_fw_launch_detect_time
3037 Time for which thresholds have to breached to consider launch happened [ms]
3039 | Default | Min | Max |
3040 | --- | --- | --- |
3041 | 40 | 10 | 1000 |
3045 ### nav_fw_launch_end_time
3047 Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]
3049 | Default | Min | Max |
3050 | --- | --- | --- |
3051 | 3000 | 0 | 5000 |
3055 ### nav_fw_launch_idle_motor_delay
3057 Delay between raising throttle and motor starting at idle throttle (ms)
3059 | Default | Min | Max |
3060 | --- | --- | --- |
3061 | 0 | 0 | 60000 |
3065 ### nav_fw_launch_idle_thr
3067 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)
3069 | Default | Min | Max |
3070 | --- | --- | --- |
3071 | 1000 | 1000 | 2000 |
3075 ### nav_fw_launch_max_altitude
3077 Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000].
3079 | Default | Min | Max |
3080 | --- | --- | --- |
3081 | 0 | 0 | 60000 |
3085 ### nav_fw_launch_max_angle
3087 Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]
3089 | Default | Min | Max |
3090 | --- | --- | --- |
3091 | 45 | 5 | 180 |
3095 ### nav_fw_launch_min_time
3097 Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000].
3099 | Default | Min | Max |
3100 | --- | --- | --- |
3101 | 0 | 0 | 60000 |
3105 ### nav_fw_launch_motor_delay
3107 Delay between detected launch and launch sequence start and throttling up (ms)
3109 | Default | Min | Max |
3110 | --- | --- | --- |
3111 | 500 | 0 | 5000 |
3115 ### nav_fw_launch_spinup_time
3117 Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller
3119 | Default | Min | Max |
3120 | --- | --- | --- |
3121 | 100 | 0 | 1000 |
3125 ### nav_fw_launch_thr
3127 Launch throttle - throttle to be set during launch sequence (pwm units)
3129 | Default | Min | Max |
3130 | --- | --- | --- |
3131 | 1700 | 1000 | 2000 |
3135 ### nav_fw_launch_timeout
3137 Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)
3139 | Default | Min | Max |
3140 | --- | --- | --- |
3141 | 5000 |  | 60000 |
3145 ### nav_fw_launch_velocity
3147 Forward velocity threshold for swing-launch detection [cm/s]
3149 | Default | Min | Max |
3150 | --- | --- | --- |
3151 | 300 | 100 | 10000 |
3155 ### nav_fw_loiter_radius
3157 PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]
3159 | Default | Min | Max |
3160 | --- | --- | --- |
3161 | 7500 | 0 | 30000 |
3165 ### nav_fw_max_thr
3167 Maximum throttle for flying wing in GPS assisted modes
3169 | Default | Min | Max |
3170 | --- | --- | --- |
3171 | 1700 | 1000 | 2000 |
3175 ### nav_fw_min_thr
3177 Minimum throttle for flying wing in GPS assisted modes
3179 | Default | Min | Max |
3180 | --- | --- | --- |
3181 | 1200 | 1000 | 2000 |
3185 ### nav_fw_pitch2thr
3187 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)
3189 | Default | Min | Max |
3190 | --- | --- | --- |
3191 | 10 | 0 | 100 |
3195 ### nav_fw_pitch2thr_smoothing
3197 How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh.
3199 | Default | Min | Max |
3200 | --- | --- | --- |
3201 | 6 | 0 | 9 |
3205 ### nav_fw_pitch2thr_threshold
3207 Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]
3209 | Default | Min | Max |
3210 | --- | --- | --- |
3211 | 50 | 0 | 900 |
3215 ### nav_fw_pos_hdg_d
3217 D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)
3219 | Default | Min | Max |
3220 | --- | --- | --- |
3221 | 0 | 0 | 255 |
3225 ### nav_fw_pos_hdg_i
3227 I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)
3229 | Default | Min | Max |
3230 | --- | --- | --- |
3231 | 2 | 0 | 255 |
3235 ### nav_fw_pos_hdg_p
3237 P gain of heading PID controller. (Fixedwing, rovers, boats)
3239 | Default | Min | Max |
3240 | --- | --- | --- |
3241 | 30 | 0 | 255 |
3245 ### nav_fw_pos_hdg_pidsum_limit
3247 Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)
3249 | Default | Min | Max |
3250 | --- | --- | --- |
3251 | 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX |
3255 ### nav_fw_pos_xy_d
3257 D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero
3259 | Default | Min | Max |
3260 | --- | --- | --- |
3261 | 8 | 0 | 255 |
3265 ### nav_fw_pos_xy_i
3267 I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero
3269 | Default | Min | Max |
3270 | --- | --- | --- |
3271 | 5 | 0 | 255 |
3275 ### nav_fw_pos_xy_p
3277 P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH
3279 | Default | Min | Max |
3280 | --- | --- | --- |
3281 | 75 | 0 | 255 |
3285 ### nav_fw_pos_z_d
3287 D gain of altitude PID controller (Fixedwing)
3289 | Default | Min | Max |
3290 | --- | --- | --- |
3291 | 10 | 0 | 255 |
3295 ### nav_fw_pos_z_i
3297 I gain of altitude PID controller (Fixedwing)
3299 | Default | Min | Max |
3300 | --- | --- | --- |
3301 | 5 | 0 | 255 |
3305 ### nav_fw_pos_z_p
3307 P gain of altitude PID controller (Fixedwing)
3309 | Default | Min | Max |
3310 | --- | --- | --- |
3311 | 40 | 0 | 255 |
3315 ### nav_fw_yaw_deadband
3317 Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course
3319 | Default | Min | Max |
3320 | --- | --- | --- |
3321 | 0 | 0 | 90 |
3325 ### nav_land_maxalt_vspd
3327 Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]
3329 | Default | Min | Max |
3330 | --- | --- | --- |
3331 | 200 | 100 | 2000 |
3335 ### nav_land_minalt_vspd
3337 Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]
3339 | Default | Min | Max |
3340 | --- | --- | --- |
3341 | 50 | 50 | 500 |
3345 ### nav_land_slowdown_maxalt
3347 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]
3349 | Default | Min | Max |
3350 | --- | --- | --- |
3351 | 2000 | 500 | 4000 |
3355 ### nav_land_slowdown_minalt
3357 Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]
3359 | Default | Min | Max |
3360 | --- | --- | --- |
3361 | 500 | 50 | 1000 |
3365 ### nav_manual_climb_rate
3367 Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]
3369 | Default | Min | Max |
3370 | --- | --- | --- |
3371 | 200 | 10 | 2000 |
3375 ### nav_manual_speed
3377 Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]
3379 | Default | Min | Max |
3380 | --- | --- | --- |
3381 | 500 | 10 | 2000 |
3385 ### nav_max_altitude
3387 Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled
3389 | Default | Min | Max |
3390 | --- | --- | --- |
3391 | 0 | 0 | 65000 |
3395 ### nav_max_terrain_follow_alt
3397 Max allowed above the ground altitude for terrain following mode
3399 | Default | Min | Max |
3400 | --- | --- | --- |
3401 | 100 |  | 1000 |
3405 ### nav_mc_auto_disarm_delay
3407 Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)
3409 | Default | Min | Max |
3410 | --- | --- | --- |
3411 | 2000 | 100 | 10000 |
3415 ### nav_mc_bank_angle
3417 Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude
3419 | Default | Min | Max |
3420 | --- | --- | --- |
3421 | 30 | 15 | 45 |
3425 ### nav_mc_braking_bank_angle
3427 max angle that MR is allowed to bank in BOOST mode
3429 | Default | Min | Max |
3430 | --- | --- | --- |
3431 | 40 | 15 | 60 |
3435 ### nav_mc_braking_boost_disengage_speed
3437 BOOST will be disabled when speed goes below this value
3439 | Default | Min | Max |
3440 | --- | --- | --- |
3441 | 100 | 0 | 1000 |
3445 ### nav_mc_braking_boost_factor
3447 acceleration factor for BOOST phase
3449 | Default | Min | Max |
3450 | --- | --- | --- |
3451 | 100 | 0 | 200 |
3455 ### nav_mc_braking_boost_speed_threshold
3457 BOOST can be enabled when speed is above this value
3459 | Default | Min | Max |
3460 | --- | --- | --- |
3461 | 150 | 100 | 1000 |
3465 ### nav_mc_braking_boost_timeout
3467 how long in ms BOOST phase can happen
3469 | Default | Min | Max |
3470 | --- | --- | --- |
3471 | 750 | 0 | 5000 |
3475 ### nav_mc_braking_disengage_speed
3477 braking is disabled when speed goes below this value
3479 | Default | Min | Max |
3480 | --- | --- | --- |
3481 | 75 | 0 | 1000 |
3485 ### nav_mc_braking_speed_threshold
3487 min speed in cm/s above which braking can happen
3489 | Default | Min | Max |
3490 | --- | --- | --- |
3491 | 100 | 0 | 1000 |
3495 ### nav_mc_braking_timeout
3497 timeout in ms for braking
3499 | Default | Min | Max |
3500 | --- | --- | --- |
3501 | 2000 | 100 | 5000 |
3505 ### nav_mc_heading_p
3507 P gain of Heading Hold controller (Multirotor)
3509 | Default | Min | Max |
3510 | --- | --- | --- |
3511 | 60 | 0 | 255 |
3515 ### nav_mc_hover_thr
3517 Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering.
3519 | Default | Min | Max |
3520 | --- | --- | --- |
3521 | 1500 | 1000 | 2000 |
3525 ### nav_mc_pos_deceleration_time
3527 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
3529 | Default | Min | Max |
3530 | --- | --- | --- |
3531 | 120 | 0 | 255 |
3535 ### nav_mc_pos_expo
3537 Expo for PosHold control
3539 | Default | Min | Max |
3540 | --- | --- | --- |
3541 | 10 | 0 | 255 |
3545 ### nav_mc_pos_xy_p
3547 Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity
3549 | Default | Min | Max |
3550 | --- | --- | --- |
3551 | 65 | 0 | 255 |
3555 ### nav_mc_pos_z_p
3557 P gain of altitude PID controller (Multirotor)
3559 | Default | Min | Max |
3560 | --- | --- | --- |
3561 | 50 | 0 | 255 |
3565 ### nav_mc_vel_xy_d
3567 D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target.
3569 | Default | Min | Max |
3570 | --- | --- | --- |
3571 | 100 | 0 | 255 |
3575 ### nav_mc_vel_xy_dterm_attenuation
3577 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.
3579 | Default | Min | Max |
3580 | --- | --- | --- |
3581 | 90 | 0 | 100 |
3585 ### nav_mc_vel_xy_dterm_attenuation_end
3587 A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum
3589 | Default | Min | Max |
3590 | --- | --- | --- |
3591 | 60 | 0 | 100 |
3595 ### nav_mc_vel_xy_dterm_attenuation_start
3597 A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins
3599 | Default | Min | Max |
3600 | --- | --- | --- |
3601 | 10 | 0 | 100 |
3605 ### nav_mc_vel_xy_dterm_lpf_hz
3607 _// TODO_
3609 | Default | Min | Max |
3610 | --- | --- | --- |
3611 | 2 | 0 | 100 |
3615 ### nav_mc_vel_xy_ff
3617 _// TODO_
3619 | Default | Min | Max |
3620 | --- | --- | --- |
3621 | 40 | 0 | 255 |
3625 ### nav_mc_vel_xy_i
3627 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
3629 | Default | Min | Max |
3630 | --- | --- | --- |
3631 | 15 | 0 | 255 |
3635 ### nav_mc_vel_xy_p
3637 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
3639 | Default | Min | Max |
3640 | --- | --- | --- |
3641 | 40 | 0 | 255 |
3645 ### nav_mc_vel_z_d
3647 D gain of velocity PID controller
3649 | Default | Min | Max |
3650 | --- | --- | --- |
3651 | 10 | 0 | 255 |
3655 ### nav_mc_vel_z_i
3657 I gain of velocity PID controller
3659 | Default | Min | Max |
3660 | --- | --- | --- |
3661 | 50 | 0 | 255 |
3665 ### nav_mc_vel_z_p
3667 P gain of velocity PID controller
3669 | Default | Min | Max |
3670 | --- | --- | --- |
3671 | 100 | 0 | 255 |
3675 ### nav_mc_wp_slowdown
3677 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.
3679 | Default | Min | Max |
3680 | --- | --- | --- |
3681 | ON |  |  |
3685 ### nav_min_rth_distance
3687 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.
3689 | Default | Min | Max |
3690 | --- | --- | --- |
3691 | 500 | 0 | 5000 |
3695 ### nav_overrides_motor_stop
3697 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
3699 | Default | Min | Max |
3700 | --- | --- | --- |
3701 | ALL_NAV |  |  |
3705 ### nav_position_timeout
3707 If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)
3709 | Default | Min | Max |
3710 | --- | --- | --- |
3711 | 5 | 0 | 10 |
3715 ### nav_rth_abort_threshold
3717 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. [cm]
3719 | Default | Min | Max |
3720 | --- | --- | --- |
3721 | 50000 |  | 65000 |
3725 ### nav_rth_allow_landing
3727 If set to ON drone will land as a last phase of RTH.
3729 | Default | Min | Max |
3730 | --- | --- | --- |
3731 | ALWAYS |  |  |
3735 ### nav_rth_alt_control_override
3737 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)
3739 | Default | Min | Max |
3740 | --- | --- | --- |
3741 | OFF |  |  |
3745 ### nav_rth_alt_mode
3747 Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details
3749 | Default | Min | Max |
3750 | --- | --- | --- |
3751 | AT_LEAST |  |  |
3755 ### nav_rth_altitude
3757 Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)
3759 | Default | Min | Max |
3760 | --- | --- | --- |
3761 | 1000 |  | 65000 |
3765 ### nav_rth_climb_first
3767 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)
3769 | Default | Min | Max |
3770 | --- | --- | --- |
3771 | ON |  |  |
3775 ### nav_rth_climb_ignore_emerg
3777 If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status.
3779 | Default | Min | Max |
3780 | --- | --- | --- |
3781 | OFF |  |  |
3785 ### nav_rth_home_altitude
3787 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]
3789 | Default | Min | Max |
3790 | --- | --- | --- |
3791 | 0 |  | 65000 |
3795 ### nav_rth_tail_first
3797 If set to ON drone will return tail-first. Obviously meaningless for airplanes.
3799 | Default | Min | Max |
3800 | --- | --- | --- |
3801 | OFF |  |  |
3805 ### nav_use_fw_yaw_control
3807 Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats
3809 | Default | Min | Max |
3810 | --- | --- | --- |
3811 | OFF |  |  |
3815 ### nav_use_midthr_for_althold
3817 If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude
3819 | Default | Min | Max |
3820 | --- | --- | --- |
3821 | OFF |  |  |
3825 ### nav_user_control_mode
3827 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.
3829 | Default | Min | Max |
3830 | --- | --- | --- |
3831 | ATTI |  |  |
3835 ### nav_wp_load_on_boot
3837 If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup.
3839 | Default | Min | Max |
3840 | --- | --- | --- |
3841 | OFF |  |  |
3845 ### nav_wp_radius
3847 Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius
3849 | Default | Min | Max |
3850 | --- | --- | --- |
3851 | 100 | 10 | 10000 |
3855 ### nav_wp_safe_distance
3857 First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check.
3859 | Default | Min | Max |
3860 | --- | --- | --- |
3861 | 10000 |  | 65000 |
3865 ### opflow_hardware
3867 Selection of OPFLOW hardware.
3869 | Default | Min | Max |
3870 | --- | --- | --- |
3871 | NONE |  |  |
3875 ### opflow_scale
3877 _// TODO_
3879 | Default | Min | Max |
3880 | --- | --- | --- |
3881 | 10.5 | 0 | 10000 |
3885 ### osd_ahi_bordered
3887 Shows a border/corners around the AHI region (pixel OSD only)
3889 | Default | Min | Max |
3890 | --- | --- | --- |
3891 | OFF |  |  |
3895 ### osd_ahi_camera_uptilt_comp
3897 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).
3899 | Default | Min | Max |
3900 | --- | --- | --- |
3901 | OFF |  |  |
3905 ### osd_ahi_height
3907 AHI height in pixels (pixel OSD only)
3909 | Default | Min | Max |
3910 | --- | --- | --- |
3911 | 162 |  | 255 |
3915 ### osd_ahi_max_pitch
3917 Max pitch, in degrees, for OSD artificial horizon
3919 | Default | Min | Max |
3920 | --- | --- | --- |
3921 | 20 | 10 | 90 |
3925 ### osd_ahi_reverse_roll
3927 _// TODO_
3929 | Default | Min | Max |
3930 | --- | --- | --- |
3931 | OFF |  |  |
3935 ### osd_ahi_style
3937 Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD.
3939 | Default | Min | Max |
3940 | --- | --- | --- |
3941 | DEFAULT |  |  |
3945 ### osd_ahi_vertical_offset
3947 AHI vertical offset from center (pixel OSD only)
3949 | Default | Min | Max |
3950 | --- | --- | --- |
3951 | -18 | -128 | 127 |
3955 ### osd_ahi_width
3957 AHI width in pixels (pixel OSD only)
3959 | Default | Min | Max |
3960 | --- | --- | --- |
3961 | 132 |  | 255 |
3965 ### osd_alt_alarm
3967 Value above which to make the OSD relative altitude indicator blink (meters)
3969 | Default | Min | Max |
3970 | --- | --- | --- |
3971 | 100 | 0 | 10000 |
3975 ### osd_baro_temp_alarm_max
3977 Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)
3979 | Default | Min | Max |
3980 | --- | --- | --- |
3981 | 600 | -550 | 1250 |
3985 ### osd_baro_temp_alarm_min
3987 Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)
3989 | Default | Min | Max |
3990 | --- | --- | --- |
3991 | -200 | -550 | 1250 |
3995 ### osd_camera_fov_h
3997 Horizontal field of view for the camera in degres
3999 | Default | Min | Max |
4000 | --- | --- | --- |
4001 | 135 | 60 | 150 |
4005 ### osd_camera_fov_v
4007 Vertical field of view for the camera in degres
4009 | Default | Min | Max |
4010 | --- | --- | --- |
4011 | 85 | 30 | 120 |
4015 ### osd_camera_uptilt
4017 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).
4019 | Default | Min | Max |
4020 | --- | --- | --- |
4021 | 0 | -40 | 80 |
4025 ### osd_coordinate_digits
4027 _// TODO_
4029 | Default | Min | Max |
4030 | --- | --- | --- |
4031 | 9 | 8 | 11 |
4035 ### osd_crosshairs_style
4037 To set the visual type for the crosshair
4039 | Default | Min | Max |
4040 | --- | --- | --- |
4041 | DEFAULT |  |  |
4045 ### osd_crsf_lq_format
4047 To select LQ format
4049 | Default | Min | Max |
4050 | --- | --- | --- |
4051 | TYPE1 |  |  |
4055 ### osd_current_alarm
4057 Value above which the OSD current consumption element will start blinking. Measured in full Amperes.
4059 | Default | Min | Max |
4060 | --- | --- | --- |
4061 | 0 | 0 | 255 |
4065 ### osd_dist_alarm
4067 Value above which to make the OSD distance from home indicator blink (meters)
4069 | Default | Min | Max |
4070 | --- | --- | --- |
4071 | 1000 | 0 | 50000 |
4075 ### osd_esc_temp_alarm_max
4077 Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)
4079 | Default | Min | Max |
4080 | --- | --- | --- |
4081 | 900 | -550 | 1500 |
4085 ### osd_esc_temp_alarm_min
4087 Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)
4089 | Default | Min | Max |
4090 | --- | --- | --- |
4091 | -200 | -550 | 1500 |
4095 ### osd_estimations_wind_compensation
4097 Use wind estimation for remaining flight time/distance estimation
4099 | Default | Min | Max |
4100 | --- | --- | --- |
4101 | ON |  |  |
4105 ### osd_failsafe_switch_layout
4107 If enabled the OSD automatically switches to the first layout during failsafe
4109 | Default | Min | Max |
4110 | --- | --- | --- |
4111 | OFF |  |  |
4115 ### osd_force_grid
4117 Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
4119 | Default | Min | Max |
4120 | --- | --- | --- |
4121 | OFF |  |  |
4125 ### osd_gforce_alarm
4127 Value above which the OSD g force indicator will blink (g)
4129 | Default | Min | Max |
4130 | --- | --- | --- |
4131 | 5 | 0 | 20 |
4135 ### osd_gforce_axis_alarm_max
4137 Value above which the OSD axis g force indicators will blink (g)
4139 | Default | Min | Max |
4140 | --- | --- | --- |
4141 | 5 | -20 | 20 |
4145 ### osd_gforce_axis_alarm_min
4147 Value under which the OSD axis g force indicators will blink (g)
4149 | Default | Min | Max |
4150 | --- | --- | --- |
4151 | -5 | -20 | 20 |
4155 ### osd_home_position_arm_screen
4157 Should home position coordinates be displayed on the arming screen.
4159 | Default | Min | Max |
4160 | --- | --- | --- |
4161 | ON |  |  |
4165 ### osd_horizon_offset
4167 To vertically adjust the whole OSD and AHI and scrolling bars
4169 | Default | Min | Max |
4170 | --- | --- | --- |
4171 | 0 | -2 | 2 |
4175 ### osd_hud_homepoint
4177 To 3D-display the home point location in the hud
4179 | Default | Min | Max |
4180 | --- | --- | --- |
4181 | OFF |  |  |
4185 ### osd_hud_homing
4187 To display little arrows around the crossair showing where the home point is in the hud
4189 | Default | Min | Max |
4190 | --- | --- | --- |
4191 | OFF |  |  |
4195 ### osd_hud_margin_h
4197 Left and right margins for the hud area
4199 | Default | Min | Max |
4200 | --- | --- | --- |
4201 | 3 | 0 | 4 |
4205 ### osd_hud_margin_v
4207 Top and bottom margins for the hud area
4209 | Default | Min | Max |
4210 | --- | --- | --- |
4211 | 3 | 1 | 3 |
4215 ### osd_hud_radar_disp
4217 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
4219 | Default | Min | Max |
4220 | --- | --- | --- |
4221 | 0 | 0 | 4 |
4225 ### osd_hud_radar_nearest
4227 To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in Â°, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable.
4229 | Default | Min | Max |
4230 | --- | --- | --- |
4231 | 0 | 0 | 4000 |
4235 ### osd_hud_radar_range_max
4237 In meters, radar aircrafts further away than this will not be displayed in the hud
4239 | Default | Min | Max |
4240 | --- | --- | --- |
4241 | 4000 | 100 | 9990 |
4245 ### osd_hud_radar_range_min
4247 In meters, radar aircrafts closer than this will not be displayed in the hud
4249 | Default | Min | Max |
4250 | --- | --- | --- |
4251 | 3 | 1 | 30 |
4255 ### osd_hud_wp_disp
4257 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)
4259 | Default | Min | Max |
4260 | --- | --- | --- |
4261 | 0 | 0 | 3 |
4265 ### osd_imu_temp_alarm_max
4267 Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)
4269 | Default | Min | Max |
4270 | --- | --- | --- |
4271 | 600 | -550 | 1250 |
4275 ### osd_imu_temp_alarm_min
4277 Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)
4279 | Default | Min | Max |
4280 | --- | --- | --- |
4281 | -200 | -550 | 1250 |
4285 ### osd_left_sidebar_scroll
4287 _// TODO_
4289 | Default | Min | Max |
4290 | --- | --- | --- |
4291 | NONE |  |  |
4295 ### osd_left_sidebar_scroll_step
4297 How many units each sidebar step represents. 0 means the default value for the scroll type.
4299 | Default | Min | Max |
4300 | --- | --- | --- |
4301 | 0 |  | 255 |
4305 ### osd_link_quality_alarm
4307 LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%
4309 | Default | Min | Max |
4310 | --- | --- | --- |
4311 | 70 | 0 | 100 |
4315 ### osd_main_voltage_decimals
4317 Number of decimals for the battery voltages displayed in the OSD [1-2].
4319 | Default | Min | Max |
4320 | --- | --- | --- |
4321 | 1 | 1 | 2 |
4325 ### osd_neg_alt_alarm
4327 Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)
4329 | Default | Min | Max |
4330 | --- | --- | --- |
4331 | 5 | 0 | 10000 |
4335 ### osd_pan_servo_index
4337 Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos.
4339 | Default | Min | Max |
4340 | --- | --- | --- |
4341 | 0 | 0 | 10 |
4345 ### osd_pan_servo_pwm2centideg
4347 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.
4349 | Default | Min | Max |
4350 | --- | --- | --- |
4351 | 0 | -36 | 36 |
4355 ### osd_plus_code_digits
4357 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.
4359 | Default | Min | Max |
4360 | --- | --- | --- |
4361 | 11 | 10 | 13 |
4365 ### osd_plus_code_short
4367 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.
4369 | Default | Min | Max |
4370 | --- | --- | --- |
4371 | 0 |  |  |
4375 ### osd_right_sidebar_scroll
4377 _// TODO_
4379 | Default | Min | Max |
4380 | --- | --- | --- |
4381 | NONE |  |  |
4385 ### osd_right_sidebar_scroll_step
4387 Same as left_sidebar_scroll_step, but for the right sidebar
4389 | Default | Min | Max |
4390 | --- | --- | --- |
4391 | 0 |  | 255 |
4395 ### osd_row_shiftdown
4397 Number of rows to shift the OSD display (increase if top rows are cut off)
4399 | Default | Min | Max |
4400 | --- | --- | --- |
4401 | 0 | 0 | 1 |
4405 ### osd_rssi_alarm
4407 Value below which to make the OSD RSSI indicator blink
4409 | Default | Min | Max |
4410 | --- | --- | --- |
4411 | 20 | 0 | 100 |
4415 ### osd_rssi_dbm_alarm
4417 RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm
4419 | Default | Min | Max |
4420 | --- | --- | --- |
4421 | 0 | -130 | 0 |
4425 ### osd_sidebar_height
4427 Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
4429 | Default | Min | Max |
4430 | --- | --- | --- |
4431 | 3 | 0 | 5 |
4435 ### osd_sidebar_horizontal_offset
4437 Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
4439 | Default | Min | Max |
4440 | --- | --- | --- |
4441 | 0 | -128 | 127 |
4445 ### osd_sidebar_scroll_arrows
4447 _// TODO_
4449 | Default | Min | Max |
4450 | --- | --- | --- |
4451 | OFF |  |  |
4455 ### osd_snr_alarm
4457 Value below which Crossfire SNR Alarm pops-up. (dB)
4459 | Default | Min | Max |
4460 | --- | --- | --- |
4461 | 4 | -20 | 10 |
4465 ### osd_speed_source
4467 Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR
4469 | Default | Min | Max |
4470 | --- | --- | --- |
4471 | GROUND |  |  |
4475 ### osd_stats_energy_unit
4477 Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)
4479 | Default | Min | Max |
4480 | --- | --- | --- |
4481 | MAH |  |  |
4485 ### osd_stats_min_voltage_unit
4487 Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats.
4489 | Default | Min | Max |
4490 | --- | --- | --- |
4491 | BATTERY |  |  |
4495 ### osd_telemetry
4497 To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`
4499 | Default | Min | Max |
4500 | --- | --- | --- |
4501 | OFF |  |  |
4505 ### osd_temp_label_align
4507 Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`
4509 | Default | Min | Max |
4510 | --- | --- | --- |
4511 | LEFT |  |  |
4515 ### osd_time_alarm
4517 Value above which to make the OSD flight time indicator blink (minutes)
4519 | Default | Min | Max |
4520 | --- | --- | --- |
4521 | 10 | 0 | 600 |
4525 ### osd_units
4527 IMPERIAL, METRIC, UK
4529 | Default | Min | Max |
4530 | --- | --- | --- |
4531 | METRIC |  |  |
4535 ### osd_video_system
4537 Video system used. Possible values are `AUTO`, `PAL` and `NTSC`
4539 | Default | Min | Max |
4540 | --- | --- | --- |
4541 | AUTO |  |  |
4545 ### pid_type
4547 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`
4549 | Default | Min | Max |
4550 | --- | --- | --- |
4551 | AUTO |  |  |
4555 ### pidsum_limit
4557 A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help
4559 | Default | Min | Max |
4560 | --- | --- | --- |
4561 | 500 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX |
4565 ### pidsum_limit_yaw
4567 A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help
4569 | Default | Min | Max |
4570 | --- | --- | --- |
4571 | 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX |
4575 ### pinio_box1
4577 Mode assignment for PINIO#1
4579 | Default | Min | Max |
4580 | --- | --- | --- |
4581 | `BOX_PERMANENT_ID_NONE` | 0 | 255 |
4585 ### pinio_box2
4587 Mode assignment for PINIO#1
4589 | Default | Min | Max |
4590 | --- | --- | --- |
4591 | `BOX_PERMANENT_ID_NONE` | 0 | 255 |
4595 ### pinio_box3
4597 Mode assignment for PINIO#1
4599 | Default | Min | Max |
4600 | --- | --- | --- |
4601 | `BOX_PERMANENT_ID_NONE` | 0 | 255 |
4605 ### pinio_box4
4607 Mode assignment for PINIO#1
4609 | Default | Min | Max |
4610 | --- | --- | --- |
4611 | `BOX_PERMANENT_ID_NONE` | 0 | 255 |
4615 ### pitch_rate
4617 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.
4619 | Default | Min | Max |
4620 | --- | --- | --- |
4621 | 20 | 4 | 180 |
4625 ### pitot_hardware
4627 Selection of pitot hardware.
4629 | Default | Min | Max |
4630 | --- | --- | --- |
4631 | NONE |  |  |
4635 ### pitot_lpf_milli_hz
4637 _// TODO_
4639 | Default | Min | Max |
4640 | --- | --- | --- |
4641 | 350 | 0 | 10000 |
4645 ### pitot_scale
4647 _// TODO_
4649 | Default | Min | Max |
4650 | --- | --- | --- |
4651 | 1.0 | 0 | 100 |
4655 ### platform_type
4657 Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented
4659 | Default | Min | Max |
4660 | --- | --- | --- |
4661 | MULTIROTOR |  |  |
4665 ### pos_hold_deadband
4667 Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes.
4669 | Default | Min | Max |
4670 | --- | --- | --- |
4671 | 10 | 2 | 250 |
4675 ### prearm_timeout
4677 Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout.
4679 | Default | Min | Max |
4680 | --- | --- | --- |
4681 | 10000 | 0 | 10000 |
4685 ### rangefinder_hardware
4687 Selection of rangefinder hardware.
4689 | Default | Min | Max |
4690 | --- | --- | --- |
4691 | NONE |  |  |
4695 ### rangefinder_median_filter
4697 3-point median filtering for rangefinder readouts
4699 | Default | Min | Max |
4700 | --- | --- | --- |
4701 | OFF |  |  |
4705 ### rate_accel_limit_roll_pitch
4707 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.
4709 | Default | Min | Max |
4710 | --- | --- | --- |
4711 | 0 |  | 500000 |
4715 ### rate_accel_limit_yaw
4717 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.
4719 | Default | Min | Max |
4720 | --- | --- | --- |
4721 | 10000 |  | 500000 |
4725 ### rc_expo
4727 Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)
4729 | Default | Min | Max |
4730 | --- | --- | --- |
4731 | 70 | 0 | 100 |
4735 ### rc_filter_frequency
4737 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
4739 | Default | Min | Max |
4740 | --- | --- | --- |
4741 | 50 | 0 | 100 |
4745 ### rc_yaw_expo
4747 Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)
4749 | Default | Min | Max |
4750 | --- | --- | --- |
4751 | 20 | 0 | 100 |
4755 ### reboot_character
4757 Special character used to trigger reboot
4759 | Default | Min | Max |
4760 | --- | --- | --- |
4761 | 82 | 48 | 126 |
4765 ### receiver_type
4767 Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`
4769 | Default | Min | Max |
4770 | --- | --- | --- |
4771 | _target default_ |  |  |
4775 ### report_cell_voltage
4777 S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON
4779 | Default | Min | Max |
4780 | --- | --- | --- |
4781 | OFF |  |  |
4785 ### roll_rate
4787 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.
4789 | Default | Min | Max |
4790 | --- | --- | --- |
4791 | 20 | 4 | 180 |
4795 ### rpm_gyro_filter_enabled
4797 Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV
4799 | Default | Min | Max |
4800 | --- | --- | --- |
4801 | OFF |  |  |
4805 ### rpm_gyro_harmonics
4807 Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine
4809 | Default | Min | Max |
4810 | --- | --- | --- |
4811 | 1 | 1 | 3 |
4815 ### rpm_gyro_min_hz
4817 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`
4819 | Default | Min | Max |
4820 | --- | --- | --- |
4821 | 100 | 30 | 200 |
4825 ### rpm_gyro_q
4827 Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting
4829 | Default | Min | Max |
4830 | --- | --- | --- |
4831 | 500 | 1 | 3000 |
4835 ### rssi_adc_channel
4837 ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled
4839 | Default | Min | Max |
4840 | --- | --- | --- |
4841 | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX |
4845 ### rssi_channel
4847 RX channel containing the RSSI signal
4849 | Default | Min | Max |
4850 | --- | --- | --- |
4851 | 0 | 0 | MAX_SUPPORTED_RC_CHANNEL_COUNT |
4855 ### rssi_max
4857 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.
4859 | Default | Min | Max |
4860 | --- | --- | --- |
4861 | 100 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX |
4865 ### rssi_min
4867 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).
4869 | Default | Min | Max |
4870 | --- | --- | --- |
4871 | 0 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX |
4875 ### rssi_source
4877 Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`
4879 | Default | Min | Max |
4880 | --- | --- | --- |
4881 | AUTO |  |  |
4885 ### rth_energy_margin
4887 Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation
4889 | Default | Min | Max |
4890 | --- | --- | --- |
4891 | 5 | 0 | 100 |
4895 ### rx_max_usec
4897 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.
4899 | Default | Min | Max |
4900 | --- | --- | --- |
4901 | 2115 | PWM_PULSE_MIN | PWM_PULSE_MAX |
4905 ### rx_min_usec
4907 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.
4909 | Default | Min | Max |
4910 | --- | --- | --- |
4911 | 885 | PWM_PULSE_MIN | PWM_PULSE_MAX |
4915 ### rx_spi_id
4917 _// TODO_
4919 | Default | Min | Max |
4920 | --- | --- | --- |
4921 | 0 | 0 | 0 |
4925 ### rx_spi_protocol
4927 _// TODO_
4929 | Default | Min | Max |
4930 | --- | --- | --- |
4931 | _target default_ |  |  |
4935 ### rx_spi_rf_channel_count
4937 _// TODO_
4939 | Default | Min | Max |
4940 | --- | --- | --- |
4941 | 0 | 0 | 8 |
4945 ### safehome_max_distance
4947 In order for a safehome to be used, it must be less than this distance (in cm) from the arming point.
4949 | Default | Min | Max |
4950 | --- | --- | --- |
4951 | 20000 | 0 | 65000 |
4955 ### safehome_usage_mode
4957 Used to control when safehomes will be used. Possible values are `OFF`, `RTH` and `RTH_FS`.  See [Safehome documentation](Safehomes.md#Safehome) for more information.
4959 | Default | Min | Max |
4960 | --- | --- | --- |
4961 | RTH |  |  |
4965 ### sbus_sync_interval
4967 _// TODO_
4969 | Default | Min | Max |
4970 | --- | --- | --- |
4971 | 3000 | 500 | 10000 |
4975 ### sdcard_detect_inverted
4977 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.
4979 | Default | Min | Max |
4980 | --- | --- | --- |
4981 | _target default_ |  |  |
4985 ### serialrx_halfduplex
4987 Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire.
4989 | Default | Min | Max |
4990 | --- | --- | --- |
4991 | AUTO |  |  |
4995 ### serialrx_inverted
4997 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).
4999 | Default | Min | Max |
5000 | --- | --- | --- |
5001 | OFF |  |  |
5005 ### serialrx_provider
5007 When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section.
5009 | Default | Min | Max |
5010 | --- | --- | --- |
5011 | _target default_ |  |  |
5015 ### servo_autotrim_rotation_limit
5017 Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`.
5019 | Default | Min | Max |
5020 | --- | --- | --- |
5021 | 15 | 1 | 60 |
5025 ### servo_center_pulse
5027 Servo midpoint
5029 | Default | Min | Max |
5030 | --- | --- | --- |
5031 | 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX |
5035 ### servo_lpf_hz
5037 Selects the servo PWM output cutoff frequency. Value is in [Hz]
5039 | Default | Min | Max |
5040 | --- | --- | --- |
5041 | 20 | 0 | 400 |
5045 ### servo_protocol
5047 An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)
5049 | Default | Min | Max |
5050 | --- | --- | --- |
5051 | PWM |  |  |
5055 ### servo_pwm_rate
5057 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.
5059 | Default | Min | Max |
5060 | --- | --- | --- |
5061 | 50 | 50 | 498 |
5065 ### setpoint_kalman_enabled
5067 Enable Kalman filter on the PID controller setpoint
5069 | Default | Min | Max |
5070 | --- | --- | --- |
5071 | OFF |  |  |
5075 ### setpoint_kalman_q
5077 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
5079 | Default | Min | Max |
5080 | --- | --- | --- |
5081 | 100 | 1 | 16000 |
5085 ### setpoint_kalman_sharpness
5087 Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets
5089 | Default | Min | Max |
5090 | --- | --- | --- |
5091 | 100 | 1 | 16000 |
5095 ### setpoint_kalman_w
5097 Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response
5099 | Default | Min | Max |
5100 | --- | --- | --- |
5101 | 4 | 1 | 40 |
5105 ### sim_ground_station_number
5107 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.
5109 | Default | Min | Max |
5110 | --- | --- | --- |
5111 | _empty_ |  |  |
5115 ### sim_low_altitude
5117 Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`.
5119 | Default | Min | Max |
5120 | --- | --- | --- |
5121 | -32767 | -32768 | 32767 |
5125 ### sim_pin
5127 PIN code for the SIM module
5129 | Default | Min | Max |
5130 | --- | --- | --- |
5131 | 0000 |  |  |
5135 ### sim_transmit_flags
5137 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`
5139 | Default | Min | Max |
5140 | --- | --- | --- |
5141 | `SIM_TX_FLAG_FAILSAFE` |  | 63 |
5145 ### sim_transmit_interval
5147 Text message transmission interval in seconds for SIM module. Minimum value: 10
5149 | Default | Min | Max |
5150 | --- | --- | --- |
5151 | 60 | SIM_MIN_TRANSMIT_INTERVAL | 65535 |
5155 ### small_angle
5157 If the aircraft tilt angle exceed this value the copter will refuse to arm.
5159 | Default | Min | Max |
5160 | --- | --- | --- |
5161 | 25 | 0 | 180 |
5165 ### smartport_fuel_unit
5167 S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]
5169 | Default | Min | Max |
5170 | --- | --- | --- |
5171 | MAH |  |  |
5175 ### smartport_master_halfduplex
5177 _// TODO_
5179 | Default | Min | Max |
5180 | --- | --- | --- |
5181 | ON |  |  |
5185 ### smartport_master_inverted
5187 _// TODO_
5189 | Default | Min | Max |
5190 | --- | --- | --- |
5191 | OFF |  |  |
5195 ### smith_predictor_delay
5197 Expected delay of the gyro signal. In milliseconds
5199 | Default | Min | Max |
5200 | --- | --- | --- |
5201 | 0 | 0 | 8 |
5205 ### smith_predictor_lpf_hz
5207 Cutoff frequency for the Smith Predictor Low Pass Filter
5209 | Default | Min | Max |
5210 | --- | --- | --- |
5211 | 50 | 1 | 500 |
5215 ### smith_predictor_strength
5217 The strength factor of a Smith Predictor of PID measurement. In percents
5219 | Default | Min | Max |
5220 | --- | --- | --- |
5221 | 0.5 | 0 | 1 |
5225 ### spektrum_sat_bind
5227 0 = disabled. Used to bind the spektrum satellite to RX
5229 | Default | Min | Max |
5230 | --- | --- | --- |
5231 | `SPEKTRUM_SAT_BIND_DISABLED` | SPEKTRUM_SAT_BIND_DISABLED | SPEKTRUM_SAT_BIND_MAX |
5235 ### srxl2_baud_fast
5237 _// TODO_
5239 | Default | Min | Max |
5240 | --- | --- | --- |
5241 | ON |  |  |
5245 ### srxl2_unit_id
5247 _// TODO_
5249 | Default | Min | Max |
5250 | --- | --- | --- |
5251 | 1 | 0 | 15 |
5255 ### stats
5257 General switch of the statistics recording feature (a.k.a. odometer)
5259 | Default | Min | Max |
5260 | --- | --- | --- |
5261 | OFF |  |  |
5265 ### stats_total_dist
5267 Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled.
5269 | Default | Min | Max |
5270 | --- | --- | --- |
5271 | 0 |  | 2147483647 |
5275 ### stats_total_energy
5277 _// TODO_
5279 | Default | Min | Max |
5280 | --- | --- | --- |
5281 | 0 |  | 2147483647 |
5285 ### stats_total_time
5287 Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled.
5289 | Default | Min | Max |
5290 | --- | --- | --- |
5291 | 0 |  | 2147483647 |
5295 ### switch_disarm_delay
5297 Delay before disarming when requested by switch (ms) [0-1000]
5299 | Default | Min | Max |
5300 | --- | --- | --- |
5301 | 250 | 0 | 1000 |
5305 ### telemetry_halfduplex
5307 S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details
5309 | Default | Min | Max |
5310 | --- | --- | --- |
5311 | ON |  |  |
5315 ### telemetry_inverted
5317 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.
5319 | Default | Min | Max |
5320 | --- | --- | --- |
5321 | OFF |  |  |
5325 ### telemetry_switch
5327 Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed.
5329 | Default | Min | Max |
5330 | --- | --- | --- |
5331 | OFF |  |  |
5335 ### thr_comp_weight
5337 Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)
5339 | Default | Min | Max |
5340 | --- | --- | --- |
5341 | 1 | 0 | 2 |
5345 ### thr_expo
5347 Throttle exposition value
5349 | Default | Min | Max |
5350 | --- | --- | --- |
5351 | 0 | 0 | 100 |
5355 ### thr_mid
5357 Throttle value when the stick is set to mid-position. Used in the throttle curve calculation.
5359 | Default | Min | Max |
5360 | --- | --- | --- |
5361 | 50 | 0 | 100 |
5365 ### throttle_idle
5367 The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle.
5369 | Default | Min | Max |
5370 | --- | --- | --- |
5371 | 15 | 0 | 30 |
5375 ### throttle_scale
5377 Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%
5379 | Default | Min | Max |
5380 | --- | --- | --- |
5381 | 1.0 | 0 | 1 |
5385 ### throttle_tilt_comp_str
5387 Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled.
5389 | Default | Min | Max |
5390 | --- | --- | --- |
5391 | 0 | 0 | 100 |
5395 ### tpa_breakpoint
5397 See tpa_rate.
5399 | Default | Min | Max |
5400 | --- | --- | --- |
5401 | 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX |
5405 ### tpa_rate
5407 Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate.
5409 | Default | Min | Max |
5410 | --- | --- | --- |
5411 | 0 | 0 | 100 |
5415 ### tri_unarmed_servo
5417 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.
5419 | Default | Min | Max |
5420 | --- | --- | --- |
5421 | ON |  |  |
5425 ### turtle_mode_power_factor
5427 Turtle mode power factor
5429 | Default | Min | Max |
5430 | --- | --- | --- |
5431 | 55 | 0 | 100 |
5435 ### tz_automatic_dst
5437 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`.
5439 | Default | Min | Max |
5440 | --- | --- | --- |
5441 | OFF |  |  |
5445 ### tz_offset
5447 Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs
5449 | Default | Min | Max |
5450 | --- | --- | --- |
5451 | 0 | -1440 | 1440 |
5455 ### vbat_adc_channel
5457 ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled
5459 | Default | Min | Max |
5460 | --- | --- | --- |
5461 | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX |
5465 ### vbat_cell_detect_voltage
5467 Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units.
5469 | Default | Min | Max |
5470 | --- | --- | --- |
5471 | 425 | 100 | 500 |
5475 ### vbat_max_cell_voltage
5477 Maximum voltage per cell in 0.01V units, default is 4.20V
5479 | Default | Min | Max |
5480 | --- | --- | --- |
5481 | 420 | 100 | 500 |
5485 ### vbat_meter_type
5487 Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running
5489 | Default | Min | Max |
5490 | --- | --- | --- |
5491 | ADC |  |  |
5495 ### vbat_min_cell_voltage
5497 Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)
5499 | Default | Min | Max |
5500 | --- | --- | --- |
5501 | 330 | 100 | 500 |
5505 ### vbat_scale
5507 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.
5509 | Default | Min | Max |
5510 | --- | --- | --- |
5511 | _target default_ | VBAT_SCALE_MIN | VBAT_SCALE_MAX |
5515 ### vbat_warning_cell_voltage
5517 Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)
5519 | Default | Min | Max |
5520 | --- | --- | --- |
5521 | 350 | 100 | 500 |
5525 ### vtx_band
5527 Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race.
5529 | Default | Min | Max |
5530 | --- | --- | --- |
5531 | 4 | VTX_SETTINGS_NO_BAND | VTX_SETTINGS_MAX_BAND |
5535 ### vtx_channel
5537 Channel to use within the configured `vtx_band`. Valid values are [1, 8].
5539 | Default | Min | Max |
5540 | --- | --- | --- |
5541 | 1 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL |
5545 ### vtx_halfduplex
5547 Use half duplex UART to communicate with the VTX, using only a TX pin in the FC.
5549 | Default | Min | Max |
5550 | --- | --- | --- |
5551 | ON |  |  |
5555 ### vtx_low_power_disarm
5557 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.
5559 | Default | Min | Max |
5560 | --- | --- | --- |
5561 | OFF |  |  |
5565 ### vtx_max_power_override
5567 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
5569 | Default | Min | Max |
5570 | --- | --- | --- |
5571 | 0 | 0 | 10000 |
5575 ### vtx_pit_mode_chan
5577 _// TODO_
5579 | Default | Min | Max |
5580 | --- | --- | --- |
5581 | 1 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL |
5585 ### vtx_power
5587 VTX RF power level to use. The exact number of mw depends on the VTX hardware.
5589 | Default | Min | Max |
5590 | --- | --- | --- |
5591 | 1 | VTX_SETTINGS_MIN_POWER | VTX_SETTINGS_MAX_POWER |
5595 ### vtx_smartaudio_early_akk_workaround
5597 Enable workaround for early AKK SAudio-enabled VTX bug.
5599 | Default | Min | Max |
5600 | --- | --- | --- |
5601 | ON |  |  |
5605 ### yaw_deadband
5607 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.
5609 | Default | Min | Max |
5610 | --- | --- | --- |
5611 | 5 | 0 | 100 |
5615 ### yaw_lpf_hz
5617 Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)
5619 | Default | Min | Max |
5620 | --- | --- | --- |
5621 | 0 | 0 | 200 |
5625 ### yaw_rate
5627 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.
5629 | Default | Min | Max |
5630 | --- | --- | --- |
5631 | 20 | 1 | 180 |