From 6aec1d7d924c4bfc623d7fcfad90577190e0a3c0 Mon Sep 17 00:00:00 2001 From: ShikOfTheRa Date: Thu, 7 May 2020 12:51:33 +0100 Subject: [PATCH 01/16] Update Building in Windows 10 with Linux Subsystem.md Added a bit more detail. --- ...ding in Windows 10 with Linux Subsystem.md | 56 +++++++++++++++---- 1 file changed, 46 insertions(+), 10 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 228c4787aa..5ed64eb83f 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -2,17 +2,53 @@ Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10. -1. Enable WSL (_Windows Subsystem for Linux) using any guide from internet. [This](https://winaero.com/blog/enable-wsl-windows-10-fall-creators-update/) is up to date step by step (January 2018) -1. From _Windows Store_ install `Ubuntu` -1. Start `Ubuntu` and run: -1. `sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa` -1. `sudo apt-get update` -1. `sudo apt-get install gcc-arm-embedded make ruby` +## Setting up the environment -At the moment (January 2018) it will install `gcc-arm-none-eabi` in version _7 q4_ +Enable WSL: +run `windows features` +enable `windows subsytem for linux` +reboot -From this moment INAV can be build using the following command -`make TARGET={TARGET_NAME}` +Install Ubuntu: +1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home +1. Search and install most recent Ubunto LTS version +1. When download completed, select `Launch Ubuntu` +1. When prompted enter a user name and password which you will need to remember +1. When complete, the linux command prompt will be displayed -Of course, replace `{TARGET_NAME}` with a target you want to compile \ No newline at end of file +NOTE: from this point all commands are entered into the Ubunto shell command window + +Update the repo packages: +1. `sudo apt update` + +Install Git, Make, gcc and Ruby +1. `sudo apt-get install git` +1. `sudo apt-get install make` +1. `sudo apt-get install gcc-arm-none-eabi` +1. `sudo apt-get install ruby` + +## Downloading the iNav repository (example): + +Mount MS windows C drive and clone iNav +1. `cd /mnt/c` +1. `git clone https://github.com/iNavFlight/inav.git` + +You are ready! +You now have a folder called inav in the root of C drive that you can edit in windows + + +## Building (example): + +Launch Ubuntu: +Click Windows Start button then scroll and lauch "Ubunto" + +Building from Ubunto command line +`cd /mnt/c/inav` +`make clean TARGET=OMNIBUSF4PRO` (as an example) +`make TARGET=MATEKF405` (as an example) + + +## Flashing: +Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]` +Hex files can be found in the folder `c:\inav\obj` From 6976d464c8e866f316fb752ac1697eb6e85379a5 Mon Sep 17 00:00:00 2001 From: Darren Lines Date: Sun, 10 May 2020 16:21:07 +0100 Subject: [PATCH 02/16] Removed Air from OSD mode display --- src/main/io/osd.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index a61947d4e3..1e5fbe14bc 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1655,8 +1655,6 @@ static bool osdDrawSingleElement(uint8_t item) p = "ANGL"; else if (FLIGHT_MODE(HORIZON_MODE)) p = "HOR "; - else if (STATE(AIRMODE_ACTIVE)) - p = "AIR "; displayWrite(osdDisplayPort, elemPosX, elemPosY, p); return true; From ac43b52599da138149a738686c4d57a6b7034a03 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 15 Jun 2020 16:40:39 +0200 Subject: [PATCH 03/16] Autogenerate CLI docs from settings.yaml --- docs/Cli.md | 637 ++++++++++++++++------------- src/main/fc/settings.yaml | 772 +++++++++++++++++++++++++++++++++++ src/utils/update_cli_docs.py | 131 ++++++ 3 files changed, 1246 insertions(+), 294 deletions(-) create mode 100755 src/utils/update_cli_docs.py diff --git a/docs/Cli.md b/docs/Cli.md index 851f623f89..391182da54 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -125,276 +125,161 @@ A shorter form is also supported to enable and disable functions using `serial < ## CLI Variable Reference -| Variable Name | Default Value | Description | -| ------ | ------ | ------ | -| looptime | 1000 | 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. | -| i2c_speed | 400KHZ | 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) | -| cpu_underclock | OFF | 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 | -| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | -| min_check | 1100 | 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. | -| max_check | 1900 | 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. | -| rssi_channel | 0 | RX channel containing the RSSI signal | -| rssi_min | 0 | 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). | -| rssi_max | 100 | 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. | -| rc_filter_frequency | 50 | 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 | -| input_filtering_mode | OFF | Filter out noise from OpenLRS Telemetry RX | -| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | -| max_throttle | 1850 | 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. | -| min_command | 1000 | 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. | -| 3d_deadband_low | 1406 | 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) | -| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | -| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | -| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | -| motor_pwm_rate | 400 | 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. | -| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | -| fixed_wing_auto_arm | OFF | 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. | -| disarm_kill_switch | ON | 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. | -| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | -| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | -| reboot_character | 82 | Special character used to trigger reboot | -| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | -| gps_sbas_mode | NONE | Which SBAS mode to be used | -| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | -| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | -| gps_auto_baud | ON | 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 | -| gps_min_sats | 6 | 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. | -| gps_ublox_use_galileo | OFF | 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]. -| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | -| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | -| inav_use_gps_velned | ON | 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. | -| inav_reset_altitude | FIRST_ARM | 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) | -| inav_reset_home | FIRST_ARM | 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 | -| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | -| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | -| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | -| inav_w_z_gps_v | 0.500 | 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 | -| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | -| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | -| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | -| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | -| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | -| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | -| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | -| name | Empty string | Craft name | -| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | -| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | -| nav_extra_arming_safety | ON | 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 | -| nav_user_control_mode | ATTI | 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. | -| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | -| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | -| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | -| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | -| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | -| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | -| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | -| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | -| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | -| nav_min_rth_distance | 500 | 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. | -| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | -| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | -| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | -| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | -| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | -| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | -| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | -| nav_rth_home_altitude | 0 | 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] | -| nav_rth_abort_threshold | 50000 | 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] | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | -| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | -| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | -| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | -| nav_mc_auto_disarm_delay | 2000 | | -| nav_fw_cruise_thr | 1400 | 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 ) | -| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | -| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | -| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | -| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | -| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | -| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_pitch2thr | 10 | 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) | -| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | -| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | -| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | -| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | -| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | -| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | -| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_idle_thr | 1000 | 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) | -| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | -| nav_fw_launch_timeout | 5000 | 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) | -| nav_fw_launch_max_altitude | 0 | Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. [cm] | -| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | -| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | -| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | -| nav_fw_land_dive_angle | 2 | 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 | -| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]| -| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | -| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | -| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | -| serialrx_inverted | OFF | 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). | -| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | -| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | -| telemetry_inverted | OFF | 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. | -| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | -| frsky_default_latitude | 0.000 | 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. | -| frsky_default_longitude | 0.000 | 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. | -| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | -| frsky_vfas_precision | 0 | 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 | -| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | -| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends precent). [PERCENT/MAH/MWH] | -| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | -| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | -| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | -| smartport_fuel_unit | MAH | S.Port and D-Series telemetry: Unit of the value sent with the `FUEL` ID. [PERCENT/MAH/MWH] | -| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | -| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | -| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. | -| vbat_scale | 1100 | 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. | -| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | -| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | -| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | -| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | -| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | -| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | -| current_meter_scale | 400 | 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. | -| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | -| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | -| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | -| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | -| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | -| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | -| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | -| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | -| multiwii_current_meter_output | OFF | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps) | -| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | -| align_gyro | DEFAULT | 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. | -| align_acc | DEFAULT | 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. | -| align_mag | DEFAULT | 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. | -| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_mag_roll | 0 | 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. | -| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | -| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | -| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | -| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | -| moron_threshold | 32 | 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. | -| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | -| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | -| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | -| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | -| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | -| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | -| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | -| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | -| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | -| tri_unarmed_servo | ON | 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. | -| servo_protocol | PWM | 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) | -| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | -| servo_center_pulse | 1500 | Servo midpoint | -| servo_pwm_rate | 50 | 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. | -| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | -| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | -| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | -| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | -| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_stick_threshold | 50 | 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. | -| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | -| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | -| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | -| failsafe_min_distance | 0 | 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. | -| failsafe_min_distance_procedure | DROP | 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). | -| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | -| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | -| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | -| failsafe_mission | ON | 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 | -| rx_min_usec | 885 | 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. | -| rx_max_usec | 2115 | 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. | -| rx_nosignal_throttle | HOLD | Defines behavior of throttle channel after signal loss is detected and until `failsafe_procedure` kicks in. Possible values - `HOLD` and `DROP`. | -| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | -| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | -| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | -| blackbox_rate_num | 1 | 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 | -| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | -| blackbox_device | SPIFLASH | Selection of where to write blackbox data | -| sdcard_detect_inverted | `TARGET dependent` | 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. | -| ledstrip_visual_beeper | OFF | | -| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | -| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | -| osd_units | METRIC| IMPERIAL, METRIC, UK | -| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | -| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | -| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | -| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | -| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | -| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | -| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | -| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | -| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | -| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | -| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | -| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | -| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | -| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | -| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD.| -| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | -| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | -| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | -| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | -| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | -| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | -| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | -| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | -| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | -| nav_mc_vel_xy_p | 40 | 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 | -| nav_mc_vel_xy_i | 15 | 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 | -| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | -| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | -| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | -| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | -| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | -| deadband | 5 | 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. | -| yaw_deadband | 5 | 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. | -| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | -| flaperon_throw_offset | 200 | 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. | -| fw_iterm_throw_limit | 165 | 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. | -| fw_reference_airspeed | 1000 | 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. | -| fw_turn_assist_yaw_gain | 1 | 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 | -| fw_loiter_direction | RIGHT | 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. | -| mode_range_logic_operator | OR | Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. | -| default_rate_profile | 0 | Default = profile number | -| mag_declination | 0 | 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. | -| heading_hold_rate_limit | 90 | 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. | +| Variable Name | Default Value | Description | +| ------------- | ------------- | ----------- | +| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | +| 3d_deadband_low | 1406 | 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) | +| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | +| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | +| acc_event_threshold_high | 0 | 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. | +| acc_event_threshold_low | 0 | 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. | +| acc_event_threshold_neg_x | 0 | 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. | +| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| acc_lpf_hz | 15 | 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. | +| acc_lpf_type | BIQUAD | 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. | +| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| airspeed_adc_channel | 0 | 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 | +| align_acc | DEFAULT | 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. | +| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_gyro | DEFAULT | 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. | +| align_mag | DEFAULT | 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. | +| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | +| align_mag_roll | 0 | 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. | +| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | +| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | +| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | +| antigravity_accelerator | 1 | | +| antigravity_cutoff_lpf_hz | 15 | 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 | +| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | +| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | +| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | +| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | +| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | +| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | +| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | +| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | +| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | +| blackbox_device | SPIFLASH | Selection of where to write blackbox data | +| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | +| blackbox_rate_num | 1 | 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 | +| cpu_underclock | OFF | 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 | +| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | +| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | +| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | +| current_meter_scale | 400 | 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. | +| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | +| deadband | 5 | 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. | +| disarm_kill_switch | ON | 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. | +| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | +| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | +| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dterm_lpf_hz | 40 | 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 | +| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | +| dynamic_gyro_notch_min_hz | 150 | 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` | +| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | +| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | +| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | +| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | +| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | +| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | +| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | +| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | +| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | +| failsafe_min_distance | 0 | 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. | +| failsafe_min_distance_procedure | DROP | 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). | +| failsafe_mission | ON | 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 | +| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | +| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | +| failsafe_stick_threshold | 50 | 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. | +| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | +| fixed_wing_auto_arm | OFF | 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. | +| flaperon_throw_offset | 200 | 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. | +| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | +| frsky_default_latitude | 0.000 | 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. | +| frsky_default_longitude | 0.000 | 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. | +| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | +| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | +| frsky_vfas_precision | 0 | 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 | +| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | +| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | +| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | +| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | +| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | +| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | +| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | +| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | +| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | +| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | +| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | +| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | +| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | +| fw_iterm_limit_stick_position | 0.5 | 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 | +| fw_iterm_throw_limit | 165 | 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. | +| fw_loiter_direction | RIGHT | 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. | +| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | +| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | +| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | +| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | +| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | +| fw_reference_airspeed | 1000 | 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. | +| fw_tpa_time_constant | 0 | 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 | +| fw_turn_assist_yaw_gain | 1 | 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 | +| gps_auto_baud | ON | 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 | +| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | +| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | +| gps_min_sats | 6 | 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. | +| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | +| gps_sbas_mode | NONE | Which SBAS mode to be used | +| gps_ublox_use_galileo | OFF | 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]. | +| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | +| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | +| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | +| has_flaps | OFF | 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 | +| heading_hold_rate_limit | 90 | 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. | +| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | +| i2c_speed | 400KHZ | 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) | +| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | +| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | +| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | +| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | +| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | +| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | +| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | +| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | +| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | +| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | +| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | +| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | +| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | +| inav_reset_altitude | FIRST_ARM | 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) | +| inav_reset_home | FIRST_ARM | 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 | +| inav_use_gps_velned | ON | 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. | +| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | +| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | +| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | +| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | +| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | +| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | +| inav_w_z_gps_v | 0.500 | 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 | +| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | +| iterm_windup | 50 | 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) | +| ledstrip_visual_beeper | OFF | | +| looptime | 1000 | 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. | +| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | | mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | | mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | | mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | @@ -494,34 +379,198 @@ A shorter form is also supported to enable and disable functions using `serial < | vtx_max_power_override | 0 | 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 it's capabilities | | motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | | motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | -| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | -| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | -| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | -| nav_mc_braking_timeout | 2000 | timeout in ms for braking | -| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | -| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | -| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | -| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | +| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | +| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | +| motor_pwm_rate | 400 | 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. | +| name | Empty string | Craft name | +| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | +| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | +| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | +| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | +| nav_extra_arming_safety | ON | 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 | +| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | +| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | +| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | +| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | +| nav_fw_cruise_thr | 1400 | 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 ) | +| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | +| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | +| nav_fw_land_dive_angle | 2 | 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 | +| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | +| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | +| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | +| nav_fw_launch_idle_thr | 1000 | 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) | +| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | +| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | +| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | +| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | +| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | +| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | +| nav_fw_launch_timeout | 5000 | 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) | +| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | +| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | +| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | +| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | +| nav_fw_pitch2thr | 10 | 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) | +| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | +| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | +| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | +| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | +| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | +| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | +| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | +| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | +| nav_mc_auto_disarm_delay | 2000 | | +| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | | nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | +| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | +| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | +| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | +| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | +| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | +| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | +| nav_mc_braking_timeout | 2000 | timeout in ms for braking | +| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | +| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | | nav_mc_pos_deceleration_time | 120 | 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 | | nav_mc_pos_expo | 10 | Expo for PosHold control | +| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | +| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | +| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | +| nav_mc_vel_xy_i | 15 | 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 | +| nav_mc_vel_xy_p | 40 | 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 | +| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | +| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | +| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | +| nav_min_rth_distance | 500 | 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. | +| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | +| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | +| nav_rth_abort_threshold | 50000 | 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] | +| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | +| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | +| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | +| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | +| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | +| nav_rth_home_altitude | 0 | 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] | +| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | +| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | +| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | +| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | +| nav_user_control_mode | ATTI | 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. | +| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | +| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | +| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | +| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | | osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | -| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | -| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. 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 `mc_airmode_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** mode. | -| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used | +| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | +| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | +| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | +| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | +| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | +| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | +| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | +| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | +| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | +| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | +| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | +| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | +| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | +| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | +| osd_units | METRIC | IMPERIAL, METRIC, UK | +| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | +| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | +| pidsum_limit | 500 | 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 | +| pidsum_limit_yaw | 400 | 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 | +| pitch_rate | 20 | 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. | +| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | +| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | +| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | +| rate_accel_limit_roll_pitch | 0 | 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. | +| rate_accel_limit_yaw | 10000 | 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. | +| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | +| rc_filter_frequency | 50 | 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 | +| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | +| reboot_character | 82 | Special character used to trigger reboot | +| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | +| roll_rate | 20 | 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. | +| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | +| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | +| rpm_gyro_min_hz | 150 | 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` | +| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | +| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | +| rssi_channel | 0 | RX channel containing the RSSI signal | +| rssi_max | 100 | 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. | +| rssi_min | 0 | 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). | +| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | +| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | +| rx_max_usec | 2115 | 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. | +| rx_min_usec | 885 | 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. | +| sdcard_detect_inverted | `TARGET dependent` | 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. | +| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_inverted | OFF | 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). | +| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | +| servo_center_pulse | 1500 | Servo midpoint | +| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | +| servo_protocol | PWM | 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) | +| servo_pwm_rate | 50 | 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. | | sim_ground_station_number | Empty string | 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. | +| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | | sim_pin | Empty string | PIN code for the SIM module | -| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | | sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | -| acc_event_threshold_high | 0 | 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. | -| acc_event_threshold_low | 0 | 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. | -| acc_event_threshold_neg_x | 0 | 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. | -| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`.| -| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | -| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | -| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | -| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | -| antigravity_accelerator | 1 | | -| antigravity_cutoff_lpf_hz | 15 | 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 | -| sim_pin | | PIN for GSM card module | -| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky | \ No newline at end of file +| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | +| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | +| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | +| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | +| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | +| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | +| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | +| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | +| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | +| telemetry_inverted | OFF | 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. | +| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | +| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | +| thr_expo | 0 | Throttle exposition value | +| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | +| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | +| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | +| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | +| tpa_breakpoint | 1500 | See tpa_rate. | +| tpa_rate | 0 | 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. | +| tri_unarmed_servo | ON | 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. | +| tz_automatic_dst | OFF | 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`. | +| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | +| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | +| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | +| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | +| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | +| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | +| vbat_scale | 1100 | 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. | +| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | +| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | +| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | +| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | +| vtx_low_power_disarm | OFF | 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. | +| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| yaw_deadband | 5 | 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. | +| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | +| yaw_rate | 20 | 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. | + + > Note: this table is autogenerated. Do not edit it manually. diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5a760bde8f..be3096bc72 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -151,24 +151,38 @@ groups: headers: ["sensors/gyro.h"] members: - name: looptime + docs_description: "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." + docs_default_value: "1000" max: 9000 - name: gyro_sync + docs_description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" + docs_default_value: "OFF" field: gyroSync type: bool - name: align_gyro + docs_description: "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." + docs_default_value: "DEFAULT" field: gyro_align type: uint8_t table: alignment - name: gyro_hardware_lpf + docs_description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." + docs_default_value: "42HZ" field: gyro_lpf table: gyro_lpf - name: gyro_lpf_hz + docs_description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + docs_default_value: "60" field: gyro_soft_lpf_hz max: 200 - name: gyro_lpf_type + docs_description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + docs_default_value: "BIQUAD" field: gyro_soft_lpf_type table: filter_type - name: moron_threshold + docs_description: "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." + docs_default_value: "32" field: gyroMovementCalibrationThreshold max: 128 - name: gyro_notch_hz @@ -179,26 +193,38 @@ groups: min: 1 max: 500 - name: gyro_stage2_lowpass_hz + docs_description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" + docs_default_value: "0" field: gyro_stage2_lowpass_hz min: 0 max: 500 - name: gyro_stage2_lowpass_type + docs_description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: gyro_stage2_lowpass_type table: filter_type - name: dynamic_gyro_notch_enabled + docs_description: "Enable/disable dynamic gyro notch also known as Matrix Filter" + docs_default_value: "`OFF`" field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool - name: dynamic_gyro_notch_range + docs_description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" + docs_default_value: "`MEDIUM`" field: dynamicGyroNotchRange condition: USE_DYNAMIC_FILTERS table: dynamicFilterRangeTable - name: dynamic_gyro_notch_q + docs_description: "Q factor for dynamic notches" + docs_default_value: "120" field: dynamicGyroNotchQ condition: USE_DYNAMIC_FILTERS min: 1 max: 1000 - name: dynamic_gyro_notch_min_hz + docs_description: "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`" + docs_default_value: "150" field: dynamicGyroNotchMinHz condition: USE_DYNAMIC_FILTERS min: 30 @@ -233,18 +259,26 @@ groups: condition: USE_ADC members: - name: vbat_adc_channel + docs_description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_BATTERY] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: rssi_adc_channel + docs_description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_RSSI] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: current_adc_channel + docs_description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" + docs_default_value: "-" field: adcFunctionChannel[ADC_CURRENT] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: airspeed_adc_channel + docs_description: "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" + docs_default_value: "0" field: adcFunctionChannel[ADC_AIRSPEED] min: ADC_CHN_NONE max: ADC_CHN_MAX @@ -260,38 +294,58 @@ groups: min: 1 max: 255 - name: align_acc + docs_description: "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." + docs_default_value: "DEFAULT" field: acc_align type: uint8_t table: alignment - name: acc_hardware + docs_description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: acc_hardware - name: acc_lpf_hz + docs_description: "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." + docs_default_value: "15" min: 0 max: 200 - name: acc_lpf_type + docs_description: "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." + docs_default_value: "BIQUAD" field: acc_soft_lpf_type table: filter_type - name: acczero_x + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[X] min: INT16_MIN max: INT16_MAX - name: acczero_y + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: acczero_z + docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." + docs_default_value: "0" field: accZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: accgain_x + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[X] min: 1 max: 8192 - name: accgain_y + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[Y] min: 1 max: 8192 - name: accgain_z + docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + docs_default_value: "4096" field: accGain.raw[Z] min: 1 max: 8192 @@ -304,6 +358,8 @@ groups: - name: rangefinder_hardware table: rangefinder_hardware - name: rangefinder_median_filter + docs_description: "3-point median filtering for rangefinder readouts" + docs_default_value: "OFF" field: use_median_filtering type: bool @@ -318,6 +374,8 @@ groups: min: 0 max: 10000 - name: align_opflow + docs_description: "Optical flow module alignment (default CW0_DEG_FLIP)" + docs_default_value: "5" field: opflow_align type: uint8_t table: alignment @@ -328,43 +386,64 @@ groups: condition: USE_MAG members: - name: align_mag + docs_description: "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." + docs_default_value: "DEFAULT" field: mag_align type: uint8_t table: alignment - name: mag_hardware + docs_description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: mag_hardware - name: mag_declination + docs_description: "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." + docs_default_value: "0" min: -18000 max: 18000 - name: magzero_x + docs_description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[X] min: INT16_MIN max: INT16_MAX - name: magzero_y + docs_description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: magzero_z + docs_description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." + docs_default_value: "0" field: magZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: mag_calibration_time + docs_description: "Adjust how long time the Calibration of mag will last." + docs_default_value: "30" field: magCalibrationTimeLimit min: 30 max: 120 - name: mag_to_use + docs_description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" condition: USE_DUAL_MAG min: 0 max: 1 - name: align_mag_roll + docs_description: "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." + docs_default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_mag_pitch + docs_description: "Same as align_mag_roll, but for the pitch axis." + docs_default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_mag_yaw + docs_description: "Same as align_mag_roll, but for the yaw axis." + docs_default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -375,11 +454,17 @@ groups: condition: USE_BARO members: - name: baro_hardware + docs_description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + docs_default_value: "AUTO" table: baro_hardware - name: baro_median_filter + docs_description: "3-point median filtering for barometer readouts. No reason to change this setting" + docs_default_value: "ON" field: use_median_filtering type: bool - name: baro_cal_tolerance + docs_description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." + docs_default_value: "150" field: baro_calibration_tolerance min: 0 max: 1000 @@ -406,24 +491,36 @@ groups: field: receiverType table: receiver_type - name: min_check + docs_description: "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." + docs_default_value: "1100" field: mincheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: max_check + docs_description: "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." + docs_default_value: "1900" field: maxcheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: rssi_source + docs_description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" + docs_default_value: "`AUTO`" field: rssi_source table: rssi_source - name: rssi_channel + docs_description: "RX channel containing the RSSI signal" + docs_default_value: "0" min: 0 max: MAX_SUPPORTED_RC_CHANNEL_COUNT - name: rssi_min + docs_description: "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)." + docs_default_value: "0" field: rssiMin min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX - name: rssi_max + docs_description: "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." + docs_default_value: "100" field: rssiMax min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX @@ -432,13 +529,19 @@ groups: min: 500 max: 10000 - name: rc_filter_frequency + docs_description: "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" + docs_default_value: "50" field: rcFilterFrequency min: 0 max: 100 - name: serialrx_provider + docs_description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." + docs_default_value: "SPEK1024" condition: USE_SERIAL_RX table: serial_rx - name: serialrx_inverted + docs_description: "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)." + docs_default_value: "OFF" condition: USE_SERIAL_RX type: bool - name: rx_spi_protocol @@ -452,16 +555,24 @@ groups: min: 0 max: 8 - name: spektrum_sat_bind + docs_description: "0 = disabled. Used to bind the spektrum satellite to RX" + docs_default_value: "0" condition: USE_SPEKTRUM_BIND min: SPEKTRUM_SAT_BIND_DISABLED max: SPEKTRUM_SAT_BIND_MAX - name: rx_min_usec + docs_description: "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." + docs_default_value: "885" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: rx_max_usec + docs_description: "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." + docs_default_value: "2115" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: serialrx_halfduplex + docs_description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" + docs_default_value: "OFF" field: halfDuplex type: bool - name: msp_override_channels @@ -476,17 +587,25 @@ groups: condition: USE_BLACKBOX members: - name: blackbox_rate_num + docs_description: "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" + docs_default_value: "1" field: rate_num min: 1 max: 65535 - name: blackbox_rate_denom + docs_description: "Blackbox logging rate denominator. See blackbox_rate_num." + docs_default_value: "1" field: rate_denom min: 1 max: 65535 - name: blackbox_device + docs_description: "Selection of where to write blackbox data" + docs_default_value: "SPIFLASH" field: device table: blackbox_device - name: sdcard_detect_inverted + docs_description: "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." + docs_default_value: "`TARGET dependent`" field: invertedCardDetection condition: USE_SDCARD type: bool @@ -496,33 +615,49 @@ groups: headers: ["flight/mixer.h"] members: - name: max_throttle + docs_description: "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." + docs_default_value: "1850" field: maxthrottle min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: min_command + docs_description: "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." + docs_default_value: "1000" field: mincommand min: 0 max: PWM_RANGE_MAX - name: motor_pwm_rate + docs_description: "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." + docs_default_value: "400" field: motorPwmRate min: 50 max: 32000 - name: motor_accel_time + docs_description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" + docs_default_value: "0" field: motorAccelTimeMs min: 0 max: 1000 - name: motor_decel_time + docs_description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" + docs_default_value: "0" field: motorDecelTimeMs min: 0 max: 1000 - name: motor_pwm_protocol + docs_description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" + docs_default_value: "STANDARD" field: motorPwmProtocol table: motor_pwm_protocol - name: throttle_scale + docs_description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" + docs_default_value: "1.000" field: throttleScale min: 0 max: 1 - name: throttle_idle + docs_description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." + docs_default_value: "15" field: throttleIdle min: 4 max: 30 @@ -536,41 +671,67 @@ groups: headers: ["flight/failsafe.h"] members: - name: failsafe_delay + docs_description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." + docs_default_value: "5" min: 0 max: 200 - name: failsafe_recovery_delay + docs_description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." + docs_default_value: "5" min: 0 max: 200 - name: failsafe_off_delay + docs_description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." + docs_default_value: "200" min: 0 max: 200 - name: failsafe_throttle + docs_description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + docs_default_value: "1000" min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: failsafe_throttle_low_delay + docs_description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" + docs_default_value: "100" min: 0 max: 300 - name: failsafe_procedure + docs_description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + docs_default_value: "SET-THR" table: failsafe_procedure - name: failsafe_stick_threshold + docs_description: "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." + docs_default_value: "50" field: failsafe_stick_motion_threshold min: 0 max: 500 - name: failsafe_fw_roll_angle + docs_description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" + docs_default_value: "-200" min: -800 max: 800 - name: failsafe_fw_pitch_angle + docs_description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" + docs_default_value: "100" min: -800 max: 800 - name: failsafe_fw_yaw_rate + docs_description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" + docs_default_value: "-45" min: -1000 max: 1000 - name: failsafe_min_distance + docs_description: "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." + docs_default_value: "0" min: 0 max: 65000 - name: failsafe_min_distance_procedure + docs_description: "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)." + docs_default_value: "DROP" table: failsafe_procedure - name: failsafe_mission + docs_description: "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" + docs_default_value: "ON" type: bool - name: PG_LIGHTS_CONFIG @@ -579,13 +740,19 @@ groups: condition: USE_LIGHTS members: - name: failsafe_lights + docs_description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." + docs_default_value: "ON" field: failsafe.enabled type: bool - name: failsafe_lights_flash_period + docs_description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." + docs_default_value: "1000" field: failsafe.flash_period min: 40 max: 65535 - name: failsafe_lights_flash_on_time + docs_description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." + docs_default_value: "100" field: failsafe.flash_on_time min: 20 max: 65535 @@ -595,14 +762,20 @@ groups: headers: ["sensors/boardalignment.h"] members: - name: align_board_roll + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_board_pitch + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_board_yaw + docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + docs_default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -612,42 +785,62 @@ groups: headers: ["sensors/battery.h"] members: - name: vbat_meter_type + docs_description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" + docs_default_value: "`ADC`" field: voltage.type table: voltage_sensor type: uint8_t - name: vbat_scale + docs_description: "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." + docs_default_value: "1100" field: voltage.scale condition: USE_ADC min: VBAT_SCALE_MIN max: VBAT_SCALE_MAX - name: current_meter_scale + docs_description: "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." + docs_default_value: "400" field: current.scale min: -10000 max: 10000 - name: current_meter_offset + docs_description: "This sets the output offset voltage of the current sensor in millivolts." + docs_default_value: "0" field: current.offset min: -32768 max: 32767 - name: current_meter_type + docs_description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." + docs_default_value: "ADC" field: current.type table: current_sensor type: uint8_t - name: bat_voltage_src + docs_description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" + docs_default_value: "RAW" field: voltageSource table: bat_voltage_source type: uint8_t - name: cruise_power + docs_description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" + docs_default_value: "0" field: cruise_power min: 0 max: 4294967295 - name: idle_power + docs_description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" + docs_default_value: "0" field: idle_power min: 0 max: 65535 - name: rth_energy_margin + docs_description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" + docs_default_value: "5" min: 0 max: 100 - name: thr_comp_weight + docs_description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" + docs_default_value: "0.692" field: throttle_compensation_weight min: 0 max: 2 @@ -658,43 +851,61 @@ groups: value_type: BATTERY_CONFIG_VALUE members: - name: bat_cells + docs_description: "Number of cells of the battery (0 = autodetect), see battery documentation" + docs_default_value: "0" field: cells condition: USE_ADC min: 0 max: 8 - name: vbat_cell_detect_voltage + docs_description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" + docs_default_value: "430" field: voltage.cellDetect condition: USE_ADC min: 100 max: 500 - name: vbat_max_cell_voltage + docs_description: "Maximum voltage per cell in 0.01V units, default is 4.20V" + docs_default_value: "420" field: voltage.cellMax condition: USE_ADC min: 100 max: 500 - name: vbat_min_cell_voltage + docs_description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" + docs_default_value: "330" field: voltage.cellMin condition: USE_ADC min: 100 max: 500 - name: vbat_warning_cell_voltage + docs_description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" + docs_default_value: "350" field: voltage.cellWarning condition: USE_ADC min: 100 max: 500 - name: battery_capacity + docs_description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." + docs_default_value: "0" field: capacity.value min: 0 max: 4294967295 - name: battery_capacity_warning + docs_description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." + docs_default_value: "0" field: capacity.warning min: 0 max: 4294967295 - name: battery_capacity_critical + docs_description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." + docs_default_value: "0" field: capacity.critical min: 0 max: 4294967295 - name: battery_capacity_unit + docs_description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." + docs_default_value: "MAH" field: capacity.unit table: bat_capacity_unit type: uint8_t @@ -703,20 +914,30 @@ groups: type: mixerConfig_t members: - name: motor_direction_inverted + docs_description: "Use if you need to inverse yaw motor direction." + docs_default_value: "OFF" field: motorDirectionInverted type: bool - name: platform_type + docs_description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" + docs_default_value: "\"MULTIROTOR\"" field: platformType type: uint8_t table: platform_type - name: has_flaps + docs_description: "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" + docs_default_value: "OFF" field: hasFlaps type: bool - name: model_preview_type + docs_description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." + docs_default_value: "-1" field: appliedMixerPreset min: -1 max: INT16_MAX - name: fw_min_throttle_down_pitch + docs_description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + docs_default_value: "0" field: fwMinThrottleDownPitchAngle min: 0 max: 450 @@ -725,14 +946,20 @@ groups: type: reversibleMotorsConfig_t members: - name: 3d_deadband_low + docs_description: "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)" + docs_default_value: "1406" field: deadband_low min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_deadband_high + docs_description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" + docs_default_value: "1514" field: deadband_high min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_neutral + docs_description: "Neutral (stop) throttle value for 3D mode" + docs_default_value: "1460" field: neutral min: PWM_RANGE_MIN max: PWM_RANGE_MAX @@ -742,24 +969,36 @@ groups: headers: ["flight/servos.h"] members: - name: servo_protocol + docs_description: "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)" + docs_default_value: "PWM" field: servo_protocol table: servo_protocol - name: servo_center_pulse + docs_description: "Servo midpoint" + docs_default_value: "1500" field: servoCenterPulse min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: servo_pwm_rate + docs_description: "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." + docs_default_value: "50" field: servoPwmRate min: 50 max: 498 - name: servo_lpf_hz + docs_description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" + docs_default_value: "20" field: servo_lowpass_freq min: 0 max: 400 - name: flaperon_throw_offset + docs_description: "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." + docs_default_value: "200" min: FLAPERON_THROW_MIN max: FLAPERON_THROW_MAX - name: tri_unarmed_servo + docs_description: "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." + docs_default_value: "ON" type: bool - name: PG_CONTROL_RATE_PROFILES @@ -768,64 +1007,94 @@ groups: value_type: CONTROL_RATE_VALUE members: - name: thr_mid + docs_description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." + docs_default_value: "50" field: throttle.rcMid8 min: 0 max: 100 - name: thr_expo + docs_description: "Throttle exposition value" + docs_default_value: "0" field: throttle.rcExpo8 min: 0 max: 100 - name: tpa_rate + docs_description: "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." + docs_default_value: "0" field: throttle.dynPID min: 0 max: CONTROL_RATE_CONFIG_TPA_MAX - name: tpa_breakpoint + docs_description: "See tpa_rate." + docs_default_value: "1500" field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: fw_tpa_time_constant + docs_description: "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" + docs_default_value: "0" field: throttle.fixedWingTauMs min: 0 max: 5000 - name: rc_expo + docs_description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" + docs_default_value: "70" field: stabilized.rcExpo8 min: 0 max: 100 - name: rc_yaw_expo + docs_description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" + docs_default_value: "20" field: stabilized.rcYawExpo8 min: 0 max: 100 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis. # Rate 180 (1800dps) is max. value gyro can measure reliably - name: roll_rate + docs_description: "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." + docs_default_value: "20" field: stabilized.rates[FD_ROLL] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: pitch_rate + docs_description: "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." + docs_default_value: "20" field: stabilized.rates[FD_PITCH] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: yaw_rate + docs_description: "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." + docs_default_value: "20" field: stabilized.rates[FD_YAW] min: CONTROL_RATE_CONFIG_YAW_RATE_MIN max: CONTROL_RATE_CONFIG_YAW_RATE_MAX - name: manual_rc_expo + docs_description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" + docs_default_value: "70" field: manual.rcExpo8 min: 0 max: 100 - name: manual_rc_yaw_expo + docs_description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" + docs_default_value: "20" field: manual.rcYawExpo8 min: 0 max: 100 - name: manual_roll_rate + docs_description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_ROLL] min: 0 max: 100 - name: manual_pitch_rate + docs_description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_PITCH] min: 0 max: 100 - name: manual_yaw_rate + docs_description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" + docs_default_value: "100" field: manual.rates[FD_YAW] min: 0 max: 100 @@ -839,6 +1108,8 @@ groups: headers: ["io/serial.h"] members: - name: reboot_character + docs_description: "Special character used to trigger reboot" + docs_default_value: "82" min: 48 max: 126 @@ -847,25 +1118,39 @@ groups: headers: ["flight/imu.h"] members: - name: imu_dcm_kp + docs_description: "Inertial Measurement Unit KP Gain for accelerometer measurements" + docs_default_value: "2500" field: dcm_kp_acc max: UINT16_MAX - name: imu_dcm_ki + docs_description: "Inertial Measurement Unit KI Gain for accelerometer measurements" + docs_default_value: "50" field: dcm_ki_acc max: UINT16_MAX - name: imu_dcm_kp_mag + docs_description: "Inertial Measurement Unit KP Gain for compass measurements" + docs_default_value: "10000" field: dcm_kp_mag max: UINT16_MAX - name: imu_dcm_ki_mag + docs_description: "Inertial Measurement Unit KI Gain for compass measurements" + docs_default_value: "0" field: dcm_ki_mag max: UINT16_MAX - name: small_angle + docs_description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." + docs_default_value: "25" min: 0 max: 180 - name: imu_acc_ignore_rate + docs_description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" + docs_default_value: "0" field: acc_ignore_rate min: 0 max: 20 - name: imu_acc_ignore_slope + docs_description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" + docs_default_value: "0" field: acc_ignore_slope min: 0 max: 5 @@ -874,10 +1159,16 @@ groups: type: armingConfig_t members: - name: fixed_wing_auto_arm + docs_description: "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." + docs_default_value: "OFF" type: bool - name: disarm_kill_switch + docs_description: "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." + docs_default_value: "ON" type: bool - name: switch_disarm_delay + docs_description: "Delay before disarming when requested by switch (ms) [0-1000]" + docs_default_value: "250" field: switchDisarmDelayMs min: 0 max: 1000 @@ -896,19 +1187,27 @@ groups: type: rpmFilterConfig_t members: - name: rpm_gyro_filter_enabled + docs_description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" + docs_default_value: "`OFF`" field: gyro_filter_enabled type: bool - name: rpm_gyro_harmonics + docs_description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" + docs_default_value: "1" field: gyro_harmonics type: uint8_t min: 1 max: 3 - name: rpm_gyro_min_hz + docs_description: "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`" + docs_default_value: "150" field: gyro_min_hz type: uint8_t min: 30 max: 200 - name: rpm_gyro_q + docs_description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" + docs_default_value: "500" field: gyro_q type: uint16_t min: 1 @@ -918,27 +1217,41 @@ groups: condition: USE_GPS members: - name: gps_provider + docs_description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." + docs_default_value: "UBLOX" field: provider table: gps_provider type: uint8_t - name: gps_sbas_mode + docs_description: "Which SBAS mode to be used" + docs_default_value: "NONE" field: sbasMode table: gps_sbas_mode type: uint8_t - name: gps_dyn_model + docs_description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." + docs_default_value: "AIR_1G" field: dynModel table: gps_dyn_model type: uint8_t - name: gps_auto_config + docs_description: "Enable automatic configuration of UBlox GPS receivers." + docs_default_value: "ON" field: autoConfig type: bool - name: gps_auto_baud + docs_description: "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" + docs_default_value: "ON" field: autoBaud type: bool - name: gps_ublox_use_galileo + docs_description: "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]." + docs_default_value: "OFF" field: ubloxUseGalileo type: bool - name: gps_min_sats + docs_description: "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." + docs_default_value: "6" field: gpsMinSats min: 5 max: 10 @@ -948,25 +1261,39 @@ groups: headers: ["fc/rc_controls.h"] members: - name: deadband + docs_description: "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." + docs_default_value: "5" min: 0 max: 32 - name: yaw_deadband + docs_description: "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." + docs_default_value: "5" min: 0 max: 100 - name: pos_hold_deadband + docs_description: "Stick deadband in [r/c points], applied after r/c deadband and expo" + docs_default_value: "20" min: 2 max: 250 - name: alt_hold_deadband + docs_description: "Defines the deadband of throttle during alt_hold [r/c points]" + docs_default_value: "50" min: 10 max: 250 - name: 3d_deadband_throttle + docs_description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." + docs_default_value: "50" field: mid_throttle_deadband min: 0 max: 200 - name: mc_airmode_type + docs_description: "Defines the Airmode state handling type for Multirotors. 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 `mc_airmode_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** mode." + docs_default_value: "STICK_CENTER" field: airmodeHandlingType table: airmodeHandlingType - name: mc_airmode_threshold + docs_description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" + docs_default_value: "1300" field: airmodeThrottleThreshold min: 1000 max: 2000 @@ -977,214 +1304,320 @@ groups: value_type: PROFILE_VALUE members: - name: mc_p_pitch + docs_description: "Multicopter rate stabilisation P-gain for PITCH" + docs_default_value: "40" field: bank_mc.pid[PID_PITCH].P min: 0 max: 200 - name: mc_i_pitch + docs_description: "Multicopter rate stabilisation I-gain for PITCH" + docs_default_value: "30" field: bank_mc.pid[PID_PITCH].I min: 0 max: 200 - name: mc_d_pitch + docs_description: "Multicopter rate stabilisation D-gain for PITCH" + docs_default_value: "23" field: bank_mc.pid[PID_PITCH].D min: 0 max: 200 - name: mc_cd_pitch + docs_description: "Multicopter Control Derivative gain for PITCH" + docs_default_value: "60" field: bank_mc.pid[PID_PITCH].FF min: 0 max: 200 - name: mc_p_roll + docs_description: "Multicopter rate stabilisation P-gain for ROLL" + docs_default_value: "40" field: bank_mc.pid[PID_ROLL].P min: 0 max: 200 - name: mc_i_roll + docs_description: "Multicopter rate stabilisation I-gain for ROLL" + docs_default_value: "30" field: bank_mc.pid[PID_ROLL].I min: 0 max: 200 - name: mc_d_roll + docs_description: "Multicopter rate stabilisation D-gain for ROLL" + docs_default_value: "23" field: bank_mc.pid[PID_ROLL].D min: 0 max: 200 - name: mc_cd_roll + docs_description: "Multicopter Control Derivative gain for ROLL" + docs_default_value: "60" field: bank_mc.pid[PID_ROLL].FF min: 0 max: 200 - name: mc_p_yaw + docs_description: "Multicopter rate stabilisation P-gain for YAW" + docs_default_value: "85" field: bank_mc.pid[PID_YAW].P min: 0 max: 200 - name: mc_i_yaw + docs_description: "Multicopter rate stabilisation I-gain for YAW" + docs_default_value: "45" field: bank_mc.pid[PID_YAW].I min: 0 max: 200 - name: mc_d_yaw + docs_description: "Multicopter rate stabilisation D-gain for YAW" + docs_default_value: "0" field: bank_mc.pid[PID_YAW].D min: 0 max: 200 - name: mc_cd_yaw + docs_description: "Multicopter Control Derivative gain for YAW" + docs_default_value: "60" field: bank_mc.pid[PID_YAW].FF min: 0 max: 200 - name: mc_p_level + docs_description: "Multicopter attitude stabilisation P-gain" + docs_default_value: "20" field: bank_mc.pid[PID_LEVEL].P min: 0 max: 200 - name: mc_i_level + docs_description: "Multicopter attitude stabilisation low-pass filter cutoff" + docs_default_value: "15" field: bank_mc.pid[PID_LEVEL].I min: 0 max: 200 - name: mc_d_level + docs_description: "Multicopter attitude stabilisation HORIZON transition point" + docs_default_value: "75" field: bank_mc.pid[PID_LEVEL].D min: 0 max: 200 - name: fw_p_pitch + docs_description: "Fixed-wing rate stabilisation P-gain for PITCH" + docs_default_value: "5" field: bank_fw.pid[PID_PITCH].P min: 0 max: 200 - name: fw_i_pitch + docs_description: "Fixed-wing rate stabilisation I-gain for PITCH" + docs_default_value: "7" field: bank_fw.pid[PID_PITCH].I min: 0 max: 200 - name: fw_ff_pitch + docs_description: "Fixed-wing rate stabilisation FF-gain for PITCH" + docs_default_value: "50" field: bank_fw.pid[PID_PITCH].FF min: 0 max: 200 - name: fw_p_roll + docs_description: "Fixed-wing rate stabilisation P-gain for ROLL" + docs_default_value: "5" field: bank_fw.pid[PID_ROLL].P min: 0 max: 200 - name: fw_i_roll + docs_description: "Fixed-wing rate stabilisation I-gain for ROLL" + docs_default_value: "7" field: bank_fw.pid[PID_ROLL].I min: 0 max: 200 - name: fw_ff_roll + docs_description: "Fixed-wing rate stabilisation FF-gain for ROLL" + docs_default_value: "50" field: bank_fw.pid[PID_ROLL].FF min: 0 max: 200 - name: fw_p_yaw + docs_description: "Fixed-wing rate stabilisation P-gain for YAW" + docs_default_value: "6" field: bank_fw.pid[PID_YAW].P min: 0 max: 200 - name: fw_i_yaw + docs_description: "Fixed-wing rate stabilisation I-gain for YAW" + docs_default_value: "10" field: bank_fw.pid[PID_YAW].I min: 0 max: 200 - name: fw_ff_yaw + docs_description: "Fixed-wing rate stabilisation FF-gain for YAW" + docs_default_value: "60" field: bank_fw.pid[PID_YAW].FF min: 0 max: 200 - name: fw_p_level + docs_description: "Fixed-wing attitude stabilisation P-gain" + docs_default_value: "20" field: bank_fw.pid[PID_LEVEL].P min: 0 max: 200 - name: fw_i_level + docs_description: "Fixed-wing attitude stabilisation low-pass filter cutoff" + docs_default_value: "5" field: bank_fw.pid[PID_LEVEL].I min: 0 max: 200 - name: fw_d_level + docs_description: "Fixed-wing attitude stabilisation HORIZON transition point" + docs_default_value: "75" field: bank_fw.pid[PID_LEVEL].D min: 0 max: 200 - name: max_angle_inclination_rll + docs_description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" + docs_default_value: "300" field: max_angle_inclination[FD_ROLL] min: 100 max: 900 - name: max_angle_inclination_pit + docs_description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" + docs_default_value: "300" field: max_angle_inclination[FD_PITCH] min: 100 max: 900 - name: dterm_lpf_hz + docs_description: "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" + docs_default_value: "40" min: 0 max: 500 - name: dterm_lpf_type + docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: dterm_lpf_type table: filter_type - name: dterm_lpf2_hz + docs_description: "Cutoff frequency for stage 2 D-term low pass filter" + docs_default_value: "0" min: 0 max: 500 - name: dterm_lpf2_type + docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + docs_default_value: "`BIQUAD`" field: dterm_lpf2_type table: filter_type - name: yaw_lpf_hz + docs_description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" + docs_default_value: "30" min: 0 max: 200 - name: fw_iterm_throw_limit + docs_description: "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." + docs_default_value: "165" field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN max: FW_ITERM_THROW_LIMIT_MAX - name: fw_loiter_direction + docs_description: "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." + docs_default_value: "RIGHT" field: loiter_direction condition: USE_NAV table: direction - name: fw_reference_airspeed + docs_description: "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." + docs_default_value: "1000" field: fixedWingReferenceAirspeed min: 1 max: 5000 - name: fw_turn_assist_yaw_gain + docs_description: "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" + docs_default_value: "1" field: fixedWingCoordinatedYawGain min: 0 max: 2 - name: fw_iterm_limit_stick_position + docs_description: "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" + docs_default_value: "0.5" field: fixedWingItermLimitOnStickPosition min: 0 max: 1 - name: pidsum_limit + docs_description: "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" + docs_default_value: "500" field: pidSumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: pidsum_limit_yaw + docs_description: "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" + docs_default_value: "400" field: pidSumLimitYaw min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup + docs_description: "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)" + docs_default_value: "50" field: itermWindupPointPercent min: 0 max: 90 - name: rate_accel_limit_roll_pitch + docs_description: "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." + docs_default_value: "0" field: axisAccelerationLimitRollPitch max: 500000 - name: rate_accel_limit_yaw + docs_description: "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." + docs_default_value: "10000" field: axisAccelerationLimitYaw max: 500000 - name: heading_hold_rate_limit + docs_description: "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." + docs_default_value: "90" min: HEADING_HOLD_RATE_LIMIT_MIN max: HEADING_HOLD_RATE_LIMIT_MAX - name: nav_mc_pos_z_p + docs_description: "P gain of altitude PID controller (Multirotor)" + docs_default_value: "50" field: bank_mc.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_p + docs_description: "P gain of velocity PID controller" + docs_default_value: "100" field: bank_mc.pid[PID_VEL_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_i + docs_description: "I gain of velocity PID controller" + docs_default_value: "50" field: bank_mc.pid[PID_VEL_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_d + docs_description: "D gain of velocity PID controller" + docs_default_value: "10" field: bank_mc.pid[PID_VEL_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_xy_p + docs_description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" + docs_default_value: "65" field: bank_mc.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_p + docs_description: "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" + docs_default_value: "40" field: bank_mc.pid[PID_VEL_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_i + docs_description: "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" + docs_default_value: "15" field: bank_mc.pid[PID_VEL_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_d + docs_description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." + docs_default_value: "100" field: bank_mc.pid[PID_VEL_XY].D condition: USE_NAV min: 0 @@ -1195,6 +1628,8 @@ groups: min: 0 max: 255 - name: nav_mc_heading_p + docs_description: "P gain of Heading Hold controller (Multirotor)" + docs_default_value: "60" field: bank_mc.pid[PID_HEADING].P condition: USE_NAV min: 0 @@ -1204,56 +1639,78 @@ groups: min: 0 max: 100 - name: nav_fw_pos_z_p + docs_description: "P gain of altitude PID controller (Fixedwing)" + docs_default_value: "50" field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_i + docs_description: "I gain of altitude PID controller (Fixedwing)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_d + docs_description: "D gain of altitude PID controller (Fixedwing)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_p + docs_description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" + docs_default_value: "75" field: bank_fw.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_i + docs_description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + docs_default_value: "5" field: bank_fw.pid[PID_POS_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_d + docs_description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + docs_default_value: "8" field: bank_fw.pid[PID_POS_XY].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_heading_p + docs_description: "P gain of Heading Hold controller (Fixedwing)" + docs_default_value: "60" field: bank_fw.pid[PID_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_p + docs_description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "60" field: bank_fw.pid[PID_POS_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_i + docs_description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_HEADING].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_d + docs_description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "0" field: bank_fw.pid[PID_POS_HEADING].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_pidsum_limit + docs_description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" + docs_default_value: "350" field: navFwPosHdgPidsumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX @@ -1283,24 +1740,33 @@ groups: min: 10 max: 250 - name: antigravity_gain + docs_description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" + docs_default_value: "1" field: antigravityGain condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_accelerator + docs_description: "" + docs_default_value: "1" field: antigravityAccelerator condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_cutoff_lpf_hz + docs_description: "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" + docs_default_value: "15" field: antigravityCutoff condition: USE_ANTIGRAVITY min: 1 max: 30 - name: pid_type + docs_description: "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`" field: pidControllerType table: pidTypeTable - name: mc_cd_lpf_hz + docs_description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" + docs_default_value: "30" field: controlDerivativeLpfHz min: 0 max: 200 @@ -1310,22 +1776,32 @@ groups: condition: USE_NAV && USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_overshoot_time + docs_description: "Time [ms] to detect sustained overshoot" + docs_default_value: "100" field: fw_overshoot_time min: 50 max: 500 - name: fw_autotune_undershoot_time + docs_description: "Time [ms] to detect sustained undershoot" + docs_default_value: "200" field: fw_undershoot_time min: 50 max: 500 - name: fw_autotune_threshold + docs_description: "Threshold [%] of max rate to consider overshoot/undershoot detection" + docs_default_value: "50" field: fw_max_rate_threshold min: 0 max: 100 - name: fw_autotune_ff_to_p_gain + docs_description: "FF to P gain (strength relationship) [%]" + docs_default_value: "10" field: fw_ff_to_p_gain min: 0 max: 100 - name: fw_autotune_ff_to_i_tc + docs_description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" + docs_default_value: "600" field: fw_ff_to_i_time_constant min: 100 max: 5000 @@ -1335,25 +1811,37 @@ groups: condition: USE_NAV members: - name: inav_auto_mag_decl + docs_description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." + docs_default_value: "ON" field: automatic_mag_declination type: bool - name: inav_gravity_cal_tolerance + docs_description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." + docs_default_value: "5" field: gravity_calibration_tolerance min: 0 max: 255 - name: inav_use_gps_velned + docs_description: "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." + docs_default_value: "ON" field: use_gps_velned type: bool - name: inav_allow_dead_reckoning field: allow_dead_reckoning type: bool - name: inav_reset_altitude + docs_description: "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)" + docs_default_value: "FIRST_ARM" field: reset_altitude_type table: reset_type - name: inav_reset_home + docs_description: "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" + docs_default_value: "FIRST_ARM" field: reset_home_type table: reset_type - name: inav_max_surface_altitude + docs_description: "Max allowed altitude for surface following mode. [cm]" + docs_default_value: "200" field: max_surface_altitude min: 0 max: 1000 @@ -1374,30 +1862,44 @@ groups: min: 0 max: 100 - name: inav_w_z_baro_p + docs_description: "Weight of barometer measurements in estimated altitude and climb rate" + docs_default_value: "0.350" field: w_z_baro_p min: 0 max: 10 - name: inav_w_z_gps_p + docs_description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" + docs_default_value: "0.200" field: w_z_gps_p min: 0 max: 10 - name: inav_w_z_gps_v + docs_description: "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" + docs_default_value: "0.500" field: w_z_gps_v min: 0 max: 10 - name: inav_w_xy_gps_p + docs_description: "Weight of GPS coordinates in estimated UAV position and speed." + docs_default_value: "1.000" field: w_xy_gps_p min: 0 max: 10 - name: inav_w_xy_gps_v + docs_description: "Weight of GPS velocity data in estimated UAV speed" + docs_default_value: "2.000" field: w_xy_gps_v min: 0 max: 10 - name: inav_w_z_res_v + docs_description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" + docs_default_value: "0.500" field: w_z_res_v min: 0 max: 10 - name: inav_w_xy_res_v + docs_description: "Decay coefficient for estimated velocity when GPS reference for position is lost" + docs_default_value: "0.500" field: w_xy_res_v min: 0 max: 10 @@ -1406,14 +1908,20 @@ groups: min: 0 max: 1 - name: inav_w_acc_bias + docs_description: "Weight for accelerometer drift estimation" + docs_default_value: "0.010" field: w_acc_bias min: 0 max: 1 - name: inav_max_eph_epv + docs_description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" + docs_default_value: "1000.000" field: max_eph_epv min: 0 max: 9999 - name: inav_baro_epv + docs_description: "Uncertainty value for barometric sensor [cm]" + docs_default_value: "100.000" field: baro_epv min: 0 max: 9999 @@ -1424,267 +1932,401 @@ groups: condition: USE_NAV members: - name: nav_disarm_on_landing + docs_description: "If set to ON, iNav disarms the FC after landing" + docs_default_value: "OFF" field: general.flags.disarm_on_landing type: bool - name: nav_use_midthr_for_althold + docs_description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" + docs_default_value: "OFF" field: general.flags.use_thr_mid_for_althold type: bool - name: nav_extra_arming_safety + docs_description: "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" + docs_default_value: "ON" field: general.flags.extra_arming_safety table: nav_extra_arming_safety - name: nav_user_control_mode + docs_description: "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." + docs_default_value: "ATTI" field: general.flags.user_control_mode table: nav_user_control_mode - name: nav_position_timeout + docs_description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" + docs_default_value: "5" field: general.pos_failure_timeout min: 0 max: 10 - name: nav_wp_radius + docs_description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" + docs_default_value: "100" field: general.waypoint_radius min: 10 max: 10000 - name: nav_wp_safe_distance + docs_description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." + docs_default_value: "10000" field: general.waypoint_safe_distance max: 65000 - name: nav_auto_speed + docs_description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" + docs_default_value: "300" field: general.max_auto_speed min: 10 max: 2000 - name: nav_auto_climb_rate + docs_description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" + docs_default_value: "500" field: general.max_auto_climb_rate min: 10 max: 2000 - name: nav_manual_speed + docs_description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" + docs_default_value: "500" field: general.max_manual_speed min: 10 max: 2000 - name: nav_manual_climb_rate + docs_description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" + docs_default_value: "200" field: general.max_manual_climb_rate min: 10 max: 2000 - name: nav_landing_speed + docs_description: "Vertical descent velocity during the RTH landing phase. [cm/s]" + docs_default_value: "200" field: general.land_descent_rate min: 100 max: 2000 - name: nav_land_slowdown_minalt + docs_description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" + docs_default_value: "500" field: general.land_slowdown_minalt min: 50 max: 1000 - name: nav_land_slowdown_maxalt + docs_description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" + docs_default_value: "2000" field: general.land_slowdown_maxalt min: 500 max: 4000 - name: nav_emerg_landing_speed + docs_description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" + docs_default_value: "500" field: general.emerg_descent_rate min: 100 max: 2000 - name: nav_min_rth_distance + docs_description: "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." + docs_default_value: "500" field: general.min_rth_distance min: 0 max: 5000 - name: nav_overrides_motor_stop + docs_description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." + docs_default_value: "ON" field: general.flags.auto_overrides_motor_stop type: bool - name: nav_rth_climb_first + docs_description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." + docs_default_value: "ON" field: general.flags.rth_climb_first type: bool - name: nav_rth_climb_ignore_emerg + docs_description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." + docs_default_value: "OFF" field: general.flags.rth_climb_ignore_emerg type: bool - name: nav_rth_tail_first + docs_description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." + docs_default_value: "OFF" field: general.flags.rth_tail_first type: bool - name: nav_rth_allow_landing + docs_description: "If set to ON drone will land as a last phase of RTH." + docs_default_value: "ALWAYS" field: general.flags.rth_allow_landing table: nav_rth_allow_landing - name: nav_rth_alt_mode + docs_description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" + docs_default_value: "AT_LEAST" field: general.flags.rth_alt_control_mode table: nav_rth_alt_mode - name: nav_rth_abort_threshold + docs_description: "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]" + docs_default_value: "50000" field: general.rth_abort_threshold max: 65000 - name: nav_max_terrain_follow_alt field: general.max_terrain_follow_altitude max: 1000 - name: nav_rth_altitude + docs_description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" + docs_default_value: "1000" field: general.rth_altitude max: 65000 - name: nav_rth_home_altitude + docs_description: "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]" + docs_default_value: "0" field: general.rth_home_altitude max: 65000 - name: nav_rth_home_offset_distance + docs_description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" + docs_default_value: "0" field: general.rth_home_offset_distance max: 65000 - name: nav_rth_home_offset_direction + docs_description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" + docs_default_value: "0" field: general.rth_home_offset_direction max: 359 - name: nav_mc_bank_angle + docs_description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" + docs_default_value: "30" field: mc.max_bank_angle min: 15 max: 45 - name: nav_mc_hover_thr + docs_description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." + docs_default_value: "1500" field: mc.hover_throttle min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay + docs_description: "" + docs_default_value: "2000" field: mc.auto_disarm_delay min: 100 max: 10000 - name: nav_mc_braking_speed_threshold + docs_description: "min speed in cm/s above which braking can happen" + docs_default_value: "100" field: mc.braking_speed_threshold condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_disengage_speed + docs_description: "braking is disabled when speed goes below this value" + docs_default_value: "75" field: mc.braking_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_timeout + docs_description: "timeout in ms for braking" + docs_default_value: "2000" field: mc.braking_timeout condition: USE_MR_BRAKING_MODE min: 100 max: 5000 - name: nav_mc_braking_boost_factor + docs_description: "acceleration factor for BOOST phase" + docs_default_value: "100" field: mc.braking_boost_factor condition: USE_MR_BRAKING_MODE min: 0 max: 200 - name: nav_mc_braking_boost_timeout + docs_description: "how long in ms BOOST phase can happen" + docs_default_value: "750" field: mc.braking_boost_timeout condition: USE_MR_BRAKING_MODE min: 0 max: 5000 - name: nav_mc_braking_boost_speed_threshold + docs_description: "BOOST can be enabled when speed is above this value" + docs_default_value: "150" field: mc.braking_boost_speed_threshold condition: USE_MR_BRAKING_MODE min: 100 max: 1000 - name: nav_mc_braking_boost_disengage_speed + docs_description: "BOOST will be disabled when speed goes below this value" + docs_default_value: "100" field: mc.braking_boost_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_bank_angle + docs_description: "max angle that MR is allowed to bank in BOOST mode" + docs_default_value: "40" field: mc.braking_bank_angle condition: USE_MR_BRAKING_MODE min: 15 max: 60 - name: nav_mc_pos_deceleration_time + docs_description: "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" + docs_default_value: "120" field: mc.posDecelerationTime condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_expo + docs_description: "Expo for PosHold control" + docs_default_value: "10" field: mc.posResponseExpo condition: USE_NAV min: 0 max: 255 - name: nav_fw_cruise_thr + docs_description: "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 )" + docs_default_value: "1400" field: fw.cruise_throttle min: 1000 max: 2000 - name: nav_fw_min_thr + docs_description: "Minimum throttle for flying wing in GPS assisted modes" + docs_default_value: "1200" field: fw.min_throttle min: 1000 max: 2000 - name: nav_fw_max_thr + docs_description: "Maximum throttle for flying wing in GPS assisted modes" + docs_default_value: "1700" field: fw.max_throttle min: 1000 max: 2000 - name: nav_fw_bank_angle + docs_description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" + docs_default_value: "20" field: fw.max_bank_angle min: 5 max: 80 - name: nav_fw_climb_angle + docs_description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + docs_default_value: "20" field: fw.max_climb_angle min: 5 max: 80 - name: nav_fw_dive_angle + docs_description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + docs_default_value: "15" field: fw.max_dive_angle min: 5 max: 80 - name: nav_fw_pitch2thr + docs_description: "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)" + docs_default_value: "10" field: fw.pitch_to_throttle min: 0 max: 100 - name: nav_fw_loiter_radius + docs_description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" + docs_default_value: "5000" field: fw.loiter_radius min: 0 max: 10000 - name: nav_fw_cruise_speed + docs_description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" + docs_default_value: "0" field: fw.cruise_speed min: 0 max: 65535 - name: nav_fw_control_smoothness + docs_description: "How smoothly the autopilot controls the airplane to correct the navigation error" + docs_default_value: "0" field: fw.control_smoothness min: 0 max: 9 - name: nav_fw_land_dive_angle + docs_description: "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" + docs_default_value: "2" field: fw.land_dive_angle condition: NAV_FIXED_WING_LANDING min: -20 max: 20 - name: nav_fw_launch_velocity + docs_description: "Forward velocity threshold for swing-launch detection [cm/s]" + docs_default_value: "300" field: fw.launch_velocity_thresh min: 100 max: 10000 - name: nav_fw_launch_accel + docs_description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + docs_default_value: "1863" field: fw.launch_accel_thresh min: 1000 max: 20000 - name: nav_fw_launch_max_angle + docs_description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" + docs_default_value: "45" field: fw.launch_max_angle min: 5 max: 180 - name: nav_fw_launch_detect_time + docs_description: "Time for which thresholds have to breached to consider launch happened [ms]" + docs_default_value: "40" field: fw.launch_time_thresh min: 10 max: 1000 - name: nav_fw_launch_thr + docs_description: "Launch throttle - throttle to be set during launch sequence (pwm units)" + docs_default_value: "1700" field: fw.launch_throttle min: 1000 max: 2000 - name: nav_fw_launch_idle_thr + docs_description: "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)" + docs_default_value: "1000" field: fw.launch_idle_throttle min: 1000 max: 2000 - name: nav_fw_launch_motor_delay + docs_description: "Delay between detected launch and launch sequence start and throttling up (ms)" + docs_default_value: "500" field: fw.launch_motor_timer min: 0 max: 5000 - name: nav_fw_launch_spinup_time + docs_description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" + docs_default_value: "100" field: fw.launch_motor_spinup_time min: 0 max: 1000 - name: nav_fw_launch_min_time + docs_description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." + docs_default_value: "0" field: fw.launch_min_time min: 0 max: 60000 - name: nav_fw_launch_timeout + docs_description: "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)" + docs_default_value: "5000" field: fw.launch_timeout max: 60000 - name: nav_fw_launch_max_altitude + docs_description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." + docs_default_value: "0" field: fw.launch_max_altitude min: 0 max: 60000 - name: nav_fw_launch_climb_angle + docs_description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" + docs_default_value: "18" field: fw.launch_climb_angle min: 5 max: 45 - name: nav_fw_cruise_yaw_rate + docs_description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" + docs_default_value: "20" field: fw.cruise_yaw_rate min: 0 max: 60 - name: nav_fw_allow_manual_thr_increase + docs_description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" + docs_default_value: "OFF" field: fw.allow_manual_thr_increase type: bool - name: nav_use_fw_yaw_control + docs_description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" + docs_default_value: "OFF" field: fw.useFwNavYawControl type: bool - name: nav_fw_yaw_deadband + docs_description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" + docs_default_value: "0" field: fw.yawControlDeadband min: 0 max: 90 @@ -1695,92 +2337,136 @@ groups: condition: USE_TELEMETRY members: - name: telemetry_switch + docs_description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." + docs_default_value: "OFF" type: bool - name: telemetry_inverted + docs_description: "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." + docs_default_value: "OFF" type: bool - name: frsky_default_latitude + docs_description: "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." + docs_default_value: "0.000" field: gpsNoFixLatitude min: -90 max: 90 - name: frsky_default_longitude + docs_description: "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." + docs_default_value: "0.000" field: gpsNoFixLongitude min: -180 max: 180 - name: frsky_coordinates_format + docs_description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" + docs_default_value: "0" field: frsky_coordinate_format min: 0 max: FRSKY_FORMAT_NMEA type: uint8_t # TODO: This seems to use an enum, we should use table: - name: frsky_unit + docs_description: "Not used? [METRIC/IMPERIAL]" + docs_default_value: "METRIC" table: frsky_unit type: uint8_t - name: frsky_vfas_precision + docs_description: "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" + docs_default_value: "0" min: FRSKY_VFAS_PRECISION_LOW max: FRSKY_VFAS_PRECISION_HIGH - name: frsky_pitch_roll + docs_description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" + docs_default_value: "OFF" type: bool - name: report_cell_voltage + docs_description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" + docs_default_value: "OFF" type: bool - name: hott_alarm_sound_interval + docs_description: "Battery alarm delay in seconds for Hott telemetry" + docs_default_value: "5" field: hottAlarmSoundInterval min: 0 max: 120 - name: telemetry_halfduplex + docs_description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" + docs_default_value: "OFF" field: halfDuplex type: bool - name: smartport_fuel_unit + docs_description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" + docs_default_value: "MAH" field: smartportFuelUnit condition: USE_TELEMETRY_SMARTPORT type: uint8_t table: smartport_fuel_unit - name: ibus_telemetry_type + docs_description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." + docs_default_value: "0" field: ibusTelemetryType min: 0 max: 255 - name: ltm_update_rate + docs_description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." + docs_default_value: "NORMAL" field: ltmUpdateRate condition: USE_TELEMETRY_LTM table: ltm_rates - name: sim_ground_station_number + docs_description: "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." + docs_default_value: "Empty string" field: simGroundStationNumber condition: USE_TELEMETRY_SIM type: string max: 16 - name: sim_pin + docs_description: "PIN code for the SIM module" + docs_default_value: "Empty string" field: simPin condition: USE_TELEMETRY_SIM type: string max: 8 - name: sim_transmit_interval + docs_description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" + docs_default_value: "60" field: simTransmitInterval condition: USE_TELEMETRY_SIM type: uint16_t min: SIM_MIN_TRANSMIT_INTERVAL max: 65535 - name: sim_transmit_flags + docs_description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" + docs_default_value: "F" field: simTransmitFlags condition: USE_TELEMETRY_SIM type: string max: SIM_N_TX_FLAGS - name: acc_event_threshold_high + docs_description: "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." + docs_default_value: "0" field: accEventThresholdHigh condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: acc_event_threshold_low + docs_description: "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." + docs_default_value: "0" field: accEventThresholdLow condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 900 - name: acc_event_threshold_neg_x + docs_description: "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." + docs_default_value: "0" field: accEventThresholdNegX condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: sim_low_altitude + docs_description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." + docs_default_value: "0" field: simLowAltitude condition: USE_TELEMETRY_SIM type: int16_t @@ -1848,6 +2534,8 @@ groups: condition: USE_LED_STRIP members: - name: ledstrip_visual_beeper + docs_description: "" + docs_default_value: "OFF" type: bool - name: PG_OSD_CONFIG @@ -1856,85 +2544,125 @@ groups: condition: USE_OSD members: - name: osd_video_system + docs_description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" + docs_default_value: "AUTO" table: osd_video_system field: video_system type: uint8_t - name: osd_row_shiftdown + docs_description: "Number of rows to shift the OSD display (increase if top rows are cut off)" + docs_default_value: "0" field: row_shiftdown min: 0 max: 1 - name: osd_units + docs_description: "IMPERIAL, METRIC, UK" + docs_default_value: "METRIC" field: units table: osd_unit type: uint8_t - name: osd_stats_energy_unit + docs_description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" + docs_default_value: "MAH" field: stats_energy_unit table: osd_stats_energy_unit type: uint8_t - name: osd_rssi_alarm + docs_description: "Value bellow which to make the OSD RSSI indicator blink" + docs_default_value: "20" field: rssi_alarm min: 0 max: 100 - name: osd_time_alarm + docs_description: "Value above which to make the OSD flight time indicator blink (minutes)" + docs_default_value: "10" field: time_alarm min: 0 max: 600 - name: osd_alt_alarm + docs_description: "Value above which to make the OSD relative altitude indicator blink (meters)" + docs_default_value: "100" field: alt_alarm min: 0 max: 10000 - name: osd_dist_alarm + docs_description: "Value above which to make the OSD distance from home indicator blink (meters)" + docs_default_value: "1000" field: dist_alarm min: 0 max: 50000 - name: osd_neg_alt_alarm + docs_description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" + docs_default_value: "5" field: neg_alt_alarm min: 0 max: 10000 - name: osd_current_alarm + docs_description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." + docs_default_value: "0" field: current_alarm min: 0 max: 255 - name: osd_gforce_alarm + docs_description: "Value above which the OSD g force indicator will blink (g)" + docs_default_value: "5" field: gforce_alarm min: 0 max: 20 - name: osd_gforce_axis_alarm_min + docs_description: "Value under which the OSD axis g force indicators will blink (g)" + docs_default_value: "-5" field: gforce_axis_alarm_min min: -20 max: 20 - name: osd_gforce_axis_alarm_max + docs_description: "Value above which the OSD axis g force indicators will blink (g)" + docs_default_value: "5" field: gforce_axis_alarm_max min: -20 max: 20 - name: osd_imu_temp_alarm_min + docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: imu_temp_alarm_min min: -550 max: 1250 - name: osd_imu_temp_alarm_max + docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "600" field: imu_temp_alarm_max min: -550 max: 1250 - name: osd_esc_temp_alarm_max + docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "900" field: esc_temp_alarm_max min: -550 max: 1500 - name: osd_esc_temp_alarm_min + docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: esc_temp_alarm_min min: -550 max: 1500 - name: osd_baro_temp_alarm_min + docs_description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "-200" field: baro_temp_alarm_min condition: USE_BARO min: -550 max: 1250 - name: osd_baro_temp_alarm_max + docs_description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" + docs_default_value: "600" field: baro_temp_alarm_max condition: USE_BARO min: -550 max: 1250 - name: osd_temp_label_align + docs_description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" + docs_default_value: "LEFT" field: temp_label_align condition: USE_TEMPERATURE_SENSOR table: osd_alignment @@ -1944,6 +2672,8 @@ groups: field: ahi_reverse_roll type: bool - name: osd_artificial_horizon_max_pitch + docs_description: "Max pitch, in degrees, for OSD artificial horizon" + docs_default_value: "20" field: ahi_max_pitch min: 10 max: 90 @@ -1998,6 +2728,8 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp + docs_description: "Controls display of the next waypoints in the HUD." + docs_default_value: "OFF" field: hud_wp_disp min: 0 max: 3 @@ -2013,6 +2745,8 @@ groups: field: sidebar_scroll_arrows type: bool - name: osd_main_voltage_decimals + docs_description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." + docs_default_value: "1" field: main_voltage_decimals min: 1 max: 2 @@ -2022,11 +2756,15 @@ groups: max: 11 - name: osd_estimations_wind_compensation + docs_description: "Use wind estimation for remaining flight time/distance estimation" + docs_default_value: "ON" condition: USE_WIND_ESTIMATOR field: estimations_wind_compensation type: bool - name: osd_failsafe_switch_layout + docs_description: "If enabled the OSD automatically switches to the first layout during failsafe" + docs_default_value: "OFF" type: bool - name: osd_plus_code_digits @@ -2035,6 +2773,8 @@ groups: max: 13 - name: osd_ahi_style + docs_description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." + docs_default_value: "DEFAULT" table: osd_ahi_style - name: PG_SYSTEM_CONFIG @@ -2042,25 +2782,35 @@ groups: headers: ["fc/config.h"] members: - name: i2c_speed + docs_description: "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)" + docs_default_value: "400KHZ" condition: USE_I2C table: i2c_speed - name: cpu_underclock + docs_description: "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" + docs_default_value: "OFF" field: cpuUnderclock condition: USE_UNDERCLOCK type: bool - name: debug_mode table: debug_modes - name: throttle_tilt_comp_str + docs_description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." + docs_default_value: "0" field: throttle_tilt_compensation_strength min: 0 max: 100 - name: name + docs_description: "Craft name" + docs_default_value: "Empty string" - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG type: modeActivationOperatorConfig_t headers: ["fc/rc_modes.h"] members: - name: mode_range_logic_operator + docs_description: "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." + docs_default_value: "OR" field: modeActivationOperator table: aux_operator type: uint8_t @@ -2071,11 +2821,17 @@ groups: condition: USE_STATS members: - name: stats + docs_description: "General switch of the statistics recording feature (a.k.a. odometer)" + docs_default_value: "OFF" field: stats_enabled type: bool - name: stats_total_time + docs_description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." + docs_default_value: "0" max: INT32_MAX - name: stats_total_dist + docs_description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." + docs_default_value: "0" max: INT32_MAX - name: stats_total_energy max: INT32_MAX @@ -2086,9 +2842,13 @@ groups: headers: ["common/time.h"] members: - name: tz_offset + docs_description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" + docs_default_value: "0" min: -1440 max: 1440 - name: tz_automatic_dst + docs_description: "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`." + docs_default_value: "OFF" type: uint8_t table: tz_automatic_dst @@ -2097,6 +2857,8 @@ groups: headers: ["drivers/display.h"] members: - name: display_force_sw_blink + docs_description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" + docs_default_value: "OFF" field: force_sw_blink type: bool @@ -2106,6 +2868,8 @@ groups: condition: USE_VTX_CONTROL members: - name: vtx_halfduplex + docs_description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." + docs_default_value: "ON" field: halfDuplex type: bool @@ -2114,18 +2878,26 @@ groups: headers: ["drivers/vtx_common.h", "io/vtx.h"] members: - name: vtx_band + docs_description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." + docs_default_value: "4" field: band min: VTX_SETTINGS_NO_BAND max: VTX_SETTINGS_MAX_BAND - name: vtx_channel + docs_description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." + docs_default_value: "1" field: channel min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_power + docs_description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." + docs_default_value: "1" field: power min: VTX_SETTINGS_MIN_POWER max: VTX_SETTINGS_MAX_POWER - name: vtx_low_power_disarm + docs_description: "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." + docs_default_value: "OFF" field: lowPowerDisarm table: vtx_low_power_disarm type: uint8_t diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py new file mode 100755 index 0000000000..35534291f0 --- /dev/null +++ b/src/utils/update_cli_docs.py @@ -0,0 +1,131 @@ +#!/usr/bin/env python3 + +import re +from sys import argv +import yaml + +CLI_MD_PATH = "docs/Cli.md" +SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" + +CLI_MD_SECTION_HEADER = "## CLI Variable Reference" + +def read_cli_md(): + with open(CLI_MD_PATH, "r") as cli_md: + return cli_md.readlines() + +def parse_params_from_md_table(cli_md_lines): + table_offset = cli_md_lines.index("## CLI Variable Reference\n") + 4 + params, i = {}, table_offset + while cli_md_lines[i] != "" and i < len(cli_md_lines) - 1: + param = [ s.strip() for s in cli_md_lines[i].strip("\n").split("|") ][1:-1] + params[param[0]] = { 'default': param[1], 'description': param[2] } + i += 1 + return params + +def read_settings_yaml(): + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: + return settings_yaml.readlines() + +def update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines): + new_lines = [] + skip = False + for line in settings_yaml_lines: + if skip: + if line == "\n": + skip = False + elif line.startswith("tables:"): + skip = True + elif "- name:" in line: + for param in cli_md_params: + match = re.match("^\\s+- name: {}\n$".format(param), line) + if match: + match = match.group(0) + prefix = match[:match.index("- name: ") + 8] + line = "{}\n{}\"{}\"\n".format( + match.strip("\n"), + prefix.replace("- name", " docs_description"), + cli_md_params[param]['description'].replace("\"", "\\\""), + ) + if cli_md_params[param]['default']: + line = "{}{}\"{}\"\n".format( + line, + prefix.replace("- name", " docs_default_value"), + cli_md_params[param]['default'].replace("\"", "\\\""), + ) + cli_md_params[param]['documented'] = True + break + new_lines.append(line) + + for param in cli_md_params: + if not "documented" in cli_md_params[param] or not cli_md_params[param]['documented']: + print("\"{}\" is undocumented".format(param)) + + return new_lines + +def write_settings_yaml(lines): + with open(SETTINGS_YAML_PATH, "w") as settings_yaml: + settings_yaml.writelines(lines) + +def parse_settings_yaml(): + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: + return yaml.load(settings_yaml, Loader=yaml.Loader) + +def generate_md_table_from_yaml(settings_yaml): + params = {} + for group in settings_yaml['groups']: + for member in group['members']: + if any(key in member for key in ["docs_description", "docs_default_value"]): + params[member['name']] = { + "description": member["docs_description"], + "default": member["docs_default_value"] if "docs_default_value" in member else "" + } + + md_table_lines = [ + "| Variable Name | Default Value | Description |\n", + "| ------------- | ------------- | ----------- |\n", + ] + for param in sorted(params.items()): + md_table_lines.append("| {} | {} | {} |\n".format(param[0], param[1]['default'], param[1]['description'])) + + return md_table_lines + +def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): + new_lines = [] + lines_to_skip = 0 + skip_until_empty_line = False + for line in cli_md_lines: + if lines_to_skip > 0: + lines_to_skip -= 1 + if lines_to_skip == 0: + skip_until_empty_line = True + continue + elif skip_until_empty_line: + if line != "\n": + continue + else: + skip_until_empty_line = False + new_lines.append("\n") + new_lines += md_table_lines + if line.startswith(CLI_MD_SECTION_HEADER): + lines_to_skip = 2 + new_lines.append(line) + return new_lines + +def write_cli_md(lines): + with open(CLI_MD_PATH, "w") as cli_md: + cli_md.writelines(lines) + +if __name__ == "__main__": + if len(argv) == 2 and argv[1] == "--reverse": + cli_md_lines = read_cli_md() + cli_md_params = parse_params_from_md_table(cli_md_lines) + settings_yaml_lines = read_settings_yaml() + settings_yaml_lines = update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines) + write_settings_yaml(settings_yaml_lines) + else: + settings_yaml = parse_settings_yaml() + md_table_lines = generate_md_table_from_yaml(settings_yaml) + cli_md_lines = read_cli_md() + cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) + write_cli_md(cli_md_lines) + From 551b045b64b4bca5bdb300b8d64035e6e981a8e5 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 15 Jun 2020 16:55:58 +0200 Subject: [PATCH 04/16] Remove code for markdown->yaml transition --- src/utils/update_cli_docs.py | 97 ++++++++++-------------------------- 1 file changed, 25 insertions(+), 72 deletions(-) diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index 35534291f0..4fe2bacd35 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -1,95 +1,54 @@ #!/usr/bin/env python3 -import re -from sys import argv -import yaml +import yaml # pyyaml / python-yaml CLI_MD_PATH = "docs/Cli.md" SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" CLI_MD_SECTION_HEADER = "## CLI Variable Reference" +# Read the contents of the markdown CLI docs def read_cli_md(): with open(CLI_MD_PATH, "r") as cli_md: return cli_md.readlines() -def parse_params_from_md_table(cli_md_lines): - table_offset = cli_md_lines.index("## CLI Variable Reference\n") + 4 - params, i = {}, table_offset - while cli_md_lines[i] != "" and i < len(cli_md_lines) - 1: - param = [ s.strip() for s in cli_md_lines[i].strip("\n").split("|") ][1:-1] - params[param[0]] = { 'default': param[1], 'description': param[2] } - i += 1 - return params - -def read_settings_yaml(): - with open(SETTINGS_YAML_PATH, "r") as settings_yaml: - return settings_yaml.readlines() - -def update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines): - new_lines = [] - skip = False - for line in settings_yaml_lines: - if skip: - if line == "\n": - skip = False - elif line.startswith("tables:"): - skip = True - elif "- name:" in line: - for param in cli_md_params: - match = re.match("^\\s+- name: {}\n$".format(param), line) - if match: - match = match.group(0) - prefix = match[:match.index("- name: ") + 8] - line = "{}\n{}\"{}\"\n".format( - match.strip("\n"), - prefix.replace("- name", " docs_description"), - cli_md_params[param]['description'].replace("\"", "\\\""), - ) - if cli_md_params[param]['default']: - line = "{}{}\"{}\"\n".format( - line, - prefix.replace("- name", " docs_default_value"), - cli_md_params[param]['default'].replace("\"", "\\\""), - ) - cli_md_params[param]['documented'] = True - break - new_lines.append(line) - - for param in cli_md_params: - if not "documented" in cli_md_params[param] or not cli_md_params[param]['documented']: - print("\"{}\" is undocumented".format(param)) - - return new_lines - -def write_settings_yaml(lines): - with open(SETTINGS_YAML_PATH, "w") as settings_yaml: - settings_yaml.writelines(lines) - +# Parse the YAML settings specs def parse_settings_yaml(): with open(SETTINGS_YAML_PATH, "r") as settings_yaml: return yaml.load(settings_yaml, Loader=yaml.Loader) def generate_md_table_from_yaml(settings_yaml): + """Generate a sorted markdown table with description & default value for each setting""" params = {} + + # Extract description and default value of each setting from the YAML specs (if present) for group in settings_yaml['groups']: for member in group['members']: if any(key in member for key in ["docs_description", "docs_default_value"]): params[member['name']] = { - "description": member["docs_description"], + "description": member["docs_description"] if "docs_description" in member else "", "default": member["docs_default_value"] if "docs_default_value" in member else "" } - + + # MD table header md_table_lines = [ "| Variable Name | Default Value | Description |\n", "| ------------- | ------------- | ----------- |\n", ] + + # Sort the settings by name and build the rows of the table for param in sorted(params.items()): md_table_lines.append("| {} | {} | {} |\n".format(param[0], param[1]['default'], param[1]['description'])) - + + # Return the assembled table return md_table_lines def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): + """Update the settings table in the CLI docs + + Copy all the original lines up to $CLI_MD_SECTION_HEADER (including the following newline), then insert + the updated table in place of the next block of text (replace everything until an empty line is found). + """ new_lines = [] lines_to_skip = 0 skip_until_empty_line = False @@ -109,23 +68,17 @@ def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): if line.startswith(CLI_MD_SECTION_HEADER): lines_to_skip = 2 new_lines.append(line) + return new_lines +# Write the contents of the markdown CLI docs def write_cli_md(lines): with open(CLI_MD_PATH, "w") as cli_md: cli_md.writelines(lines) if __name__ == "__main__": - if len(argv) == 2 and argv[1] == "--reverse": - cli_md_lines = read_cli_md() - cli_md_params = parse_params_from_md_table(cli_md_lines) - settings_yaml_lines = read_settings_yaml() - settings_yaml_lines = update_settings_yaml_from_cli_md(cli_md_params, settings_yaml_lines) - write_settings_yaml(settings_yaml_lines) - else: - settings_yaml = parse_settings_yaml() - md_table_lines = generate_md_table_from_yaml(settings_yaml) - cli_md_lines = read_cli_md() - cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) - write_cli_md(cli_md_lines) - + settings_yaml = parse_settings_yaml() + md_table_lines = generate_md_table_from_yaml(settings_yaml) + cli_md_lines = read_cli_md() + cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) + write_cli_md(cli_md_lines) From 46fc7f8e475696aef1ea15a6aa96dc814b3c19b3 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Sun, 21 Jun 2020 14:47:09 +0200 Subject: [PATCH 05/16] Move docs to Settings.md and drop "docs_" YAML prefix --- docs/Cli.md | 450 +--------- docs/Settings.md | 393 +++++++++ src/main/fc/settings.yaml | 1544 +++++++++++++++++----------------- src/utils/update_cli_docs.py | 61 +- 4 files changed, 1181 insertions(+), 1267 deletions(-) create mode 100644 docs/Settings.md diff --git a/docs/Cli.md b/docs/Cli.md index 391182da54..a538fb2ccd 100644 --- a/docs/Cli.md +++ b/docs/Cli.md @@ -125,452 +125,4 @@ A shorter form is also supported to enable and disable functions using `serial < ## CLI Variable Reference -| Variable Name | Default Value | Description | -| ------------- | ------------- | ----------- | -| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | -| 3d_deadband_low | 1406 | 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) | -| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | -| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | -| acc_event_threshold_high | 0 | 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. | -| acc_event_threshold_low | 0 | 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. | -| acc_event_threshold_neg_x | 0 | 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. | -| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| acc_lpf_hz | 15 | 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. | -| acc_lpf_type | BIQUAD | 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. | -| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| airspeed_adc_channel | 0 | 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 | -| align_acc | DEFAULT | 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. | -| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_gyro | DEFAULT | 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. | -| align_mag | DEFAULT | 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. | -| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | -| align_mag_roll | 0 | 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. | -| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | -| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | -| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | -| antigravity_accelerator | 1 | | -| antigravity_cutoff_lpf_hz | 15 | 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 | -| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | -| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | -| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | -| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | -| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | -| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | -| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | -| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | -| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | -| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | -| blackbox_device | SPIFLASH | Selection of where to write blackbox data | -| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | -| blackbox_rate_num | 1 | 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 | -| cpu_underclock | OFF | 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 | -| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | -| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | -| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | -| current_meter_scale | 400 | 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. | -| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | -| deadband | 5 | 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. | -| disarm_kill_switch | ON | 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. | -| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | -| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | -| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dterm_lpf_hz | 40 | 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 | -| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | -| dynamic_gyro_notch_min_hz | 150 | 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` | -| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | -| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | -| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | -| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | -| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | -| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | -| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | -| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | -| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | -| failsafe_min_distance | 0 | 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. | -| failsafe_min_distance_procedure | DROP | 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). | -| failsafe_mission | ON | 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 | -| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | -| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | -| failsafe_stick_threshold | 50 | 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. | -| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | -| fixed_wing_auto_arm | OFF | 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. | -| flaperon_throw_offset | 200 | 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. | -| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | -| frsky_default_latitude | 0.000 | 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. | -| frsky_default_longitude | 0.000 | 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. | -| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | -| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | -| frsky_vfas_precision | 0 | 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 | -| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | -| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | -| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | -| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | -| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | -| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | -| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | -| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | -| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | -| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | -| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | -| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | -| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | -| fw_iterm_limit_stick_position | 0.5 | 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 | -| fw_iterm_throw_limit | 165 | 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. | -| fw_loiter_direction | RIGHT | 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. | -| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | -| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | -| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | -| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | -| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | -| fw_reference_airspeed | 1000 | 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. | -| fw_tpa_time_constant | 0 | 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 | -| fw_turn_assist_yaw_gain | 1 | 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 | -| gps_auto_baud | ON | 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 | -| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | -| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | -| gps_min_sats | 6 | 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. | -| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | -| gps_sbas_mode | NONE | Which SBAS mode to be used | -| gps_ublox_use_galileo | OFF | 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]. | -| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | -| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | -| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | -| has_flaps | OFF | 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 | -| heading_hold_rate_limit | 90 | 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. | -| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | -| i2c_speed | 400KHZ | 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) | -| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | -| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | -| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | -| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | -| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | -| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | -| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | -| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | -| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | -| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | -| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | -| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | -| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | -| inav_reset_altitude | FIRST_ARM | 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) | -| inav_reset_home | FIRST_ARM | 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 | -| inav_use_gps_velned | ON | 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. | -| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | -| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | -| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | -| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | -| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | -| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | -| inav_w_z_gps_v | 0.500 | 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 | -| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | -| iterm_windup | 50 | 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) | -| ledstrip_visual_beeper | OFF | | -| looptime | 1000 | 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. | -| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | -| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | -| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | -| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | -| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | -| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH | -| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | -| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | -| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL | -| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL | -| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW | -| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | -| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW | -| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW | -| mc_p_level | 20 | Multicopter attitude stabilisation P-gain | -| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff | -| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point | -| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | -| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | -| fw_ff_pitch| 50 | Fixed-wing rate stabilisation FF-gain for PITCH | -| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | -| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | -| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | -| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | -| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | -| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | -| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | -| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | -| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | -| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | -| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | -| fw_iterm_limit_stick_position | 0.5 | 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 | -| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | -| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | -| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | -| acc_lpf_hz | 15 | 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. | -| acc_lpf_type | BIQUAD | 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. | -| dterm_lpf_hz | 40 | 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 | -| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | -| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | -| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | -| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | -| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | -| dynamic_gyro_notch_min_hz | 150 | 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` | -| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | -| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | -| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | -| rpm_gyro_min_hz | 150 | 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` | -| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | -| pidsum_limit | 500 | 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 | -| pidsum_limit_yaw | 400 | 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 | -| `pid_type` | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | -| iterm_windup | 50 | 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) | -| rate_accel_limit_roll_pitch | 0 | 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. | -| rate_accel_limit_yaw | 10000 | 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. | -| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | -| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | -| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] | -| manual rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | -| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | -| thr_expo | 0 | Throttle exposition value | -| roll_rate | 20 | 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. | -| pitch_rate | 20 | 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. | -| yaw_rate | 20 | 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. | -| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% | -| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | -| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | -| tpa_rate | 0 | 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. | -| tpa_breakpoint | 1500 | See tpa_rate. | -| fw_tpa_time_constant | 0 | 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 | -| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | -| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | -| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | -| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | -| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | -| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | -| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | -| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | -| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | -| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | -| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | -| airspeed_adc_channel | 0 | 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 | -| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | -| has_flaps | OFF | 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 | -| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. | -| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | -| tz_automatic_dst | OFF | 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`. | -| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | -| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | -| vtx_freq | 5740 | Set the VTX frequency using raw MHz. This parameter is ignored unless `vtx_band` is 0. | -| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | -| vtx_low_power_disarm | OFF | 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. | -| vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. | -| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | -| vtx_max_power_override | 0 | 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 it's capabilities | -| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | -| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | -| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | -| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | -| motor_pwm_rate | 400 | 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. | -| name | Empty string | Craft name | -| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | -| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | -| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | -| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | -| nav_extra_arming_safety | ON | 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 | -| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | -| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | -| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | -| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | -| nav_fw_cruise_thr | 1400 | 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 ) | -| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | -| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | -| nav_fw_land_dive_angle | 2 | 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 | -| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | -| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | -| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | -| nav_fw_launch_idle_thr | 1000 | 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) | -| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | -| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | -| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | -| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | -| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_timeout | 5000 | 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) | -| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | -| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | -| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | -| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | -| nav_fw_pitch2thr | 10 | 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) | -| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | -| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | -| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | -| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | -| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | -| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | -| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | -| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | -| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_mc_auto_disarm_delay | 2000 | | -| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | -| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | -| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | -| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | -| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | -| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | -| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | -| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | -| nav_mc_braking_timeout | 2000 | timeout in ms for braking | -| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | -| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | -| nav_mc_pos_deceleration_time | 120 | 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 | -| nav_mc_pos_expo | 10 | Expo for PosHold control | -| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | -| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | -| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | -| nav_mc_vel_xy_i | 15 | 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 | -| nav_mc_vel_xy_p | 40 | 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 | -| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | -| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | -| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | -| nav_min_rth_distance | 500 | 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. | -| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | -| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | -| nav_rth_abort_threshold | 50000 | 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] | -| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | -| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | -| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | -| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | -| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | -| nav_rth_home_altitude | 0 | 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] | -| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | -| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | -| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | -| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | -| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | -| nav_user_control_mode | ATTI | 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. | -| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | -| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | -| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | -| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | -| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | -| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | -| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | -| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | -| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | -| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | -| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | -| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | -| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | -| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | -| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | -| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | -| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | -| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | -| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | -| osd_units | METRIC | IMPERIAL, METRIC, UK | -| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | -| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | -| pidsum_limit | 500 | 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 | -| pidsum_limit_yaw | 400 | 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 | -| pitch_rate | 20 | 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. | -| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | -| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | -| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | -| rate_accel_limit_roll_pitch | 0 | 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. | -| rate_accel_limit_yaw | 10000 | 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. | -| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | -| rc_filter_frequency | 50 | 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 | -| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | -| reboot_character | 82 | Special character used to trigger reboot | -| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | -| roll_rate | 20 | 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. | -| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | -| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | -| rpm_gyro_min_hz | 150 | 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` | -| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | -| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | -| rssi_channel | 0 | RX channel containing the RSSI signal | -| rssi_max | 100 | 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. | -| rssi_min | 0 | 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). | -| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | -| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | -| rx_max_usec | 2115 | 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. | -| rx_min_usec | 885 | 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. | -| sdcard_detect_inverted | `TARGET dependent` | 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. | -| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | -| serialrx_inverted | OFF | 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). | -| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | -| servo_center_pulse | 1500 | Servo midpoint | -| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | -| servo_protocol | PWM | 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) | -| servo_pwm_rate | 50 | 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. | -| sim_ground_station_number | Empty string | 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. | -| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | -| sim_pin | Empty string | PIN code for the SIM module | -| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | -| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | -| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | -| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | -| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | -| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | -| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | -| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | -| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | -| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | -| telemetry_inverted | OFF | 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. | -| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | -| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | -| thr_expo | 0 | Throttle exposition value | -| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | -| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | -| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | -| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | -| tpa_breakpoint | 1500 | See tpa_rate. | -| tpa_rate | 0 | 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. | -| tri_unarmed_servo | ON | 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. | -| tz_automatic_dst | OFF | 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`. | -| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | -| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | -| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | -| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | -| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | -| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | -| vbat_scale | 1100 | 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. | -| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | -| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | -| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | -| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | -| vtx_low_power_disarm | OFF | 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. | -| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | -| yaw_deadband | 5 | 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. | -| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | -| yaw_rate | 20 | 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. | - - > Note: this table is autogenerated. Do not edit it manually. +See [Settings.md](Settings.md). diff --git a/docs/Settings.md b/docs/Settings.md new file mode 100644 index 0000000000..8e3ca620fd --- /dev/null +++ b/docs/Settings.md @@ -0,0 +1,393 @@ +# CLI Variable Reference + +| Variable Name | Default Value | Description | +| ------------- | ------------- | ----------- | +| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) | +| 3d_deadband_low | 1406 | 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) | +| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | +| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode | +| acc_event_threshold_high | 0 | 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. | +| acc_event_threshold_low | 0 | 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. | +| acc_event_threshold_neg_x | 0 | 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. | +| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| acc_lpf_hz | 15 | 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. | +| acc_lpf_type | BIQUAD | 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. | +| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | +| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. | +| airspeed_adc_channel | 0 | 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 | +| align_acc | DEFAULT | 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. | +| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | +| align_gyro | DEFAULT | 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. | +| align_mag | DEFAULT | 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. | +| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. | +| align_mag_roll | 0 | 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. | +| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. | +| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) | +| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] | +| antigravity_accelerator | 1 | | +| antigravity_cutoff_lpf_hz | 15 | 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 | +| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | +| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. | +| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting | +| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation | +| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` | +| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | +| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. | +| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). | +| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | +| blackbox_device | SPIFLASH | Selection of where to write blackbox data | +| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. | +| blackbox_rate_num | 1 | 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 | +| cpu_underclock | OFF | 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 | +| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | +| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | +| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. | +| current_meter_scale | 400 | 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. | +| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. | +| deadband | 5 | 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. | +| disarm_kill_switch | ON | 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. | +| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON | +| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter | +| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dterm_lpf_hz | 40 | 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 | +| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter | +| dynamic_gyro_notch_min_hz | 150 | 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` | +| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches | +| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers | +| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | +| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb | +| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll | +| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn | +| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. | +| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | +| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | +| failsafe_min_distance | 0 | 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. | +| failsafe_min_distance_procedure | DROP | 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). | +| failsafe_mission | ON | 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 | +| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). | +| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | +| failsafe_stick_threshold | 50 | 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. | +| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | +| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout | +| fixed_wing_auto_arm | OFF | 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. | +| flaperon_throw_offset | 200 | 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. | +| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | +| frsky_default_latitude | 0.000 | 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. | +| frsky_default_longitude | 0.000 | 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. | +| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data | +| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] | +| frsky_vfas_precision | 0 | 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 | +| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] | +| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] | +| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot | +| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection | +| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot | +| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point | +| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH | +| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL | +| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW | +| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff | +| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH | +| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL | +| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW | +| fw_iterm_limit_stick_position | 0.5 | 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 | +| fw_iterm_throw_limit | 165 | 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. | +| fw_loiter_direction | RIGHT | 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. | +| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) | +| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain | +| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH | +| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL | +| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW | +| fw_reference_airspeed | 1000 | 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. | +| fw_tpa_time_constant | 0 | 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 | +| fw_turn_assist_yaw_gain | 1 | 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 | +| gps_auto_baud | ON | 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 | +| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. | +| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. | +| gps_min_sats | 6 | 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. | +| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). | +| gps_sbas_mode | NONE | Which SBAS mode to be used | +| gps_ublox_use_galileo | OFF | 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]. | +| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. | +| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. | +| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. | +| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) | +| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | +| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf | +| has_flaps | OFF | 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 | +| heading_hold_rate_limit | 90 | 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. | +| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry | +| i2c_speed | 400KHZ | 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) | +| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | +| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | +| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | +| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | +| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements | +| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements | +| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements | +| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements | +| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. | +| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] | +| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | +| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | +| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] | +| inav_reset_altitude | FIRST_ARM | 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) | +| inav_reset_home | FIRST_ARM | 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 | +| inav_use_gps_velned | ON | 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. | +| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation | +| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. | +| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed | +| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost | +| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate | +| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | +| inav_w_z_gps_v | 0.500 | 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 | +| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | +| iterm_windup | 50 | 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) | +| ledstrip_visual_beeper | OFF | | +| looptime | 1000 | 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. | +| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. | +| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. | +| mag_declination | 0 | 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. | +| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info | +| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | +| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | +| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | +| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | +| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% | +| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] | +| manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | +| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | +| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | +| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | +| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | +| max_check | 1900 | 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. | +| max_throttle | 1850 | 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. | +| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used | +| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. 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 `mc_airmode_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** mode. | +| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky | +| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH | +| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL | +| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW | +| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point | +| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH | +| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL | +| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW | +| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff | +| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH | +| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL | +| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW | +| mc_p_level | 20 | Multicopter attitude stabilisation P-gain | +| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH | +| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL | +| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW | +| min_check | 1100 | 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. | +| min_command | 1000 | 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. | +| mode_range_logic_operator | OR | 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. | +| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. | +| moron_threshold | 32 | 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. | +| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | +| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] | +| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. | +| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED | +| motor_pwm_rate | 400 | 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. | +| name | Empty string | Craft name | +| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | +| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] | +| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing | +| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] | +| nav_extra_arming_safety | ON | 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 | +| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing | +| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | +| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error | +| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | +| nav_fw_cruise_thr | 1400 | 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 ) | +| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | +| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | +| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) | +| nav_fw_land_dive_angle | 2 | 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 | +| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | +| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | +| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] | +| nav_fw_launch_idle_thr | 1000 | 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) | +| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. | +| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | +| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | +| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) | +| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller | +| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) | +| nav_fw_launch_timeout | 5000 | 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) | +| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] | +| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | +| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes | +| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes | +| nav_fw_pitch2thr | 10 | 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) | +| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | +| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero | +| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH | +| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) | +| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) | +| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | +| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] | +| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] | +| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] | +| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | +| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | +| nav_mc_auto_disarm_delay | 2000 | | +| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude | +| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode | +| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value | +| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase | +| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value | +| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen | +| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value | +| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen | +| nav_mc_braking_timeout | 2000 | timeout in ms for braking | +| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) | +| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | +| nav_mc_pos_deceleration_time | 120 | 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 | +| nav_mc_pos_expo | 10 | Expo for PosHold control | +| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity | +| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) | +| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. | +| nav_mc_vel_xy_i | 15 | 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 | +| nav_mc_vel_xy_p | 40 | 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 | +| nav_mc_vel_z_d | 10 | D gain of velocity PID controller | +| nav_mc_vel_z_i | 50 | I gain of velocity PID controller | +| nav_mc_vel_z_p | 100 | P gain of velocity PID controller | +| nav_min_rth_distance | 500 | 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. | +| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. | +| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | +| nav_rth_abort_threshold | 50000 | 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] | +| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. | +| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details | +| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) | +| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. | +| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. | +| nav_rth_home_altitude | 0 | 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] | +| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) | +| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) | +| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. | +| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats | +| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude | +| nav_user_control_mode | ATTI | 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. | +| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | +| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | +| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | +| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) | +| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon | +| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | +| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | +| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) | +| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation | +| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe | +| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) | +| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) | +| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) | +| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. | +| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | +| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | +| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) | +| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) | +| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink | +| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | +| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` | +| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) | +| osd_units | METRIC | IMPERIAL, METRIC, UK | +| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` | +| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` | +| pidsum_limit | 500 | 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 | +| pidsum_limit_yaw | 400 | 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 | +| pitch_rate | 20 | 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. | +| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented | +| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo | +| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts | +| rate_accel_limit_roll_pitch | 0 | 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. | +| rate_accel_limit_yaw | 10000 | 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. | +| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | +| rc_filter_frequency | 50 | 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 | +| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | +| reboot_character | 82 | Special character used to trigger reboot | +| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | +| roll_rate | 20 | 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. | +| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV | +| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | +| rpm_gyro_min_hz | 150 | 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` | +| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | +| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | +| rssi_channel | 0 | RX channel containing the RSSI signal | +| rssi_max | 100 | 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. | +| rssi_min | 0 | 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). | +| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` | +| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | +| rx_max_usec | 2115 | 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. | +| rx_min_usec | 885 | 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. | +| sdcard_detect_inverted | `TARGET dependent` | 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. | +| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire | +| serialrx_inverted | OFF | 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). | +| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | +| servo_center_pulse | 1500 | Servo midpoint | +| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] | +| servo_protocol | PWM | 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) | +| servo_pwm_rate | 50 | 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. | +| sim_ground_station_number | Empty string | 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. | +| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | +| sim_pin | Empty string | PIN code for the SIM module | +| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low | +| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | +| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. | +| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] | +| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX | +| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) | +| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | +| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | +| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] | +| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details | +| telemetry_inverted | OFF | 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. | +| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. | +| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) | +| thr_expo | 0 | Throttle exposition value | +| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | +| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | +| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | +| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | +| tpa_breakpoint | 1500 | See tpa_rate. | +| tpa_rate | 0 | 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. | +| tri_unarmed_servo | ON | 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. | +| tz_automatic_dst | OFF | 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`. | +| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs | +| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | +| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V | +| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V | +| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running | +| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | +| vbat_scale | 1100 | 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. | +| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | +| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. | +| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. | +| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. | +| vtx_low_power_disarm | OFF | 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. | +| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | +| yaw_deadband | 5 | 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. | +| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | +| yaw_rate | 20 | 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. | + +> Note: this table is autogenerated. Do not edit it manually. \ No newline at end of file diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index be3096bc72..e832b7a48d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -151,38 +151,38 @@ groups: headers: ["sensors/gyro.h"] members: - name: looptime - docs_description: "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." - docs_default_value: "1000" + description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible." + default_value: "1000" max: 9000 - name: gyro_sync - docs_description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" - docs_default_value: "OFF" + description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf" + default_value: "OFF" field: gyroSync type: bool - name: align_gyro - docs_description: "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." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: gyro_align type: uint8_t table: alignment - name: gyro_hardware_lpf - docs_description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." - docs_default_value: "42HZ" + description: "Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first." + default_value: "42HZ" field: gyro_lpf table: gyro_lpf - name: gyro_lpf_hz - docs_description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." - docs_default_value: "60" + description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + default_value: "60" field: gyro_soft_lpf_hz max: 200 - name: gyro_lpf_type - docs_description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." - docs_default_value: "BIQUAD" + description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + default_value: "BIQUAD" field: gyro_soft_lpf_type table: filter_type - name: moron_threshold - docs_description: "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." - docs_default_value: "32" + description: "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." + default_value: "32" field: gyroMovementCalibrationThreshold max: 128 - name: gyro_notch_hz @@ -193,38 +193,38 @@ groups: min: 1 max: 500 - name: gyro_stage2_lowpass_hz - docs_description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" - docs_default_value: "0" + description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)" + default_value: "0" field: gyro_stage2_lowpass_hz min: 0 max: 500 - name: gyro_stage2_lowpass_type - docs_description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: gyro_stage2_lowpass_type table: filter_type - name: dynamic_gyro_notch_enabled - docs_description: "Enable/disable dynamic gyro notch also known as Matrix Filter" - docs_default_value: "`OFF`" + description: "Enable/disable dynamic gyro notch also known as Matrix Filter" + default_value: "`OFF`" field: dynamicGyroNotchEnabled condition: USE_DYNAMIC_FILTERS type: bool - name: dynamic_gyro_notch_range - docs_description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" - docs_default_value: "`MEDIUM`" + description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers" + default_value: "`MEDIUM`" field: dynamicGyroNotchRange condition: USE_DYNAMIC_FILTERS table: dynamicFilterRangeTable - name: dynamic_gyro_notch_q - docs_description: "Q factor for dynamic notches" - docs_default_value: "120" + description: "Q factor for dynamic notches" + default_value: "120" field: dynamicGyroNotchQ condition: USE_DYNAMIC_FILTERS min: 1 max: 1000 - name: dynamic_gyro_notch_min_hz - docs_description: "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`" - docs_default_value: "150" + description: "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`" + default_value: "150" field: dynamicGyroNotchMinHz condition: USE_DYNAMIC_FILTERS min: 30 @@ -259,26 +259,26 @@ groups: condition: USE_ADC members: - name: vbat_adc_channel - docs_description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_BATTERY] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: rssi_adc_channel - docs_description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_RSSI] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: current_adc_channel - docs_description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" - docs_default_value: "-" + description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled" + default_value: "-" field: adcFunctionChannel[ADC_CURRENT] min: ADC_CHN_NONE max: ADC_CHN_MAX - name: airspeed_adc_channel - docs_description: "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" - docs_default_value: "0" + description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0" + default_value: "0" field: adcFunctionChannel[ADC_AIRSPEED] min: ADC_CHN_NONE max: ADC_CHN_MAX @@ -294,58 +294,58 @@ groups: min: 1 max: 255 - name: align_acc - docs_description: "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." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: acc_align type: uint8_t table: alignment - name: acc_hardware - docs_description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: acc_hardware - name: acc_lpf_hz - docs_description: "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." - docs_default_value: "15" + description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value." + default_value: "15" min: 0 max: 200 - name: acc_lpf_type - docs_description: "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." - docs_default_value: "BIQUAD" + description: "Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds." + default_value: "BIQUAD" field: acc_soft_lpf_type table: filter_type - name: acczero_x - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[X] min: INT16_MIN max: INT16_MAX - name: acczero_y - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: acczero_z - docs_description: "Calculated value after '6 position avanced calibration'. See Wiki page." - docs_default_value: "0" + description: "Calculated value after '6 position avanced calibration'. See Wiki page." + default_value: "0" field: accZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: accgain_x - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[X] min: 1 max: 8192 - name: accgain_y - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[Y] min: 1 max: 8192 - name: accgain_z - docs_description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." - docs_default_value: "4096" + description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page." + default_value: "4096" field: accGain.raw[Z] min: 1 max: 8192 @@ -358,8 +358,8 @@ groups: - name: rangefinder_hardware table: rangefinder_hardware - name: rangefinder_median_filter - docs_description: "3-point median filtering for rangefinder readouts" - docs_default_value: "OFF" + description: "3-point median filtering for rangefinder readouts" + default_value: "OFF" field: use_median_filtering type: bool @@ -374,8 +374,8 @@ groups: min: 0 max: 10000 - name: align_opflow - docs_description: "Optical flow module alignment (default CW0_DEG_FLIP)" - docs_default_value: "5" + description: "Optical flow module alignment (default CW0_DEG_FLIP)" + default_value: "5" field: opflow_align type: uint8_t table: alignment @@ -386,64 +386,64 @@ groups: condition: USE_MAG members: - name: align_mag - docs_description: "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." - docs_default_value: "DEFAULT" + description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP." + default_value: "DEFAULT" field: mag_align type: uint8_t table: alignment - name: mag_hardware - docs_description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: mag_hardware - name: mag_declination - docs_description: "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." - docs_default_value: "0" + description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix." + default_value: "0" min: -18000 max: 18000 - name: magzero_x - docs_description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[X] min: INT16_MIN max: INT16_MAX - name: magzero_y - docs_description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[Y] min: INT16_MIN max: INT16_MAX - name: magzero_z - docs_description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." - docs_default_value: "0" + description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed." + default_value: "0" field: magZero.raw[Z] min: INT16_MIN max: INT16_MAX - name: mag_calibration_time - docs_description: "Adjust how long time the Calibration of mag will last." - docs_default_value: "30" + description: "Adjust how long time the Calibration of mag will last." + default_value: "30" field: magCalibrationTimeLimit min: 30 max: 120 - name: mag_to_use - docs_description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" + description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target" condition: USE_DUAL_MAG min: 0 max: 1 - name: align_mag_roll - docs_description: "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." - docs_default_value: "0" + description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw." + default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_mag_pitch - docs_description: "Same as align_mag_roll, but for the pitch axis." - docs_default_value: "0" + description: "Same as align_mag_roll, but for the pitch axis." + default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_mag_yaw - docs_description: "Same as align_mag_roll, but for the yaw axis." - docs_default_value: "0" + description: "Same as align_mag_roll, but for the yaw axis." + default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -454,17 +454,17 @@ groups: condition: USE_BARO members: - name: baro_hardware - docs_description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" - docs_default_value: "AUTO" + description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info" + default_value: "AUTO" table: baro_hardware - name: baro_median_filter - docs_description: "3-point median filtering for barometer readouts. No reason to change this setting" - docs_default_value: "ON" + description: "3-point median filtering for barometer readouts. No reason to change this setting" + default_value: "ON" field: use_median_filtering type: bool - name: baro_cal_tolerance - docs_description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." - docs_default_value: "150" + description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]." + default_value: "150" field: baro_calibration_tolerance min: 0 max: 1000 @@ -491,36 +491,36 @@ groups: field: receiverType table: receiver_type - name: min_check - docs_description: "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." - docs_default_value: "1100" + description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + default_value: "1100" field: mincheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: max_check - docs_description: "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." - docs_default_value: "1900" + description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value." + default_value: "1900" field: maxcheck min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: rssi_source - docs_description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" - docs_default_value: "`AUTO`" + description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`" + default_value: "`AUTO`" field: rssi_source table: rssi_source - name: rssi_channel - docs_description: "RX channel containing the RSSI signal" - docs_default_value: "0" + description: "RX channel containing the RSSI signal" + default_value: "0" min: 0 max: MAX_SUPPORTED_RC_CHANNEL_COUNT - name: rssi_min - docs_description: "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)." - docs_default_value: "0" + description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)." + default_value: "0" field: rssiMin min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX - name: rssi_max - docs_description: "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." - docs_default_value: "100" + description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min." + default_value: "100" field: rssiMax min: RSSI_VISIBLE_VALUE_MIN max: RSSI_VISIBLE_VALUE_MAX @@ -529,19 +529,19 @@ groups: min: 500 max: 10000 - name: rc_filter_frequency - docs_description: "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" - docs_default_value: "50" + description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values" + default_value: "50" field: rcFilterFrequency min: 0 max: 100 - name: serialrx_provider - docs_description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." - docs_default_value: "SPEK1024" + description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section." + default_value: "SPEK1024" condition: USE_SERIAL_RX table: serial_rx - name: serialrx_inverted - docs_description: "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)." - docs_default_value: "OFF" + description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)." + default_value: "OFF" condition: USE_SERIAL_RX type: bool - name: rx_spi_protocol @@ -555,24 +555,24 @@ groups: min: 0 max: 8 - name: spektrum_sat_bind - docs_description: "0 = disabled. Used to bind the spektrum satellite to RX" - docs_default_value: "0" + description: "0 = disabled. Used to bind the spektrum satellite to RX" + default_value: "0" condition: USE_SPEKTRUM_BIND min: SPEKTRUM_SAT_BIND_DISABLED max: SPEKTRUM_SAT_BIND_MAX - name: rx_min_usec - docs_description: "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." - docs_default_value: "885" + description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc." + default_value: "885" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: rx_max_usec - docs_description: "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." - docs_default_value: "2115" + description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc." + default_value: "2115" min: PWM_PULSE_MIN max: PWM_PULSE_MAX - name: serialrx_halfduplex - docs_description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" - docs_default_value: "OFF" + description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire" + default_value: "OFF" field: halfDuplex type: bool - name: msp_override_channels @@ -587,25 +587,25 @@ groups: condition: USE_BLACKBOX members: - name: blackbox_rate_num - docs_description: "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" - docs_default_value: "1" + description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations" + default_value: "1" field: rate_num min: 1 max: 65535 - name: blackbox_rate_denom - docs_description: "Blackbox logging rate denominator. See blackbox_rate_num." - docs_default_value: "1" + description: "Blackbox logging rate denominator. See blackbox_rate_num." + default_value: "1" field: rate_denom min: 1 max: 65535 - name: blackbox_device - docs_description: "Selection of where to write blackbox data" - docs_default_value: "SPIFLASH" + description: "Selection of where to write blackbox data" + default_value: "SPIFLASH" field: device table: blackbox_device - name: sdcard_detect_inverted - docs_description: "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." - docs_default_value: "`TARGET dependent`" + description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value." + default_value: "`TARGET dependent`" field: invertedCardDetection condition: USE_SDCARD type: bool @@ -615,49 +615,49 @@ groups: headers: ["flight/mixer.h"] members: - name: max_throttle - docs_description: "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." - docs_default_value: "1850" + description: "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." + default_value: "1850" field: maxthrottle min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: min_command - docs_description: "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." - docs_default_value: "1000" + description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once." + default_value: "1000" field: mincommand min: 0 max: PWM_RANGE_MAX - name: motor_pwm_rate - docs_description: "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." - docs_default_value: "400" + description: "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." + default_value: "400" field: motorPwmRate min: 50 max: 32000 - name: motor_accel_time - docs_description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" - docs_default_value: "0" + description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]" + default_value: "0" field: motorAccelTimeMs min: 0 max: 1000 - name: motor_decel_time - docs_description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" - docs_default_value: "0" + description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]" + default_value: "0" field: motorDecelTimeMs min: 0 max: 1000 - name: motor_pwm_protocol - docs_description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" - docs_default_value: "STANDARD" + description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED" + default_value: "STANDARD" field: motorPwmProtocol table: motor_pwm_protocol - name: throttle_scale - docs_description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" - docs_default_value: "1.000" + description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%" + default_value: "1.000" field: throttleScale min: 0 max: 1 - name: throttle_idle - docs_description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." - docs_default_value: "15" + description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle." + default_value: "15" field: throttleIdle min: 4 max: 30 @@ -671,67 +671,67 @@ groups: headers: ["flight/failsafe.h"] members: - name: failsafe_delay - docs_description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." - docs_default_value: "5" + description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)." + default_value: "5" min: 0 max: 200 - name: failsafe_recovery_delay - docs_description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." - docs_default_value: "5" + description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)." + default_value: "5" min: 0 max: 200 - name: failsafe_off_delay - docs_description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." - docs_default_value: "200" + description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)." + default_value: "200" min: 0 max: 200 - name: failsafe_throttle - docs_description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - docs_default_value: "1000" + description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: "1000" min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: failsafe_throttle_low_delay - docs_description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" - docs_default_value: "100" + description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout" + default_value: "100" min: 0 max: 300 - name: failsafe_procedure - docs_description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." - docs_default_value: "SET-THR" + description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)." + default_value: "SET-THR" table: failsafe_procedure - name: failsafe_stick_threshold - docs_description: "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." - docs_default_value: "50" + description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe." + default_value: "50" field: failsafe_stick_motion_threshold min: 0 max: 500 - name: failsafe_fw_roll_angle - docs_description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" - docs_default_value: "-200" + description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll" + default_value: "-200" min: -800 max: 800 - name: failsafe_fw_pitch_angle - docs_description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" - docs_default_value: "100" + description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb" + default_value: "100" min: -800 max: 800 - name: failsafe_fw_yaw_rate - docs_description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" - docs_default_value: "-45" + description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn" + default_value: "-45" min: -1000 max: 1000 - name: failsafe_min_distance - docs_description: "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." - docs_default_value: "0" + description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken." + default_value: "0" min: 0 max: 65000 - name: failsafe_min_distance_procedure - docs_description: "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)." - docs_default_value: "DROP" + description: "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)." + default_value: "DROP" table: failsafe_procedure - name: failsafe_mission - docs_description: "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" - docs_default_value: "ON" + description: "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" + default_value: "ON" type: bool - name: PG_LIGHTS_CONFIG @@ -740,19 +740,19 @@ groups: condition: USE_LIGHTS members: - name: failsafe_lights - docs_description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." - docs_default_value: "ON" + description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]." + default_value: "ON" field: failsafe.enabled type: bool - name: failsafe_lights_flash_period - docs_description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." - docs_default_value: "1000" + description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]." + default_value: "1000" field: failsafe.flash_period min: 40 max: 65535 - name: failsafe_lights_flash_on_time - docs_description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." - docs_default_value: "100" + description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]." + default_value: "100" field: failsafe.flash_on_time min: 20 max: 65535 @@ -762,20 +762,20 @@ groups: headers: ["sensors/boardalignment.h"] members: - name: align_board_roll - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: rollDeciDegrees min: -1800 max: 3600 - name: align_board_pitch - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: pitchDeciDegrees min: -1800 max: 3600 - name: align_board_yaw - docs_description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" - docs_default_value: "0" + description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc" + default_value: "0" field: yawDeciDegrees min: -1800 max: 3600 @@ -785,62 +785,62 @@ groups: headers: ["sensors/battery.h"] members: - name: vbat_meter_type - docs_description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" - docs_default_value: "`ADC`" + description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running" + default_value: "`ADC`" field: voltage.type table: voltage_sensor type: uint8_t - name: vbat_scale - docs_description: "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." - docs_default_value: "1100" + description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli." + default_value: "1100" field: voltage.scale condition: USE_ADC min: VBAT_SCALE_MIN max: VBAT_SCALE_MAX - name: current_meter_scale - docs_description: "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." - docs_default_value: "400" + description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt." + default_value: "400" field: current.scale min: -10000 max: 10000 - name: current_meter_offset - docs_description: "This sets the output offset voltage of the current sensor in millivolts." - docs_default_value: "0" + description: "This sets the output offset voltage of the current sensor in millivolts." + default_value: "0" field: current.offset min: -32768 max: 32767 - name: current_meter_type - docs_description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." - docs_default_value: "ADC" + description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position." + default_value: "ADC" field: current.type table: current_sensor type: uint8_t - name: bat_voltage_src - docs_description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" - docs_default_value: "RAW" + description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`" + default_value: "RAW" field: voltageSource table: bat_voltage_source type: uint8_t - name: cruise_power - docs_description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" - docs_default_value: "0" + description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit" + default_value: "0" field: cruise_power min: 0 max: 4294967295 - name: idle_power - docs_description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" - docs_default_value: "0" + description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit" + default_value: "0" field: idle_power min: 0 max: 65535 - name: rth_energy_margin - docs_description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" - docs_default_value: "5" + description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation" + default_value: "5" min: 0 max: 100 - name: thr_comp_weight - docs_description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" - docs_default_value: "0.692" + description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)" + default_value: "0.692" field: throttle_compensation_weight min: 0 max: 2 @@ -851,61 +851,61 @@ groups: value_type: BATTERY_CONFIG_VALUE members: - name: bat_cells - docs_description: "Number of cells of the battery (0 = autodetect), see battery documentation" - docs_default_value: "0" + description: "Number of cells of the battery (0 = autodetect), see battery documentation" + default_value: "0" field: cells condition: USE_ADC min: 0 max: 8 - name: vbat_cell_detect_voltage - docs_description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" - docs_default_value: "430" + description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V" + default_value: "430" field: voltage.cellDetect condition: USE_ADC min: 100 max: 500 - name: vbat_max_cell_voltage - docs_description: "Maximum voltage per cell in 0.01V units, default is 4.20V" - docs_default_value: "420" + description: "Maximum voltage per cell in 0.01V units, default is 4.20V" + default_value: "420" field: voltage.cellMax condition: USE_ADC min: 100 max: 500 - name: vbat_min_cell_voltage - docs_description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" - docs_default_value: "330" + description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)" + default_value: "330" field: voltage.cellMin condition: USE_ADC min: 100 max: 500 - name: vbat_warning_cell_voltage - docs_description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" - docs_default_value: "350" + description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)" + default_value: "350" field: voltage.cellWarning condition: USE_ADC min: 100 max: 500 - name: battery_capacity - docs_description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." - docs_default_value: "0" + description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity." + default_value: "0" field: capacity.value min: 0 max: 4294967295 - name: battery_capacity_warning - docs_description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." - docs_default_value: "0" + description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink." + default_value: "0" field: capacity.warning min: 0 max: 4294967295 - name: battery_capacity_critical - docs_description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." - docs_default_value: "0" + description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps." + default_value: "0" field: capacity.critical min: 0 max: 4294967295 - name: battery_capacity_unit - docs_description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." - docs_default_value: "MAH" + description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)." + default_value: "MAH" field: capacity.unit table: bat_capacity_unit type: uint8_t @@ -914,30 +914,30 @@ groups: type: mixerConfig_t members: - name: motor_direction_inverted - docs_description: "Use if you need to inverse yaw motor direction." - docs_default_value: "OFF" + description: "Use if you need to inverse yaw motor direction." + default_value: "OFF" field: motorDirectionInverted type: bool - name: platform_type - docs_description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" - docs_default_value: "\"MULTIROTOR\"" + description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented" + default_value: "\"MULTIROTOR\"" field: platformType type: uint8_t table: platform_type - name: has_flaps - docs_description: "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" - docs_default_value: "OFF" + description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot" + default_value: "OFF" field: hasFlaps type: bool - name: model_preview_type - docs_description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." - docs_default_value: "-1" + description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons." + default_value: "-1" field: appliedMixerPreset min: -1 max: INT16_MAX - name: fw_min_throttle_down_pitch - docs_description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" - docs_default_value: "0" + description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)" + default_value: "0" field: fwMinThrottleDownPitchAngle min: 0 max: 450 @@ -946,20 +946,20 @@ groups: type: reversibleMotorsConfig_t members: - name: 3d_deadband_low - docs_description: "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)" - docs_default_value: "1406" + description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)" + default_value: "1406" field: deadband_low min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_deadband_high - docs_description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" - docs_default_value: "1514" + description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)" + default_value: "1514" field: deadband_high min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: 3d_neutral - docs_description: "Neutral (stop) throttle value for 3D mode" - docs_default_value: "1460" + description: "Neutral (stop) throttle value for 3D mode" + default_value: "1460" field: neutral min: PWM_RANGE_MIN max: PWM_RANGE_MAX @@ -969,36 +969,36 @@ groups: headers: ["flight/servos.h"] members: - name: servo_protocol - docs_description: "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)" - docs_default_value: "PWM" + description: "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)" + default_value: "PWM" field: servo_protocol table: servo_protocol - name: servo_center_pulse - docs_description: "Servo midpoint" - docs_default_value: "1500" + description: "Servo midpoint" + default_value: "1500" field: servoCenterPulse min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: servo_pwm_rate - docs_description: "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." - docs_default_value: "50" + description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz." + default_value: "50" field: servoPwmRate min: 50 max: 498 - name: servo_lpf_hz - docs_description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" - docs_default_value: "20" + description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]" + default_value: "20" field: servo_lowpass_freq min: 0 max: 400 - name: flaperon_throw_offset - docs_description: "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." - docs_default_value: "200" + description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated." + default_value: "200" min: FLAPERON_THROW_MIN max: FLAPERON_THROW_MAX - name: tri_unarmed_servo - docs_description: "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." - docs_default_value: "ON" + description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF." + default_value: "ON" type: bool - name: PG_CONTROL_RATE_PROFILES @@ -1007,94 +1007,94 @@ groups: value_type: CONTROL_RATE_VALUE members: - name: thr_mid - docs_description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." - docs_default_value: "50" + description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation." + default_value: "50" field: throttle.rcMid8 min: 0 max: 100 - name: thr_expo - docs_description: "Throttle exposition value" - docs_default_value: "0" + description: "Throttle exposition value" + default_value: "0" field: throttle.rcExpo8 min: 0 max: 100 - name: tpa_rate - docs_description: "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." - docs_default_value: "0" + description: "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." + default_value: "0" field: throttle.dynPID min: 0 max: CONTROL_RATE_CONFIG_TPA_MAX - name: tpa_breakpoint - docs_description: "See tpa_rate." - docs_default_value: "1500" + description: "See tpa_rate." + default_value: "1500" field: throttle.pa_breakpoint min: PWM_RANGE_MIN max: PWM_RANGE_MAX - name: fw_tpa_time_constant - docs_description: "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" - docs_default_value: "0" + description: "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" + default_value: "0" field: throttle.fixedWingTauMs min: 0 max: 5000 - name: rc_expo - docs_description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" - docs_default_value: "70" + description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)" + default_value: "70" field: stabilized.rcExpo8 min: 0 max: 100 - name: rc_yaw_expo - docs_description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" - docs_default_value: "20" + description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)" + default_value: "20" field: stabilized.rcYawExpo8 min: 0 max: 100 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis. # Rate 180 (1800dps) is max. value gyro can measure reliably - name: roll_rate - docs_description: "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." - docs_default_value: "20" + description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_ROLL] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: pitch_rate - docs_description: "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." - docs_default_value: "20" + description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_PITCH] min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX - name: yaw_rate - docs_description: "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." - docs_default_value: "20" + description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure." + default_value: "20" field: stabilized.rates[FD_YAW] min: CONTROL_RATE_CONFIG_YAW_RATE_MIN max: CONTROL_RATE_CONFIG_YAW_RATE_MAX - name: manual_rc_expo - docs_description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" - docs_default_value: "70" + description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" + default_value: "70" field: manual.rcExpo8 min: 0 max: 100 - name: manual_rc_yaw_expo - docs_description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" - docs_default_value: "20" + description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]" + default_value: "20" field: manual.rcYawExpo8 min: 0 max: 100 - name: manual_roll_rate - docs_description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_ROLL] min: 0 max: 100 - name: manual_pitch_rate - docs_description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_PITCH] min: 0 max: 100 - name: manual_yaw_rate - docs_description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" - docs_default_value: "100" + description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%" + default_value: "100" field: manual.rates[FD_YAW] min: 0 max: 100 @@ -1108,8 +1108,8 @@ groups: headers: ["io/serial.h"] members: - name: reboot_character - docs_description: "Special character used to trigger reboot" - docs_default_value: "82" + description: "Special character used to trigger reboot" + default_value: "82" min: 48 max: 126 @@ -1118,39 +1118,39 @@ groups: headers: ["flight/imu.h"] members: - name: imu_dcm_kp - docs_description: "Inertial Measurement Unit KP Gain for accelerometer measurements" - docs_default_value: "2500" + description: "Inertial Measurement Unit KP Gain for accelerometer measurements" + default_value: "2500" field: dcm_kp_acc max: UINT16_MAX - name: imu_dcm_ki - docs_description: "Inertial Measurement Unit KI Gain for accelerometer measurements" - docs_default_value: "50" + description: "Inertial Measurement Unit KI Gain for accelerometer measurements" + default_value: "50" field: dcm_ki_acc max: UINT16_MAX - name: imu_dcm_kp_mag - docs_description: "Inertial Measurement Unit KP Gain for compass measurements" - docs_default_value: "10000" + description: "Inertial Measurement Unit KP Gain for compass measurements" + default_value: "10000" field: dcm_kp_mag max: UINT16_MAX - name: imu_dcm_ki_mag - docs_description: "Inertial Measurement Unit KI Gain for compass measurements" - docs_default_value: "0" + description: "Inertial Measurement Unit KI Gain for compass measurements" + default_value: "0" field: dcm_ki_mag max: UINT16_MAX - name: small_angle - docs_description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." - docs_default_value: "25" + description: "If the aircraft tilt angle exceed this value the copter will refuse to arm." + default_value: "25" min: 0 max: 180 - name: imu_acc_ignore_rate - docs_description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" - docs_default_value: "0" + description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes" + default_value: "0" field: acc_ignore_rate min: 0 max: 20 - name: imu_acc_ignore_slope - docs_description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" - docs_default_value: "0" + description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)" + default_value: "0" field: acc_ignore_slope min: 0 max: 5 @@ -1159,16 +1159,16 @@ groups: type: armingConfig_t members: - name: fixed_wing_auto_arm - docs_description: "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." - docs_default_value: "OFF" + description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured." + default_value: "OFF" type: bool - name: disarm_kill_switch - docs_description: "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." - docs_default_value: "ON" + description: "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." + default_value: "ON" type: bool - name: switch_disarm_delay - docs_description: "Delay before disarming when requested by switch (ms) [0-1000]" - docs_default_value: "250" + description: "Delay before disarming when requested by switch (ms) [0-1000]" + default_value: "250" field: switchDisarmDelayMs min: 0 max: 1000 @@ -1187,27 +1187,27 @@ groups: type: rpmFilterConfig_t members: - name: rpm_gyro_filter_enabled - docs_description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" - docs_default_value: "`OFF`" + description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV" + default_value: "`OFF`" field: gyro_filter_enabled type: bool - name: rpm_gyro_harmonics - docs_description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" - docs_default_value: "1" + description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine" + default_value: "1" field: gyro_harmonics type: uint8_t min: 1 max: 3 - name: rpm_gyro_min_hz - docs_description: "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`" - docs_default_value: "150" + description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`" + default_value: "150" field: gyro_min_hz type: uint8_t min: 30 max: 200 - name: rpm_gyro_q - docs_description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" - docs_default_value: "500" + description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting" + default_value: "500" field: gyro_q type: uint16_t min: 1 @@ -1217,41 +1217,41 @@ groups: condition: USE_GPS members: - name: gps_provider - docs_description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." - docs_default_value: "UBLOX" + description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)." + default_value: "UBLOX" field: provider table: gps_provider type: uint8_t - name: gps_sbas_mode - docs_description: "Which SBAS mode to be used" - docs_default_value: "NONE" + description: "Which SBAS mode to be used" + default_value: "NONE" field: sbasMode table: gps_sbas_mode type: uint8_t - name: gps_dyn_model - docs_description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." - docs_default_value: "AIR_1G" + description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying." + default_value: "AIR_1G" field: dynModel table: gps_dyn_model type: uint8_t - name: gps_auto_config - docs_description: "Enable automatic configuration of UBlox GPS receivers." - docs_default_value: "ON" + description: "Enable automatic configuration of UBlox GPS receivers." + default_value: "ON" field: autoConfig type: bool - name: gps_auto_baud - docs_description: "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" - docs_default_value: "ON" + description: "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" + default_value: "ON" field: autoBaud type: bool - name: gps_ublox_use_galileo - docs_description: "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]." - docs_default_value: "OFF" + description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]." + default_value: "OFF" field: ubloxUseGalileo type: bool - name: gps_min_sats - docs_description: "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." - docs_default_value: "6" + description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count." + default_value: "6" field: gpsMinSats min: 5 max: 10 @@ -1261,39 +1261,39 @@ groups: headers: ["fc/rc_controls.h"] members: - name: deadband - docs_description: "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." - docs_default_value: "5" + description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + default_value: "5" min: 0 max: 32 - name: yaw_deadband - docs_description: "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." - docs_default_value: "5" + description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle." + default_value: "5" min: 0 max: 100 - name: pos_hold_deadband - docs_description: "Stick deadband in [r/c points], applied after r/c deadband and expo" - docs_default_value: "20" + description: "Stick deadband in [r/c points], applied after r/c deadband and expo" + default_value: "20" min: 2 max: 250 - name: alt_hold_deadband - docs_description: "Defines the deadband of throttle during alt_hold [r/c points]" - docs_default_value: "50" + description: "Defines the deadband of throttle during alt_hold [r/c points]" + default_value: "50" min: 10 max: 250 - name: 3d_deadband_throttle - docs_description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." - docs_default_value: "50" + description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter." + default_value: "50" field: mid_throttle_deadband min: 0 max: 200 - name: mc_airmode_type - docs_description: "Defines the Airmode state handling type for Multirotors. 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 `mc_airmode_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** mode." - docs_default_value: "STICK_CENTER" + description: "Defines the Airmode state handling type for Multirotors. 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 `mc_airmode_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** mode." + default_value: "STICK_CENTER" field: airmodeHandlingType table: airmodeHandlingType - name: mc_airmode_threshold - docs_description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" - docs_default_value: "1300" + description: "Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used" + default_value: "1300" field: airmodeThrottleThreshold min: 1000 max: 2000 @@ -1304,320 +1304,320 @@ groups: value_type: PROFILE_VALUE members: - name: mc_p_pitch - docs_description: "Multicopter rate stabilisation P-gain for PITCH" - docs_default_value: "40" + description: "Multicopter rate stabilisation P-gain for PITCH" + default_value: "40" field: bank_mc.pid[PID_PITCH].P min: 0 max: 200 - name: mc_i_pitch - docs_description: "Multicopter rate stabilisation I-gain for PITCH" - docs_default_value: "30" + description: "Multicopter rate stabilisation I-gain for PITCH" + default_value: "30" field: bank_mc.pid[PID_PITCH].I min: 0 max: 200 - name: mc_d_pitch - docs_description: "Multicopter rate stabilisation D-gain for PITCH" - docs_default_value: "23" + description: "Multicopter rate stabilisation D-gain for PITCH" + default_value: "23" field: bank_mc.pid[PID_PITCH].D min: 0 max: 200 - name: mc_cd_pitch - docs_description: "Multicopter Control Derivative gain for PITCH" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for PITCH" + default_value: "60" field: bank_mc.pid[PID_PITCH].FF min: 0 max: 200 - name: mc_p_roll - docs_description: "Multicopter rate stabilisation P-gain for ROLL" - docs_default_value: "40" + description: "Multicopter rate stabilisation P-gain for ROLL" + default_value: "40" field: bank_mc.pid[PID_ROLL].P min: 0 max: 200 - name: mc_i_roll - docs_description: "Multicopter rate stabilisation I-gain for ROLL" - docs_default_value: "30" + description: "Multicopter rate stabilisation I-gain for ROLL" + default_value: "30" field: bank_mc.pid[PID_ROLL].I min: 0 max: 200 - name: mc_d_roll - docs_description: "Multicopter rate stabilisation D-gain for ROLL" - docs_default_value: "23" + description: "Multicopter rate stabilisation D-gain for ROLL" + default_value: "23" field: bank_mc.pid[PID_ROLL].D min: 0 max: 200 - name: mc_cd_roll - docs_description: "Multicopter Control Derivative gain for ROLL" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for ROLL" + default_value: "60" field: bank_mc.pid[PID_ROLL].FF min: 0 max: 200 - name: mc_p_yaw - docs_description: "Multicopter rate stabilisation P-gain for YAW" - docs_default_value: "85" + description: "Multicopter rate stabilisation P-gain for YAW" + default_value: "85" field: bank_mc.pid[PID_YAW].P min: 0 max: 200 - name: mc_i_yaw - docs_description: "Multicopter rate stabilisation I-gain for YAW" - docs_default_value: "45" + description: "Multicopter rate stabilisation I-gain for YAW" + default_value: "45" field: bank_mc.pid[PID_YAW].I min: 0 max: 200 - name: mc_d_yaw - docs_description: "Multicopter rate stabilisation D-gain for YAW" - docs_default_value: "0" + description: "Multicopter rate stabilisation D-gain for YAW" + default_value: "0" field: bank_mc.pid[PID_YAW].D min: 0 max: 200 - name: mc_cd_yaw - docs_description: "Multicopter Control Derivative gain for YAW" - docs_default_value: "60" + description: "Multicopter Control Derivative gain for YAW" + default_value: "60" field: bank_mc.pid[PID_YAW].FF min: 0 max: 200 - name: mc_p_level - docs_description: "Multicopter attitude stabilisation P-gain" - docs_default_value: "20" + description: "Multicopter attitude stabilisation P-gain" + default_value: "20" field: bank_mc.pid[PID_LEVEL].P min: 0 max: 200 - name: mc_i_level - docs_description: "Multicopter attitude stabilisation low-pass filter cutoff" - docs_default_value: "15" + description: "Multicopter attitude stabilisation low-pass filter cutoff" + default_value: "15" field: bank_mc.pid[PID_LEVEL].I min: 0 max: 200 - name: mc_d_level - docs_description: "Multicopter attitude stabilisation HORIZON transition point" - docs_default_value: "75" + description: "Multicopter attitude stabilisation HORIZON transition point" + default_value: "75" field: bank_mc.pid[PID_LEVEL].D min: 0 max: 200 - name: fw_p_pitch - docs_description: "Fixed-wing rate stabilisation P-gain for PITCH" - docs_default_value: "5" + description: "Fixed-wing rate stabilisation P-gain for PITCH" + default_value: "5" field: bank_fw.pid[PID_PITCH].P min: 0 max: 200 - name: fw_i_pitch - docs_description: "Fixed-wing rate stabilisation I-gain for PITCH" - docs_default_value: "7" + description: "Fixed-wing rate stabilisation I-gain for PITCH" + default_value: "7" field: bank_fw.pid[PID_PITCH].I min: 0 max: 200 - name: fw_ff_pitch - docs_description: "Fixed-wing rate stabilisation FF-gain for PITCH" - docs_default_value: "50" + description: "Fixed-wing rate stabilisation FF-gain for PITCH" + default_value: "50" field: bank_fw.pid[PID_PITCH].FF min: 0 max: 200 - name: fw_p_roll - docs_description: "Fixed-wing rate stabilisation P-gain for ROLL" - docs_default_value: "5" + description: "Fixed-wing rate stabilisation P-gain for ROLL" + default_value: "5" field: bank_fw.pid[PID_ROLL].P min: 0 max: 200 - name: fw_i_roll - docs_description: "Fixed-wing rate stabilisation I-gain for ROLL" - docs_default_value: "7" + description: "Fixed-wing rate stabilisation I-gain for ROLL" + default_value: "7" field: bank_fw.pid[PID_ROLL].I min: 0 max: 200 - name: fw_ff_roll - docs_description: "Fixed-wing rate stabilisation FF-gain for ROLL" - docs_default_value: "50" + description: "Fixed-wing rate stabilisation FF-gain for ROLL" + default_value: "50" field: bank_fw.pid[PID_ROLL].FF min: 0 max: 200 - name: fw_p_yaw - docs_description: "Fixed-wing rate stabilisation P-gain for YAW" - docs_default_value: "6" + description: "Fixed-wing rate stabilisation P-gain for YAW" + default_value: "6" field: bank_fw.pid[PID_YAW].P min: 0 max: 200 - name: fw_i_yaw - docs_description: "Fixed-wing rate stabilisation I-gain for YAW" - docs_default_value: "10" + description: "Fixed-wing rate stabilisation I-gain for YAW" + default_value: "10" field: bank_fw.pid[PID_YAW].I min: 0 max: 200 - name: fw_ff_yaw - docs_description: "Fixed-wing rate stabilisation FF-gain for YAW" - docs_default_value: "60" + description: "Fixed-wing rate stabilisation FF-gain for YAW" + default_value: "60" field: bank_fw.pid[PID_YAW].FF min: 0 max: 200 - name: fw_p_level - docs_description: "Fixed-wing attitude stabilisation P-gain" - docs_default_value: "20" + description: "Fixed-wing attitude stabilisation P-gain" + default_value: "20" field: bank_fw.pid[PID_LEVEL].P min: 0 max: 200 - name: fw_i_level - docs_description: "Fixed-wing attitude stabilisation low-pass filter cutoff" - docs_default_value: "5" + description: "Fixed-wing attitude stabilisation low-pass filter cutoff" + default_value: "5" field: bank_fw.pid[PID_LEVEL].I min: 0 max: 200 - name: fw_d_level - docs_description: "Fixed-wing attitude stabilisation HORIZON transition point" - docs_default_value: "75" + description: "Fixed-wing attitude stabilisation HORIZON transition point" + default_value: "75" field: bank_fw.pid[PID_LEVEL].D min: 0 max: 200 - name: max_angle_inclination_rll - docs_description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" - docs_default_value: "300" + description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°" + default_value: "300" field: max_angle_inclination[FD_ROLL] min: 100 max: 900 - name: max_angle_inclination_pit - docs_description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" - docs_default_value: "300" + description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°" + default_value: "300" field: max_angle_inclination[FD_PITCH] min: 100 max: 900 - name: dterm_lpf_hz - docs_description: "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" - docs_default_value: "40" + description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value" + default_value: "40" min: 0 max: 500 - name: dterm_lpf_type - docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: dterm_lpf_type table: filter_type - name: dterm_lpf2_hz - docs_description: "Cutoff frequency for stage 2 D-term low pass filter" - docs_default_value: "0" + description: "Cutoff frequency for stage 2 D-term low pass filter" + default_value: "0" min: 0 max: 500 - name: dterm_lpf2_type - docs_description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." - docs_default_value: "`BIQUAD`" + description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation." + default_value: "`BIQUAD`" field: dterm_lpf2_type table: filter_type - name: yaw_lpf_hz - docs_description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" - docs_default_value: "30" + description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)" + default_value: "30" min: 0 max: 200 - name: fw_iterm_throw_limit - docs_description: "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." - docs_default_value: "165" + description: "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." + default_value: "165" field: fixedWingItermThrowLimit min: FW_ITERM_THROW_LIMIT_MIN max: FW_ITERM_THROW_LIMIT_MAX - name: fw_loiter_direction - docs_description: "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." - docs_default_value: "RIGHT" + description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick." + default_value: "RIGHT" field: loiter_direction condition: USE_NAV table: direction - name: fw_reference_airspeed - docs_description: "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." - docs_default_value: "1000" + description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present." + default_value: "1000" field: fixedWingReferenceAirspeed min: 1 max: 5000 - name: fw_turn_assist_yaw_gain - docs_description: "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" - docs_default_value: "1" + description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter" + default_value: "1" field: fixedWingCoordinatedYawGain min: 0 max: 2 - name: fw_iterm_limit_stick_position - docs_description: "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" - docs_default_value: "0.5" + description: "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" + default_value: "0.5" field: fixedWingItermLimitOnStickPosition min: 0 max: 1 - name: pidsum_limit - docs_description: "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" - docs_default_value: "500" + description: "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" + default_value: "500" field: pidSumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: pidsum_limit_yaw - docs_description: "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" - docs_default_value: "400" + description: "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" + default_value: "400" field: pidSumLimitYaw min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX - name: iterm_windup - docs_description: "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)" - docs_default_value: "50" + description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)" + default_value: "50" field: itermWindupPointPercent min: 0 max: 90 - name: rate_accel_limit_roll_pitch - docs_description: "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." - docs_default_value: "0" + description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting." + default_value: "0" field: axisAccelerationLimitRollPitch max: 500000 - name: rate_accel_limit_yaw - docs_description: "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." - docs_default_value: "10000" + description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting." + default_value: "10000" field: axisAccelerationLimitYaw max: 500000 - name: heading_hold_rate_limit - docs_description: "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." - docs_default_value: "90" + description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes." + default_value: "90" min: HEADING_HOLD_RATE_LIMIT_MIN max: HEADING_HOLD_RATE_LIMIT_MAX - name: nav_mc_pos_z_p - docs_description: "P gain of altitude PID controller (Multirotor)" - docs_default_value: "50" + description: "P gain of altitude PID controller (Multirotor)" + default_value: "50" field: bank_mc.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_p - docs_description: "P gain of velocity PID controller" - docs_default_value: "100" + description: "P gain of velocity PID controller" + default_value: "100" field: bank_mc.pid[PID_VEL_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_i - docs_description: "I gain of velocity PID controller" - docs_default_value: "50" + description: "I gain of velocity PID controller" + default_value: "50" field: bank_mc.pid[PID_VEL_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_z_d - docs_description: "D gain of velocity PID controller" - docs_default_value: "10" + description: "D gain of velocity PID controller" + default_value: "10" field: bank_mc.pid[PID_VEL_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_xy_p - docs_description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" - docs_default_value: "65" + description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity" + default_value: "65" field: bank_mc.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_p - docs_description: "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" - docs_default_value: "40" + description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations" + default_value: "40" field: bank_mc.pid[PID_VEL_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_i - docs_description: "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" - docs_default_value: "15" + description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot" + default_value: "15" field: bank_mc.pid[PID_VEL_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_mc_vel_xy_d - docs_description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." - docs_default_value: "100" + description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target." + default_value: "100" field: bank_mc.pid[PID_VEL_XY].D condition: USE_NAV min: 0 @@ -1628,8 +1628,8 @@ groups: min: 0 max: 255 - name: nav_mc_heading_p - docs_description: "P gain of Heading Hold controller (Multirotor)" - docs_default_value: "60" + description: "P gain of Heading Hold controller (Multirotor)" + default_value: "60" field: bank_mc.pid[PID_HEADING].P condition: USE_NAV min: 0 @@ -1639,78 +1639,78 @@ groups: min: 0 max: 100 - name: nav_fw_pos_z_p - docs_description: "P gain of altitude PID controller (Fixedwing)" - docs_default_value: "50" + description: "P gain of altitude PID controller (Fixedwing)" + default_value: "50" field: bank_fw.pid[PID_POS_Z].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_i - docs_description: "I gain of altitude PID controller (Fixedwing)" - docs_default_value: "0" + description: "I gain of altitude PID controller (Fixedwing)" + default_value: "0" field: bank_fw.pid[PID_POS_Z].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_z_d - docs_description: "D gain of altitude PID controller (Fixedwing)" - docs_default_value: "0" + description: "D gain of altitude PID controller (Fixedwing)" + default_value: "0" field: bank_fw.pid[PID_POS_Z].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_p - docs_description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" - docs_default_value: "75" + description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH" + default_value: "75" field: bank_fw.pid[PID_POS_XY].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_i - docs_description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" - docs_default_value: "5" + description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + default_value: "5" field: bank_fw.pid[PID_POS_XY].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_xy_d - docs_description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" - docs_default_value: "8" + description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero" + default_value: "8" field: bank_fw.pid[PID_POS_XY].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_heading_p - docs_description: "P gain of Heading Hold controller (Fixedwing)" - docs_default_value: "60" + description: "P gain of Heading Hold controller (Fixedwing)" + default_value: "60" field: bank_fw.pid[PID_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_p - docs_description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "60" + description: "P gain of heading PID controller. (Fixedwing, rovers, boats)" + default_value: "60" field: bank_fw.pid[PID_POS_HEADING].P condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_i - docs_description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "0" + description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "0" field: bank_fw.pid[PID_POS_HEADING].I condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_d - docs_description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "0" + description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "0" field: bank_fw.pid[PID_POS_HEADING].D condition: USE_NAV min: 0 max: 255 - name: nav_fw_pos_hdg_pidsum_limit - docs_description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" - docs_default_value: "350" + description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)" + default_value: "350" field: navFwPosHdgPidsumLimit min: PID_SUM_LIMIT_MIN max: PID_SUM_LIMIT_MAX @@ -1740,33 +1740,33 @@ groups: min: 10 max: 250 - name: antigravity_gain - docs_description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" - docs_default_value: "1" + description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements" + default_value: "1" field: antigravityGain condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_accelerator - docs_description: "" - docs_default_value: "1" + description: "" + default_value: "1" field: antigravityAccelerator condition: USE_ANTIGRAVITY min: 1 max: 20 - name: antigravity_cutoff_lpf_hz - docs_description: "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" - docs_default_value: "15" + description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain" + default_value: "15" field: antigravityCutoff condition: USE_ANTIGRAVITY min: 1 max: 30 - name: pid_type - docs_description: "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`" + description: "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`" field: pidControllerType table: pidTypeTable - name: mc_cd_lpf_hz - docs_description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" - docs_default_value: "30" + description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky" + default_value: "30" field: controlDerivativeLpfHz min: 0 max: 200 @@ -1776,32 +1776,32 @@ groups: condition: USE_NAV && USE_AUTOTUNE_FIXED_WING members: - name: fw_autotune_overshoot_time - docs_description: "Time [ms] to detect sustained overshoot" - docs_default_value: "100" + description: "Time [ms] to detect sustained overshoot" + default_value: "100" field: fw_overshoot_time min: 50 max: 500 - name: fw_autotune_undershoot_time - docs_description: "Time [ms] to detect sustained undershoot" - docs_default_value: "200" + description: "Time [ms] to detect sustained undershoot" + default_value: "200" field: fw_undershoot_time min: 50 max: 500 - name: fw_autotune_threshold - docs_description: "Threshold [%] of max rate to consider overshoot/undershoot detection" - docs_default_value: "50" + description: "Threshold [%] of max rate to consider overshoot/undershoot detection" + default_value: "50" field: fw_max_rate_threshold min: 0 max: 100 - name: fw_autotune_ff_to_p_gain - docs_description: "FF to P gain (strength relationship) [%]" - docs_default_value: "10" + description: "FF to P gain (strength relationship) [%]" + default_value: "10" field: fw_ff_to_p_gain min: 0 max: 100 - name: fw_autotune_ff_to_i_tc - docs_description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" - docs_default_value: "600" + description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]" + default_value: "600" field: fw_ff_to_i_time_constant min: 100 max: 5000 @@ -1811,37 +1811,37 @@ groups: condition: USE_NAV members: - name: inav_auto_mag_decl - docs_description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." - docs_default_value: "ON" + description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored." + default_value: "ON" field: automatic_mag_declination type: bool - name: inav_gravity_cal_tolerance - docs_description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." - docs_default_value: "5" + description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value." + default_value: "5" field: gravity_calibration_tolerance min: 0 max: 255 - name: inav_use_gps_velned - docs_description: "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." - docs_default_value: "ON" + description: "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." + default_value: "ON" field: use_gps_velned type: bool - name: inav_allow_dead_reckoning field: allow_dead_reckoning type: bool - name: inav_reset_altitude - docs_description: "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)" - docs_default_value: "FIRST_ARM" + description: "Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming)" + default_value: "FIRST_ARM" field: reset_altitude_type table: reset_type - name: inav_reset_home - docs_description: "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" - docs_default_value: "FIRST_ARM" + description: "Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM" + default_value: "FIRST_ARM" field: reset_home_type table: reset_type - name: inav_max_surface_altitude - docs_description: "Max allowed altitude for surface following mode. [cm]" - docs_default_value: "200" + description: "Max allowed altitude for surface following mode. [cm]" + default_value: "200" field: max_surface_altitude min: 0 max: 1000 @@ -1862,44 +1862,44 @@ groups: min: 0 max: 100 - name: inav_w_z_baro_p - docs_description: "Weight of barometer measurements in estimated altitude and climb rate" - docs_default_value: "0.350" + description: "Weight of barometer measurements in estimated altitude and climb rate" + default_value: "0.350" field: w_z_baro_p min: 0 max: 10 - name: inav_w_z_gps_p - docs_description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" - docs_default_value: "0.200" + description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes" + default_value: "0.200" field: w_z_gps_p min: 0 max: 10 - name: inav_w_z_gps_v - docs_description: "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" - docs_default_value: "0.500" + description: "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" + default_value: "0.500" field: w_z_gps_v min: 0 max: 10 - name: inav_w_xy_gps_p - docs_description: "Weight of GPS coordinates in estimated UAV position and speed." - docs_default_value: "1.000" + description: "Weight of GPS coordinates in estimated UAV position and speed." + default_value: "1.000" field: w_xy_gps_p min: 0 max: 10 - name: inav_w_xy_gps_v - docs_description: "Weight of GPS velocity data in estimated UAV speed" - docs_default_value: "2.000" + description: "Weight of GPS velocity data in estimated UAV speed" + default_value: "2.000" field: w_xy_gps_v min: 0 max: 10 - name: inav_w_z_res_v - docs_description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" - docs_default_value: "0.500" + description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost" + default_value: "0.500" field: w_z_res_v min: 0 max: 10 - name: inav_w_xy_res_v - docs_description: "Decay coefficient for estimated velocity when GPS reference for position is lost" - docs_default_value: "0.500" + description: "Decay coefficient for estimated velocity when GPS reference for position is lost" + default_value: "0.500" field: w_xy_res_v min: 0 max: 10 @@ -1908,20 +1908,20 @@ groups: min: 0 max: 1 - name: inav_w_acc_bias - docs_description: "Weight for accelerometer drift estimation" - docs_default_value: "0.010" + description: "Weight for accelerometer drift estimation" + default_value: "0.010" field: w_acc_bias min: 0 max: 1 - name: inav_max_eph_epv - docs_description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" - docs_default_value: "1000.000" + description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]" + default_value: "1000.000" field: max_eph_epv min: 0 max: 9999 - name: inav_baro_epv - docs_description: "Uncertainty value for barometric sensor [cm]" - docs_default_value: "100.000" + description: "Uncertainty value for barometric sensor [cm]" + default_value: "100.000" field: baro_epv min: 0 max: 9999 @@ -1932,401 +1932,401 @@ groups: condition: USE_NAV members: - name: nav_disarm_on_landing - docs_description: "If set to ON, iNav disarms the FC after landing" - docs_default_value: "OFF" + description: "If set to ON, iNav disarms the FC after landing" + default_value: "OFF" field: general.flags.disarm_on_landing type: bool - name: nav_use_midthr_for_althold - docs_description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" - docs_default_value: "OFF" + description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude" + default_value: "OFF" field: general.flags.use_thr_mid_for_althold type: bool - name: nav_extra_arming_safety - docs_description: "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" - docs_default_value: "ON" + description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used" + default_value: "ON" field: general.flags.extra_arming_safety table: nav_extra_arming_safety - name: nav_user_control_mode - docs_description: "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." - docs_default_value: "ATTI" + description: "Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction." + default_value: "ATTI" field: general.flags.user_control_mode table: nav_user_control_mode - name: nav_position_timeout - docs_description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" - docs_default_value: "5" + description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)" + default_value: "5" field: general.pos_failure_timeout min: 0 max: 10 - name: nav_wp_radius - docs_description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" - docs_default_value: "100" + description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius" + default_value: "100" field: general.waypoint_radius min: 10 max: 10000 - name: nav_wp_safe_distance - docs_description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." - docs_default_value: "10000" + description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check." + default_value: "10000" field: general.waypoint_safe_distance max: 65000 - name: nav_auto_speed - docs_description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" - docs_default_value: "300" + description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]" + default_value: "300" field: general.max_auto_speed min: 10 max: 2000 - name: nav_auto_climb_rate - docs_description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" - docs_default_value: "500" + description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]" + default_value: "500" field: general.max_auto_climb_rate min: 10 max: 2000 - name: nav_manual_speed - docs_description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" - docs_default_value: "500" + description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]" + default_value: "500" field: general.max_manual_speed min: 10 max: 2000 - name: nav_manual_climb_rate - docs_description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" - docs_default_value: "200" + description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]" + default_value: "200" field: general.max_manual_climb_rate min: 10 max: 2000 - name: nav_landing_speed - docs_description: "Vertical descent velocity during the RTH landing phase. [cm/s]" - docs_default_value: "200" + description: "Vertical descent velocity during the RTH landing phase. [cm/s]" + default_value: "200" field: general.land_descent_rate min: 100 max: 2000 - name: nav_land_slowdown_minalt - docs_description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" - docs_default_value: "500" + description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]" + default_value: "500" field: general.land_slowdown_minalt min: 50 max: 1000 - name: nav_land_slowdown_maxalt - docs_description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" - docs_default_value: "2000" + description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]" + default_value: "2000" field: general.land_slowdown_maxalt min: 500 max: 4000 - name: nav_emerg_landing_speed - docs_description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" - docs_default_value: "500" + description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]" + default_value: "500" field: general.emerg_descent_rate min: 100 max: 2000 - name: nav_min_rth_distance - docs_description: "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." - docs_default_value: "500" + description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase." + default_value: "500" field: general.min_rth_distance min: 0 max: 5000 - name: nav_overrides_motor_stop - docs_description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." - docs_default_value: "ON" + description: "Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall." + default_value: "ON" field: general.flags.auto_overrides_motor_stop type: bool - name: nav_rth_climb_first - docs_description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." - docs_default_value: "ON" + description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way." + default_value: "ON" field: general.flags.rth_climb_first type: bool - name: nav_rth_climb_ignore_emerg - docs_description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." - docs_default_value: "OFF" + description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status." + default_value: "OFF" field: general.flags.rth_climb_ignore_emerg type: bool - name: nav_rth_tail_first - docs_description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." - docs_default_value: "OFF" + description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes." + default_value: "OFF" field: general.flags.rth_tail_first type: bool - name: nav_rth_allow_landing - docs_description: "If set to ON drone will land as a last phase of RTH." - docs_default_value: "ALWAYS" + description: "If set to ON drone will land as a last phase of RTH." + default_value: "ALWAYS" field: general.flags.rth_allow_landing table: nav_rth_allow_landing - name: nav_rth_alt_mode - docs_description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" - docs_default_value: "AT_LEAST" + description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details" + default_value: "AT_LEAST" field: general.flags.rth_alt_control_mode table: nav_rth_alt_mode - name: nav_rth_abort_threshold - docs_description: "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]" - docs_default_value: "50000" + description: "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]" + default_value: "50000" field: general.rth_abort_threshold max: 65000 - name: nav_max_terrain_follow_alt field: general.max_terrain_follow_altitude max: 1000 - name: nav_rth_altitude - docs_description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" - docs_default_value: "1000" + description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)" + default_value: "1000" field: general.rth_altitude max: 65000 - name: nav_rth_home_altitude - docs_description: "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]" - docs_default_value: "0" + description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]" + default_value: "0" field: general.rth_home_altitude max: 65000 - name: nav_rth_home_offset_distance - docs_description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" - docs_default_value: "0" + description: "Distance offset from GPS established home to \"safe\" position used for RTH (cm, 0 disables)" + default_value: "0" field: general.rth_home_offset_distance max: 65000 - name: nav_rth_home_offset_direction - docs_description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" - docs_default_value: "0" + description: "Direction offset from GPS established home to \"safe\" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance)" + default_value: "0" field: general.rth_home_offset_direction max: 359 - name: nav_mc_bank_angle - docs_description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" - docs_default_value: "30" + description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude" + default_value: "30" field: mc.max_bank_angle min: 15 max: 45 - name: nav_mc_hover_thr - docs_description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." - docs_default_value: "1500" + description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering." + default_value: "1500" field: mc.hover_throttle min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay - docs_description: "" - docs_default_value: "2000" + description: "" + default_value: "2000" field: mc.auto_disarm_delay min: 100 max: 10000 - name: nav_mc_braking_speed_threshold - docs_description: "min speed in cm/s above which braking can happen" - docs_default_value: "100" + description: "min speed in cm/s above which braking can happen" + default_value: "100" field: mc.braking_speed_threshold condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_disengage_speed - docs_description: "braking is disabled when speed goes below this value" - docs_default_value: "75" + description: "braking is disabled when speed goes below this value" + default_value: "75" field: mc.braking_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_timeout - docs_description: "timeout in ms for braking" - docs_default_value: "2000" + description: "timeout in ms for braking" + default_value: "2000" field: mc.braking_timeout condition: USE_MR_BRAKING_MODE min: 100 max: 5000 - name: nav_mc_braking_boost_factor - docs_description: "acceleration factor for BOOST phase" - docs_default_value: "100" + description: "acceleration factor for BOOST phase" + default_value: "100" field: mc.braking_boost_factor condition: USE_MR_BRAKING_MODE min: 0 max: 200 - name: nav_mc_braking_boost_timeout - docs_description: "how long in ms BOOST phase can happen" - docs_default_value: "750" + description: "how long in ms BOOST phase can happen" + default_value: "750" field: mc.braking_boost_timeout condition: USE_MR_BRAKING_MODE min: 0 max: 5000 - name: nav_mc_braking_boost_speed_threshold - docs_description: "BOOST can be enabled when speed is above this value" - docs_default_value: "150" + description: "BOOST can be enabled when speed is above this value" + default_value: "150" field: mc.braking_boost_speed_threshold condition: USE_MR_BRAKING_MODE min: 100 max: 1000 - name: nav_mc_braking_boost_disengage_speed - docs_description: "BOOST will be disabled when speed goes below this value" - docs_default_value: "100" + description: "BOOST will be disabled when speed goes below this value" + default_value: "100" field: mc.braking_boost_disengage_speed condition: USE_MR_BRAKING_MODE min: 0 max: 1000 - name: nav_mc_braking_bank_angle - docs_description: "max angle that MR is allowed to bank in BOOST mode" - docs_default_value: "40" + description: "max angle that MR is allowed to bank in BOOST mode" + default_value: "40" field: mc.braking_bank_angle condition: USE_MR_BRAKING_MODE min: 15 max: 60 - name: nav_mc_pos_deceleration_time - docs_description: "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" - docs_default_value: "120" + description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting" + default_value: "120" field: mc.posDecelerationTime condition: USE_NAV min: 0 max: 255 - name: nav_mc_pos_expo - docs_description: "Expo for PosHold control" - docs_default_value: "10" + description: "Expo for PosHold control" + default_value: "10" field: mc.posResponseExpo condition: USE_NAV min: 0 max: 255 - name: nav_fw_cruise_thr - docs_description: "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 )" - docs_default_value: "1400" + description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )" + default_value: "1400" field: fw.cruise_throttle min: 1000 max: 2000 - name: nav_fw_min_thr - docs_description: "Minimum throttle for flying wing in GPS assisted modes" - docs_default_value: "1200" + description: "Minimum throttle for flying wing in GPS assisted modes" + default_value: "1200" field: fw.min_throttle min: 1000 max: 2000 - name: nav_fw_max_thr - docs_description: "Maximum throttle for flying wing in GPS assisted modes" - docs_default_value: "1700" + description: "Maximum throttle for flying wing in GPS assisted modes" + default_value: "1700" field: fw.max_throttle min: 1000 max: 2000 - name: nav_fw_bank_angle - docs_description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" - docs_default_value: "20" + description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll" + default_value: "20" field: fw.max_bank_angle min: 5 max: 80 - name: nav_fw_climb_angle - docs_description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" - docs_default_value: "20" + description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + default_value: "20" field: fw.max_climb_angle min: 5 max: 80 - name: nav_fw_dive_angle - docs_description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" - docs_default_value: "15" + description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit" + default_value: "15" field: fw.max_dive_angle min: 5 max: 80 - name: nav_fw_pitch2thr - docs_description: "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)" - docs_default_value: "10" + description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)" + default_value: "10" field: fw.pitch_to_throttle min: 0 max: 100 - name: nav_fw_loiter_radius - docs_description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" - docs_default_value: "5000" + description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]" + default_value: "5000" field: fw.loiter_radius min: 0 max: 10000 - name: nav_fw_cruise_speed - docs_description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" - docs_default_value: "0" + description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s" + default_value: "0" field: fw.cruise_speed min: 0 max: 65535 - name: nav_fw_control_smoothness - docs_description: "How smoothly the autopilot controls the airplane to correct the navigation error" - docs_default_value: "0" + description: "How smoothly the autopilot controls the airplane to correct the navigation error" + default_value: "0" field: fw.control_smoothness min: 0 max: 9 - name: nav_fw_land_dive_angle - docs_description: "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" - docs_default_value: "2" + description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees" + default_value: "2" field: fw.land_dive_angle condition: NAV_FIXED_WING_LANDING min: -20 max: 20 - name: nav_fw_launch_velocity - docs_description: "Forward velocity threshold for swing-launch detection [cm/s]" - docs_default_value: "300" + description: "Forward velocity threshold for swing-launch detection [cm/s]" + default_value: "300" field: fw.launch_velocity_thresh min: 100 max: 10000 - name: nav_fw_launch_accel - docs_description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" - docs_default_value: "1863" + description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s" + default_value: "1863" field: fw.launch_accel_thresh min: 1000 max: 20000 - name: nav_fw_launch_max_angle - docs_description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" - docs_default_value: "45" + description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]" + default_value: "45" field: fw.launch_max_angle min: 5 max: 180 - name: nav_fw_launch_detect_time - docs_description: "Time for which thresholds have to breached to consider launch happened [ms]" - docs_default_value: "40" + description: "Time for which thresholds have to breached to consider launch happened [ms]" + default_value: "40" field: fw.launch_time_thresh min: 10 max: 1000 - name: nav_fw_launch_thr - docs_description: "Launch throttle - throttle to be set during launch sequence (pwm units)" - docs_default_value: "1700" + description: "Launch throttle - throttle to be set during launch sequence (pwm units)" + default_value: "1700" field: fw.launch_throttle min: 1000 max: 2000 - name: nav_fw_launch_idle_thr - docs_description: "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)" - docs_default_value: "1000" + description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)" + default_value: "1000" field: fw.launch_idle_throttle min: 1000 max: 2000 - name: nav_fw_launch_motor_delay - docs_description: "Delay between detected launch and launch sequence start and throttling up (ms)" - docs_default_value: "500" + description: "Delay between detected launch and launch sequence start and throttling up (ms)" + default_value: "500" field: fw.launch_motor_timer min: 0 max: 5000 - name: nav_fw_launch_spinup_time - docs_description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" - docs_default_value: "100" + description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller" + default_value: "100" field: fw.launch_motor_spinup_time min: 0 max: 1000 - name: nav_fw_launch_min_time - docs_description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." - docs_default_value: "0" + description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]." + default_value: "0" field: fw.launch_min_time min: 0 max: 60000 - name: nav_fw_launch_timeout - docs_description: "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)" - docs_default_value: "5000" + description: "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)" + default_value: "5000" field: fw.launch_timeout max: 60000 - name: nav_fw_launch_max_altitude - docs_description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." - docs_default_value: "0" + description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]." + default_value: "0" field: fw.launch_max_altitude min: 0 max: 60000 - name: nav_fw_launch_climb_angle - docs_description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" - docs_default_value: "18" + description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit" + default_value: "18" field: fw.launch_climb_angle min: 5 max: 45 - name: nav_fw_cruise_yaw_rate - docs_description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" - docs_default_value: "20" + description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]" + default_value: "20" field: fw.cruise_yaw_rate min: 0 max: 60 - name: nav_fw_allow_manual_thr_increase - docs_description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" - docs_default_value: "OFF" + description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing" + default_value: "OFF" field: fw.allow_manual_thr_increase type: bool - name: nav_use_fw_yaw_control - docs_description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" - docs_default_value: "OFF" + description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats" + default_value: "OFF" field: fw.useFwNavYawControl type: bool - name: nav_fw_yaw_deadband - docs_description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" - docs_default_value: "0" + description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course" + default_value: "0" field: fw.yawControlDeadband min: 0 max: 90 @@ -2337,136 +2337,136 @@ groups: condition: USE_TELEMETRY members: - name: telemetry_switch - docs_description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." - docs_default_value: "OFF" + description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed." + default_value: "OFF" type: bool - name: telemetry_inverted - docs_description: "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." - docs_default_value: "OFF" + description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used." + default_value: "OFF" type: bool - name: frsky_default_latitude - docs_description: "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." - docs_default_value: "0.000" + description: "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." + default_value: "0.000" field: gpsNoFixLatitude min: -90 max: 90 - name: frsky_default_longitude - docs_description: "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." - docs_default_value: "0.000" + description: "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." + default_value: "0.000" field: gpsNoFixLongitude min: -180 max: 180 - name: frsky_coordinates_format - docs_description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" - docs_default_value: "0" + description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA" + default_value: "0" field: frsky_coordinate_format min: 0 max: FRSKY_FORMAT_NMEA type: uint8_t # TODO: This seems to use an enum, we should use table: - name: frsky_unit - docs_description: "Not used? [METRIC/IMPERIAL]" - docs_default_value: "METRIC" + description: "Not used? [METRIC/IMPERIAL]" + default_value: "METRIC" table: frsky_unit type: uint8_t - name: frsky_vfas_precision - docs_description: "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" - docs_default_value: "0" + description: "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" + default_value: "0" min: FRSKY_VFAS_PRECISION_LOW max: FRSKY_VFAS_PRECISION_HIGH - name: frsky_pitch_roll - docs_description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" - docs_default_value: "OFF" + description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data" + default_value: "OFF" type: bool - name: report_cell_voltage - docs_description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" - docs_default_value: "OFF" + description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON" + default_value: "OFF" type: bool - name: hott_alarm_sound_interval - docs_description: "Battery alarm delay in seconds for Hott telemetry" - docs_default_value: "5" + description: "Battery alarm delay in seconds for Hott telemetry" + default_value: "5" field: hottAlarmSoundInterval min: 0 max: 120 - name: telemetry_halfduplex - docs_description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" - docs_default_value: "OFF" + description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details" + default_value: "OFF" field: halfDuplex type: bool - name: smartport_fuel_unit - docs_description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" - docs_default_value: "MAH" + description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]" + default_value: "MAH" field: smartportFuelUnit condition: USE_TELEMETRY_SMARTPORT type: uint8_t table: smartport_fuel_unit - name: ibus_telemetry_type - docs_description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." - docs_default_value: "0" + description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details." + default_value: "0" field: ibusTelemetryType min: 0 max: 255 - name: ltm_update_rate - docs_description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." - docs_default_value: "NORMAL" + description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details." + default_value: "NORMAL" field: ltmUpdateRate condition: USE_TELEMETRY_LTM table: ltm_rates - name: sim_ground_station_number - docs_description: "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." - docs_default_value: "Empty string" + description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module." + default_value: "Empty string" field: simGroundStationNumber condition: USE_TELEMETRY_SIM type: string max: 16 - name: sim_pin - docs_description: "PIN code for the SIM module" - docs_default_value: "Empty string" + description: "PIN code for the SIM module" + default_value: "Empty string" field: simPin condition: USE_TELEMETRY_SIM type: string max: 8 - name: sim_transmit_interval - docs_description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" - docs_default_value: "60" + description: "Text message transmission interval in seconds for SIM module. Minimum value: 10" + default_value: "60" field: simTransmitInterval condition: USE_TELEMETRY_SIM type: uint16_t min: SIM_MIN_TRANSMIT_INTERVAL max: 65535 - name: sim_transmit_flags - docs_description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" - docs_default_value: "F" + description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low" + default_value: "F" field: simTransmitFlags condition: USE_TELEMETRY_SIM type: string max: SIM_N_TX_FLAGS - name: acc_event_threshold_high - docs_description: "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." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off." + default_value: "0" field: accEventThresholdHigh condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: acc_event_threshold_low - docs_description: "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." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off." + default_value: "0" field: accEventThresholdLow condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 900 - name: acc_event_threshold_neg_x - docs_description: "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." - docs_default_value: "0" + description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off." + default_value: "0" field: accEventThresholdNegX condition: USE_TELEMETRY_SIM type: uint16_t min: 0 max: 65535 - name: sim_low_altitude - docs_description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." - docs_default_value: "0" + description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`." + default_value: "0" field: simLowAltitude condition: USE_TELEMETRY_SIM type: int16_t @@ -2534,8 +2534,8 @@ groups: condition: USE_LED_STRIP members: - name: ledstrip_visual_beeper - docs_description: "" - docs_default_value: "OFF" + description: "" + default_value: "OFF" type: bool - name: PG_OSD_CONFIG @@ -2544,125 +2544,125 @@ groups: condition: USE_OSD members: - name: osd_video_system - docs_description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" - docs_default_value: "AUTO" + description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`" + default_value: "AUTO" table: osd_video_system field: video_system type: uint8_t - name: osd_row_shiftdown - docs_description: "Number of rows to shift the OSD display (increase if top rows are cut off)" - docs_default_value: "0" + description: "Number of rows to shift the OSD display (increase if top rows are cut off)" + default_value: "0" field: row_shiftdown min: 0 max: 1 - name: osd_units - docs_description: "IMPERIAL, METRIC, UK" - docs_default_value: "METRIC" + description: "IMPERIAL, METRIC, UK" + default_value: "METRIC" field: units table: osd_unit type: uint8_t - name: osd_stats_energy_unit - docs_description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" - docs_default_value: "MAH" + description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)" + default_value: "MAH" field: stats_energy_unit table: osd_stats_energy_unit type: uint8_t - name: osd_rssi_alarm - docs_description: "Value bellow which to make the OSD RSSI indicator blink" - docs_default_value: "20" + description: "Value bellow which to make the OSD RSSI indicator blink" + default_value: "20" field: rssi_alarm min: 0 max: 100 - name: osd_time_alarm - docs_description: "Value above which to make the OSD flight time indicator blink (minutes)" - docs_default_value: "10" + description: "Value above which to make the OSD flight time indicator blink (minutes)" + default_value: "10" field: time_alarm min: 0 max: 600 - name: osd_alt_alarm - docs_description: "Value above which to make the OSD relative altitude indicator blink (meters)" - docs_default_value: "100" + description: "Value above which to make the OSD relative altitude indicator blink (meters)" + default_value: "100" field: alt_alarm min: 0 max: 10000 - name: osd_dist_alarm - docs_description: "Value above which to make the OSD distance from home indicator blink (meters)" - docs_default_value: "1000" + description: "Value above which to make the OSD distance from home indicator blink (meters)" + default_value: "1000" field: dist_alarm min: 0 max: 50000 - name: osd_neg_alt_alarm - docs_description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" - docs_default_value: "5" + description: "Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters)" + default_value: "5" field: neg_alt_alarm min: 0 max: 10000 - name: osd_current_alarm - docs_description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." - docs_default_value: "0" + description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes." + default_value: "0" field: current_alarm min: 0 max: 255 - name: osd_gforce_alarm - docs_description: "Value above which the OSD g force indicator will blink (g)" - docs_default_value: "5" + description: "Value above which the OSD g force indicator will blink (g)" + default_value: "5" field: gforce_alarm min: 0 max: 20 - name: osd_gforce_axis_alarm_min - docs_description: "Value under which the OSD axis g force indicators will blink (g)" - docs_default_value: "-5" + description: "Value under which the OSD axis g force indicators will blink (g)" + default_value: "-5" field: gforce_axis_alarm_min min: -20 max: 20 - name: osd_gforce_axis_alarm_max - docs_description: "Value above which the OSD axis g force indicators will blink (g)" - docs_default_value: "5" + description: "Value above which the OSD axis g force indicators will blink (g)" + default_value: "5" field: gforce_axis_alarm_max min: -20 max: 20 - name: osd_imu_temp_alarm_min - docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: imu_temp_alarm_min min: -550 max: 1250 - name: osd_imu_temp_alarm_max - docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "600" + description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "600" field: imu_temp_alarm_max min: -550 max: 1250 - name: osd_esc_temp_alarm_max - docs_description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "900" + description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "900" field: esc_temp_alarm_max min: -550 max: 1500 - name: osd_esc_temp_alarm_min - docs_description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: esc_temp_alarm_min min: -550 max: 1500 - name: osd_baro_temp_alarm_min - docs_description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "-200" + description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "-200" field: baro_temp_alarm_min condition: USE_BARO min: -550 max: 1250 - name: osd_baro_temp_alarm_max - docs_description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" - docs_default_value: "600" + description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)" + default_value: "600" field: baro_temp_alarm_max condition: USE_BARO min: -550 max: 1250 - name: osd_temp_label_align - docs_description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" - docs_default_value: "LEFT" + description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" + default_value: "LEFT" field: temp_label_align condition: USE_TEMPERATURE_SENSOR table: osd_alignment @@ -2672,8 +2672,8 @@ groups: field: ahi_reverse_roll type: bool - name: osd_artificial_horizon_max_pitch - docs_description: "Max pitch, in degrees, for OSD artificial horizon" - docs_default_value: "20" + description: "Max pitch, in degrees, for OSD artificial horizon" + default_value: "20" field: ahi_max_pitch min: 10 max: 90 @@ -2728,8 +2728,8 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp - docs_description: "Controls display of the next waypoints in the HUD." - docs_default_value: "OFF" + description: "Controls display of the next waypoints in the HUD." + default_value: "OFF" field: hud_wp_disp min: 0 max: 3 @@ -2745,8 +2745,8 @@ groups: field: sidebar_scroll_arrows type: bool - name: osd_main_voltage_decimals - docs_description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." - docs_default_value: "1" + description: "Number of decimals for the battery voltages displayed in the OSD [1-2]." + default_value: "1" field: main_voltage_decimals min: 1 max: 2 @@ -2756,15 +2756,15 @@ groups: max: 11 - name: osd_estimations_wind_compensation - docs_description: "Use wind estimation for remaining flight time/distance estimation" - docs_default_value: "ON" + description: "Use wind estimation for remaining flight time/distance estimation" + default_value: "ON" condition: USE_WIND_ESTIMATOR field: estimations_wind_compensation type: bool - name: osd_failsafe_switch_layout - docs_description: "If enabled the OSD automatically switches to the first layout during failsafe" - docs_default_value: "OFF" + description: "If enabled the OSD automatically switches to the first layout during failsafe" + default_value: "OFF" type: bool - name: osd_plus_code_digits @@ -2773,8 +2773,8 @@ groups: max: 13 - name: osd_ahi_style - docs_description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." - docs_default_value: "DEFAULT" + description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD." + default_value: "DEFAULT" table: osd_ahi_style - name: PG_SYSTEM_CONFIG @@ -2782,35 +2782,35 @@ groups: headers: ["fc/config.h"] members: - name: i2c_speed - docs_description: "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)" - docs_default_value: "400KHZ" + description: "This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)" + default_value: "400KHZ" condition: USE_I2C table: i2c_speed - name: cpu_underclock - docs_description: "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" - docs_default_value: "OFF" + description: "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" + default_value: "OFF" field: cpuUnderclock condition: USE_UNDERCLOCK type: bool - name: debug_mode table: debug_modes - name: throttle_tilt_comp_str - docs_description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." - docs_default_value: "0" + description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." + default_value: "0" field: throttle_tilt_compensation_strength min: 0 max: 100 - name: name - docs_description: "Craft name" - docs_default_value: "Empty string" + description: "Craft name" + default_value: "Empty string" - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG type: modeActivationOperatorConfig_t headers: ["fc/rc_modes.h"] members: - name: mode_range_logic_operator - docs_description: "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." - docs_default_value: "OR" + description: "Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode." + default_value: "OR" field: modeActivationOperator table: aux_operator type: uint8_t @@ -2821,17 +2821,17 @@ groups: condition: USE_STATS members: - name: stats - docs_description: "General switch of the statistics recording feature (a.k.a. odometer)" - docs_default_value: "OFF" + description: "General switch of the statistics recording feature (a.k.a. odometer)" + default_value: "OFF" field: stats_enabled type: bool - name: stats_total_time - docs_description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." - docs_default_value: "0" + description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled." + default_value: "0" max: INT32_MAX - name: stats_total_dist - docs_description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." - docs_default_value: "0" + description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled." + default_value: "0" max: INT32_MAX - name: stats_total_energy max: INT32_MAX @@ -2842,13 +2842,13 @@ groups: headers: ["common/time.h"] members: - name: tz_offset - docs_description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" - docs_default_value: "0" + description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs" + default_value: "0" min: -1440 max: 1440 - name: tz_automatic_dst - docs_description: "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`." - docs_default_value: "OFF" + description: "Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`." + default_value: "OFF" type: uint8_t table: tz_automatic_dst @@ -2857,8 +2857,8 @@ groups: headers: ["drivers/display.h"] members: - name: display_force_sw_blink - docs_description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" - docs_default_value: "OFF" + description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON" + default_value: "OFF" field: force_sw_blink type: bool @@ -2868,8 +2868,8 @@ groups: condition: USE_VTX_CONTROL members: - name: vtx_halfduplex - docs_description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." - docs_default_value: "ON" + description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC." + default_value: "ON" field: halfDuplex type: bool @@ -2878,26 +2878,26 @@ groups: headers: ["drivers/vtx_common.h", "io/vtx.h"] members: - name: vtx_band - docs_description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." - docs_default_value: "4" + description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race." + default_value: "4" field: band min: VTX_SETTINGS_NO_BAND max: VTX_SETTINGS_MAX_BAND - name: vtx_channel - docs_description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." - docs_default_value: "1" + description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]." + default_value: "1" field: channel min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_power - docs_description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." - docs_default_value: "1" + description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware." + default_value: "1" field: power min: VTX_SETTINGS_MIN_POWER max: VTX_SETTINGS_MAX_POWER - name: vtx_low_power_disarm - docs_description: "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." - docs_default_value: "OFF" + description: "When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled." + default_value: "OFF" field: lowPowerDisarm table: vtx_low_power_disarm type: uint8_t diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index 4fe2bacd35..47bd255ab6 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -2,18 +2,12 @@ import yaml # pyyaml / python-yaml -CLI_MD_PATH = "docs/Cli.md" +SETTINGS_MD_PATH = "docs/Settings.md" SETTINGS_YAML_PATH = "src/main/fc/settings.yaml" -CLI_MD_SECTION_HEADER = "## CLI Variable Reference" - -# Read the contents of the markdown CLI docs -def read_cli_md(): - with open(CLI_MD_PATH, "r") as cli_md: - return cli_md.readlines() - -# Parse the YAML settings specs def parse_settings_yaml(): + """Parse the YAML settings specs""" + with open(SETTINGS_YAML_PATH, "r") as settings_yaml: return yaml.load(settings_yaml, Loader=yaml.Loader) @@ -24,10 +18,10 @@ def generate_md_table_from_yaml(settings_yaml): # Extract description and default value of each setting from the YAML specs (if present) for group in settings_yaml['groups']: for member in group['members']: - if any(key in member for key in ["docs_description", "docs_default_value"]): + if any(key in member for key in ["description", "default_value"]): params[member['name']] = { - "description": member["docs_description"] if "docs_description" in member else "", - "default": member["docs_default_value"] if "docs_default_value" in member else "" + "description": member["description"] if "description" in member else "", + "default": member["default_value"] if "default_value" in member else "" } # MD table header @@ -43,42 +37,17 @@ def generate_md_table_from_yaml(settings_yaml): # Return the assembled table return md_table_lines -def replace_md_table_in_cli_md(cli_md_lines, md_table_lines): - """Update the settings table in the CLI docs +def write_settings_md(lines): + """Write the contents of the CLI settings docs""" - Copy all the original lines up to $CLI_MD_SECTION_HEADER (including the following newline), then insert - the updated table in place of the next block of text (replace everything until an empty line is found). - """ - new_lines = [] - lines_to_skip = 0 - skip_until_empty_line = False - for line in cli_md_lines: - if lines_to_skip > 0: - lines_to_skip -= 1 - if lines_to_skip == 0: - skip_until_empty_line = True - continue - elif skip_until_empty_line: - if line != "\n": - continue - else: - skip_until_empty_line = False - new_lines.append("\n") - new_lines += md_table_lines - if line.startswith(CLI_MD_SECTION_HEADER): - lines_to_skip = 2 - new_lines.append(line) - - return new_lines - -# Write the contents of the markdown CLI docs -def write_cli_md(lines): - with open(CLI_MD_PATH, "w") as cli_md: - cli_md.writelines(lines) + with open(SETTINGS_MD_PATH, "w") as settings_md: + settings_md.writelines(lines) if __name__ == "__main__": settings_yaml = parse_settings_yaml() md_table_lines = generate_md_table_from_yaml(settings_yaml) - cli_md_lines = read_cli_md() - cli_md_lines = replace_md_table_in_cli_md(cli_md_lines, md_table_lines) - write_cli_md(cli_md_lines) + settings_md_lines = \ + ["# CLI Variable Reference\n", "\n" ] + \ + md_table_lines + \ + ["\n", "> Note: this table is autogenerated. Do not edit it manually."] + write_settings_md(settings_md_lines) From e7e431477c9e871d90157ee99f8113fd7671c5b1 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Alberto=20Garci=CC=81a=20Hierro?= Date: Mon, 22 Jun 2020 14:45:14 +0100 Subject: [PATCH 06/16] [OSD] Fix overflow in osdGridBufferClearGridRect() Width was added twice, causing an overflow when 2x the rect width ended up being bigger than the screen width in grid columns. --- src/main/drivers/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/drivers/osd.c b/src/main/drivers/osd.c index 231d8eec28..bddefea7ce 100644 --- a/src/main/drivers/osd.c +++ b/src/main/drivers/osd.c @@ -72,7 +72,7 @@ void osdGridBufferClearGridRect(int x, int y, int w, int h) osdGridBufferConstrainRect(&x, &y, &w, &h, OSD_CHARACTER_GRID_MAX_WIDTH, OSD_CHARACTER_GRID_MAX_HEIGHT); int maxX = x + w; int maxY = y + h; - for (int ii = x; ii <= maxX + w; ii++) { + for (int ii = x; ii <= maxX; ii++) { for (int jj = y; jj <= maxY; jj++) { *osdCharacterGridBufferGetEntryPtr(ii, jj) = 0; } From dc2052ba1c6a3b1873a256b9c7d4b4bc0ded93da Mon Sep 17 00:00:00 2001 From: Magnus Ivarsson Date: Sun, 5 Jul 2020 23:08:50 +0200 Subject: [PATCH 07/16] Remove pin conflict between non existent current adc pin and the pwm output 6 https://github.com/iNavFlight/inav/issues/5911 --- src/main/target/PIKOBLX/target.h | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 1d7f31c531..c60d00116b 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -64,9 +64,10 @@ #define BOARD_HAS_VOLTAGE_DIVIDER #define USE_ADC #define ADC_INSTANCE ADC2 -#define ADC_CHANNEL_1_PIN PA2 +//#define ADC_CHANNEL_1_PIN PA2 <-- conflict with pwm output 6, and the board does not have current sensor #define ADC_CHANNEL_2_PIN PA5 -#define ADC_CHANNEL_3_PIN PB2 +//#define ADC_CHANNEL_3_PIN PB2 <-- the board does not have a rssi pad + #define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 #define VBAT_ADC_CHANNEL ADC_CHN_2 #define RSSI_ADC_CHANNEL ADC_CHN_3 From 44569790b189d6f4638855ac78763566773b24bf Mon Sep 17 00:00:00 2001 From: Daniel Arruda Ribeiro Date: Mon, 6 Jul 2020 18:04:07 -0300 Subject: [PATCH 08/16] Add Azimuth OSD element --- src/main/cms/cms_menu_osd.c | 1 + src/main/drivers/osd_symbols.h | 2 +- src/main/io/osd.c | 24 ++++++++++++++++++++++++ src/main/io/osd.h | 1 + 4 files changed, 27 insertions(+), 1 deletion(-) diff --git a/src/main/cms/cms_menu_osd.c b/src/main/cms/cms_menu_osd.c index 901bb0e171..33eab41670 100755 --- a/src/main/cms/cms_menu_osd.c +++ b/src/main/cms/cms_menu_osd.c @@ -184,6 +184,7 @@ static const OSD_Entry menuOsdElemsEntries[] = OSD_ELEMENT_ENTRY("GPS HDOP", OSD_GPS_HDOP), OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED), OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE), + OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH), #endif // GPS OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING), OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH), diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 0b08e7b51d..d82d1c197f 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -118,7 +118,7 @@ #define SYM_RPM 0x8B // 139 RPM #define SYM_WAYPOINT 0x8C // 140 Waypoint -// 0x8D // 141 - +#define SYM_AZIMUTH 0x8D // 141 Azimuth // 0x8E // 142 - // 0x8F // 143 - diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f7a0f2d943..c3033400dd 100755 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2405,6 +2405,28 @@ static bool osdDrawSingleElement(uint8_t item) break; } + case OSD_AZIMUTH: + { + + buff[0] = SYM_AZIMUTH; + if (osdIsHeadingValid()) { + int16_t h = GPS_directionToHome; + if (h < 0) { + h += 360; + } + if(h >= 180) + h = h - 180; + else + h = h + 180; + + tfp_sprintf(&buff[1], "%3d", h); + } else { + buff[1] = buff[2] = buff[3] = '-'; + } + buff[4] = '\0'; + break; + } + case OSD_MAP_SCALE: { float scaleToUnit; @@ -2644,6 +2666,8 @@ void pgResetFn_osdConfig(osdConfig_t *osdConfig) osdConfig->item_pos[0][OSD_FLYMODE] = OSD_POS(13, 12) | OSD_VISIBLE_FLAG; osdConfig->item_pos[0][OSD_GPS_LON] = OSD_POS(18, 12); + osdConfig->item_pos[0][OSD_AZIMUTH] = OSD_POS(2, 12); + osdConfig->item_pos[0][OSD_ROLL_PIDS] = OSD_POS(2, 10); osdConfig->item_pos[0][OSD_PITCH_PIDS] = OSD_POS(2, 11); osdConfig->item_pos[0][OSD_YAW_PIDS] = OSD_POS(2, 12); diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 00dc2fd6d7..c641875e60 100755 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -152,6 +152,7 @@ typedef enum { OSD_VTX_POWER, OSD_ESC_RPM, OSD_ESC_TEMPERATURE, + OSD_AZIMUTH, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 268cc00f6a983c69eeeaddc7128e8232813b34c5 Mon Sep 17 00:00:00 2001 From: Olivier C Date: Tue, 7 Jul 2020 12:44:11 +0200 Subject: [PATCH 09/16] Settings.yaml, adding descriptions and defaults for the hud --- src/main/fc/settings.yaml | 31 +++++++++++++++++++++++++++++-- 1 file changed, 29 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 4af45ae2fd..5ff8f441b3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2678,59 +2678,86 @@ groups: min: 10 max: 90 - name: osd_crosshairs_style + description: "To set the visual type for the crosshair" + default_value: "DEFAULT" field: crosshairs_style table: osd_crosshairs_style type: uint8_t - name: osd_horizon_offset + description: "To vertically adjust the whole OSD and AHI and scrolling bars" + default_value: "0" field: horizon_offset min: -2 max: 2 - name: osd_camera_uptilt + description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal" + default_value: "0" field: camera_uptilt min: -40 max: 80 - name: osd_camera_fov_h + description: "Horizontal field of view for the camera in degres" + default_value: "135" field: camera_fov_h min: 60 max: 150 - name: osd_camera_fov_v + description: "Vertical field of view for the camera in degres" + default_value: "85" field: camera_fov_v min: 30 max: 120 - name: osd_hud_margin_h + description: "Left and right margins for the hud area" + default_value: "3" field: hud_margin_h min: 0 max: 4 - name: osd_hud_margin_v + description: "Top and bottom margins for the hud area" + default_value: "3" field: hud_margin_v min: 1 max: 3 - name: osd_hud_homing + description: "To display little arrows around the crossair showing where the home point is in the hud" + default_value: "0" field: hud_homing type: bool - name: osd_hud_homepoint + description: "To 3D-display the home point location in the hud" + default_value: "0" field: hud_homepoint type: bool - name: osd_hud_radar_disp + description: "Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc" + default_value: "0" field: hud_radar_disp min: 0 max: 4 - name: osd_hud_radar_range_min + description: "In meters, radar aircrafts closer than this will not be displayed in the hud" + default_value: "3" field: hud_radar_range_min min: 1 max: 30 - name: osd_hud_radar_range_max + description: "In meters, radar aircrafts further away than this will not be displayed in the hud" + default_value: 4000" field: hud_radar_range_max min: 100 max: 9990 - name: osd_hud_radar_nearest + description: "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." + default_value: "0" field: hud_radar_nearest min: 0 max: 4000 - name: osd_hud_wp_disp - description: "Controls display of the next waypoints in the HUD." - default_value: "OFF" + description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked "1") and the 5th waypoint (marked "2")" + default_value: "0" field: hud_wp_disp + min: 0 max: 3 - name: osd_left_sidebar_scroll From e5c0d0d58aa13afcc582e001c606a7b4cde2d2c0 Mon Sep 17 00:00:00 2001 From: Olivier C Date: Tue, 7 Jul 2020 14:39:38 +0200 Subject: [PATCH 10/16] Removing quotes --- src/main/fc/settings.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5ff8f441b3..5f2bcd596a 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2754,7 +2754,7 @@ groups: min: 0 max: 4000 - name: osd_hud_wp_disp - description: "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")" + description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)" default_value: "0" field: hud_wp_disp From 5a48f994c146d5c2c2f79cf5f020f4e34e7afc19 Mon Sep 17 00:00:00 2001 From: ShikOfTheRa Date: Tue, 7 Jul 2020 14:19:53 +0100 Subject: [PATCH 11/16] Update Building in Windows 10 with Linux Subsystem.md --- .../Building in Windows 10 with Linux Subsystem.md | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/development/Building in Windows 10 with Linux Subsystem.md b/docs/development/Building in Windows 10 with Linux Subsystem.md index 5ed64eb83f..39ca71cf9b 100644 --- a/docs/development/Building in Windows 10 with Linux Subsystem.md +++ b/docs/development/Building in Windows 10 with Linux Subsystem.md @@ -12,7 +12,7 @@ reboot Install Ubuntu: 1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home -1. Search and install most recent Ubunto LTS version +1. Search and install most recent Ubuntu LTS version 1. When download completed, select `Launch Ubuntu` 1. When prompted enter a user name and password which you will need to remember 1. When complete, the linux command prompt will be displayed @@ -41,7 +41,7 @@ You now have a folder called inav in the root of C drive that you can edit in wi ## Building (example): Launch Ubuntu: -Click Windows Start button then scroll and lauch "Ubunto" +Click Windows Start button then scroll and lauch "Ubuntu" Building from Ubunto command line `cd /mnt/c/inav` From 7e3c0789e67e78f5bce2530511ed76a2799c446e Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Tue, 7 Jul 2020 18:13:08 +0100 Subject: [PATCH 12/16] [DOC] document log_level and log_topic --- src/main/fc/settings.yaml | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5f2bcd596a..ce545ab777 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2222,7 +2222,7 @@ groups: field: fw.cruise_speed min: 0 max: 65535 - - name: nav_fw_control_smoothness + - name: nav_fw_control_smoothness description: "How smoothly the autopilot controls the airplane to correct the navigation error" default_value: "0" field: fw.control_smoothness @@ -2679,25 +2679,25 @@ groups: max: 90 - name: osd_crosshairs_style description: "To set the visual type for the crosshair" - default_value: "DEFAULT" + default_value: "DEFAULT" field: crosshairs_style table: osd_crosshairs_style type: uint8_t - name: osd_horizon_offset description: "To vertically adjust the whole OSD and AHI and scrolling bars" - default_value: "0" + default_value: "0" field: horizon_offset min: -2 max: 2 - name: osd_camera_uptilt description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal" - default_value: "0" + default_value: "0" field: camera_uptilt min: -40 max: 80 - name: osd_camera_fov_h description: "Horizontal field of view for the camera in degres" - default_value: "135" + default_value: "135" field: camera_fov_h min: 60 max: 150 @@ -2971,11 +2971,14 @@ groups: - name: log_level field: level table: log_level + description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage." + default_value: "`ERROR`" - name: log_topics field: topics min: 0 max: UINT32_MAX - + description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage." + default_value: "0" - name: PG_ESC_SENSOR_CONFIG type: escSensorConfig_t headers: ["sensors/esc_sensor.h"] From 29c94d7284e01b8da1b1d91d8a13615685816dec Mon Sep 17 00:00:00 2001 From: "Konstantin (DigitalEntity) Sharlaimov" Date: Wed, 8 Jul 2020 15:03:23 +0200 Subject: [PATCH 13/16] [DPS310] Fix temperature readings --- src/main/drivers/barometer/barometer_dps310.c | 32 ++++++++++++++++--- src/main/sensors/barometer.c | 1 + src/main/sensors/temperature.c | 4 +-- 3 files changed, 31 insertions(+), 6 deletions(-) diff --git a/src/main/drivers/barometer/barometer_dps310.c b/src/main/drivers/barometer/barometer_dps310.c index dcedfc373c..5fbe12fc69 100644 --- a/src/main/drivers/barometer/barometer_dps310.c +++ b/src/main/drivers/barometer/barometer_dps310.c @@ -68,7 +68,11 @@ #define DPS310_MEAS_CFG_SENSOR_RDY (1 << 6) #define DPS310_MEAS_CFG_TMP_RDY (1 << 5) #define DPS310_MEAS_CFG_PRS_RDY (1 << 4) + +#define DPS310_MEAS_CFG_MEAS_CTRL_MASK (0x7) #define DPS310_MEAS_CFG_MEAS_CTRL_CONT (0x7) +#define DPS310_MEAS_CFG_MEAS_TEMP_SING (0x2) +#define DPS310_MEAS_CFG_MEAS_IDLE (0x0) #define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec. #define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard). @@ -116,16 +120,21 @@ static void registerWrite(busDevice_t * busDev, uint8_t reg, uint8_t value) busWrite(busDev, reg, value); } -static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +static void registerWriteBits(busDevice_t * busDev, uint8_t reg, uint8_t mask, uint8_t bits) { uint8_t val = registerRead(busDev, reg); - if ((val & setbits) != setbits) { - val |= setbits; + if ((val & mask) != bits) { + val = (val & (~mask)) | bits; registerWrite(busDev, reg, val); } } +static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits) +{ + registerWriteBits(busDev, reg, setbits, setbits); +} + static int32_t getTwosComplement(uint32_t raw, uint8_t length) { if (raw & ((int)1 << (length - 1))) { @@ -190,6 +199,21 @@ static bool deviceConfigure(busDevice_t * busDev) // 0x20 c30 [15:8] + 0x21 c30 [7:0] baroState.calib.c30 = getTwosComplement(((uint32_t)coef[16] << 8) | (uint32_t)coef[17], 16); + // MEAS_CFG: Make sure the device is in IDLE mode + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_IDLE); + + // Fix IC with a fuse bit problem, which lead to a wrong temperature + // Should not affect ICs without this problem + registerWrite(busDev, 0x0E, 0xA5); + registerWrite(busDev, 0x0F, 0x96); + registerWrite(busDev, 0x62, 0x02); + registerWrite(busDev, 0x0E, 0x00); + registerWrite(busDev, 0x0F, 0x00); + + // Make ONE temperature measurement and flush it + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_TEMP_SING); + delay(40); + // PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard) registerSetBits(busDev, DPS310_REG_PRS_CFG, DPS310_PRS_CFG_BIT_PM_RATE_32HZ | DPS310_PRS_CFG_BIT_PM_PRC_16); @@ -201,7 +225,7 @@ static bool deviceConfigure(busDevice_t * busDev) registerSetBits(busDev, DPS310_REG_CFG_REG, DPS310_CFG_REG_BIT_T_SHIFT | DPS310_CFG_REG_BIT_P_SHIFT); // MEAS_CFG: Continuous pressure and temperature measurement - registerSetBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_CONT); + registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_CTRL_CONT); return true; } diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 567264f783..49d8d0cc59 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -20,6 +20,7 @@ #include #include "platform.h" +#include "build/debug.h" #include "common/calibration.h" #include "common/log.h" diff --git a/src/main/sensors/temperature.c b/src/main/sensors/temperature.c index 28cf60802d..5cb146cf16 100644 --- a/src/main/sensors/temperature.c +++ b/src/main/sensors/temperature.c @@ -210,13 +210,13 @@ PROTOTHREAD(temperatureUpdate) } else mpuBaroTempValid &= ~(1 << MPU_TEMP_VALID_BIT); - #ifdef USE_BARO +#ifdef USE_BARO if (sensors(SENSOR_BARO)) { baroTemperature = baroGetTemperature(); mpuBaroTempValid |= (1 << BARO_TEMP_VALID_BIT); } else mpuBaroTempValid &= ~(1 << BARO_TEMP_VALID_BIT); - #endif +#endif #ifdef USE_TEMPERATURE_SENSOR From 47cd8f317de376511e650266545f84805c2077b4 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Wed, 8 Jul 2020 15:18:52 +0200 Subject: [PATCH 14/16] Refactor LC, GF and GVAR to use single scheduler task --- make/source.mk | 7 ++-- src/main/fc/cli.c | 24 ++++++------- src/main/fc/fc_core.c | 4 +-- src/main/fc/fc_init.c | 4 +-- src/main/fc/fc_msp.c | 16 ++++----- src/main/fc/fc_tasks.c | 26 ++++---------- src/main/flight/mixer.c | 6 ++-- src/main/flight/pid.c | 4 +-- src/main/flight/servos.c | 8 ++--- src/main/flight/servos.h | 4 +-- .../global_functions.c | 6 ++-- .../global_functions.h | 2 +- .../global_variables.c | 4 +-- .../global_variables.h | 0 .../{common => programming}/logic_condition.c | 6 ++-- .../{common => programming}/logic_condition.h | 0 src/main/programming/programming_task.c | 35 +++++++++++++++++++ src/main/programming/programming_task.h | 27 ++++++++++++++ src/main/scheduler/scheduler.h | 7 ++-- src/main/target/common.h | 3 +- 20 files changed, 120 insertions(+), 73 deletions(-) rename src/main/{common => programming}/global_functions.c (98%) rename src/main/{common => programming}/global_functions.h (98%) rename src/main/{common => programming}/global_variables.c (96%) rename src/main/{common => programming}/global_variables.h (100%) rename src/main/{common => programming}/logic_condition.c (99%) rename src/main/{common => programming}/logic_condition.h (100%) create mode 100644 src/main/programming/programming_task.c create mode 100644 src/main/programming/programming_task.h diff --git a/make/source.mk b/make/source.mk index 6c4800aa35..e1b9aa1284 100644 --- a/make/source.mk +++ b/make/source.mk @@ -14,9 +14,6 @@ COMMON_SRC = \ common/filter.c \ common/gps_conversion.c \ common/log.c \ - common/logic_condition.c \ - common/global_functions.c \ - common/global_variables.c \ common/maths.c \ common/memory.c \ common/olc.c \ @@ -26,6 +23,10 @@ COMMON_SRC = \ common/time.c \ common/typeconversion.c \ common/uvarint.c \ + programming/logic_condition.c \ + programming/global_functions.c \ + programming/global_variables.c \ + programming/programming_task.c \ config/config_eeprom.c \ config/config_streamer.c \ config/feature.c \ diff --git a/src/main/fc/cli.c b/src/main/fc/cli.c index dc6f43f071..a63a0946ff 100755 --- a/src/main/fc/cli.c +++ b/src/main/fc/cli.c @@ -43,8 +43,8 @@ extern uint8_t __config_end; #include "common/memory.h" #include "common/time.h" #include "common/typeconversion.h" -#include "common/global_functions.h" -#include "common/global_variables.h" +#include "programming/global_functions.h" +#include "programming/global_variables.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -1682,7 +1682,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer && customServoMixer.inputSource == customServoMixerDefault.inputSource && customServoMixer.rate == customServoMixerDefault.rate && customServoMixer.speed == customServoMixerDefault.speed - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK && customServoMixer.conditionId == customServoMixerDefault.conditionId #endif ; @@ -1693,7 +1693,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer customServoMixerDefault.inputSource, customServoMixerDefault.rate, customServoMixerDefault.speed, - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixer.conditionId #else 0 @@ -1706,7 +1706,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer customServoMixer.inputSource, customServoMixer.rate, customServoMixer.speed, - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixer.conditionId #else 0 @@ -1753,7 +1753,7 @@ static void cliServoMix(char *cmdline) customServoMixersMutable(i)->inputSource = args[INPUT]; customServoMixersMutable(i)->rate = args[RATE]; customServoMixersMutable(i)->speed = args[SPEED]; - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixersMutable(i)->conditionId = args[CONDITION]; #endif cliServoMix(""); @@ -1763,7 +1763,7 @@ static void cliServoMix(char *cmdline) } } -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions) { @@ -1950,7 +1950,7 @@ static void cliGvar(char *cmdline) { #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions) { @@ -3321,7 +3321,7 @@ static void printConfig(const char *cmdline, bool doDiff) cliPrintHashLine("servo"); printServo(dumpMask, servoParams_CopyArray, servoParams(0)); -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK cliPrintHashLine("logic"); printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0)); @@ -3329,7 +3329,7 @@ static void printConfig(const char *cmdline, bool doDiff) printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0)); #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK cliPrintHashLine("gf"); printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0)); #endif @@ -3576,7 +3576,7 @@ const clicmd_t cmdTable[] = { CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", " [baud] [mode] : passthrough to serial", cliSerialPassthrough), #endif CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo), -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK CLI_COMMAND_DEF("logic", "configure logic conditions", " \r\n" "\treset\r\n", cliLogic), @@ -3585,7 +3585,7 @@ const clicmd_t cmdTable[] = { " \r\n" "\treset\r\n", cliGvar), #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK CLI_COMMAND_DEF("gf", "configure global functions", " \r\n" "\treset\r\n", cliGlobalFunctions), diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index dc50817963..9aece7e69d 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -32,7 +32,7 @@ FILE_COMPILE_FOR_SPEED #include "common/color.h" #include "common/utils.h" #include "common/filter.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" #include "drivers/light_led.h" #include "drivers/serial.h" @@ -446,7 +446,7 @@ void releaseSharedTelemetryPorts(void) { void tryArm(void) { updateArmingStatus(); -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK if ( !isArmingDisabled() || emergencyArmingIsEnabled() || diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c index ac4656bcac..1ee4dd016d 100644 --- a/src/main/fc/fc_init.c +++ b/src/main/fc/fc_init.c @@ -35,7 +35,7 @@ #include "common/maths.h" #include "common/memory.h" #include "common/printf.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "config/config_eeprom.h" #include "config/feature.h" @@ -286,7 +286,7 @@ void init(void) logInit(); #endif -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK gvInit(); #endif diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index 066e02dd5f..f20e576d5e 100644 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -35,8 +35,8 @@ #include "common/bitarray.h" #include "common/time.h" #include "common/utils.h" -#include "common/global_functions.h" -#include "common/global_variables.h" +#include "programming/global_functions.h" +#include "programming/global_variables.h" #include "config/parameter_group_ids.h" @@ -520,14 +520,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF sbufWriteU8(dst, customServoMixers(i)->inputSource); sbufWriteU16(dst, customServoMixers(i)->rate); sbufWriteU8(dst, customServoMixers(i)->speed); - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK sbufWriteU8(dst, customServoMixers(i)->conditionId); #else sbufWriteU8(dst, -1); #endif } break; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_LOGIC_CONDITIONS: for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) { sbufWriteU8(dst, logicConditions(i)->enabled); @@ -551,7 +551,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF } break; #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_GLOBAL_FUNCTIONS: for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) { sbufWriteU8(dst, globalFunctions(i)->enabled); @@ -1928,7 +1928,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) customServoMixersMutable(tmp_u8)->inputSource = sbufReadU8(src); customServoMixersMutable(tmp_u8)->rate = sbufReadU16(src); customServoMixersMutable(tmp_u8)->speed = sbufReadU8(src); - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK customServoMixersMutable(tmp_u8)->conditionId = sbufReadU8(src); #else sbufReadU8(src); @@ -1937,7 +1937,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) } else return MSP_RESULT_ERROR; break; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_SET_LOGIC_CONDITIONS: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 15) && (tmp_u8 < MAX_LOGIC_CONDITIONS)) { @@ -1953,7 +1953,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src) return MSP_RESULT_ERROR; break; #endif -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK case MSP2_INAV_SET_GLOBAL_FUNCTIONS: sbufReadU8Safe(&tmp_u8, src); if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) { diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index 7a5c64b06d..f79c596b9f 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -26,8 +26,7 @@ #include "common/axis.h" #include "common/color.h" #include "common/utils.h" -#include "common/logic_condition.h" -#include "common/global_functions.h" +#include "programming/programming_task.h" #include "drivers/accgyro/accgyro.h" #include "drivers/compass/compass.h" @@ -355,11 +354,8 @@ void fcTasksInit(void) #ifdef USE_RCDEVICE setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled()); #endif -#ifdef USE_LOGIC_CONDITIONS - setTaskEnabled(TASK_LOGIC_CONDITIONS, true); -#endif -#ifdef USE_GLOBAL_FUNCTIONS - setTaskEnabled(TASK_GLOBAL_FUNCTIONS, true); +#ifdef USE_PROGRAMMING_FRAMEWORK + setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true); #endif #ifdef USE_IRLOCK setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected()); @@ -578,18 +574,10 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_IDLE, }, #endif -#ifdef USE_LOGIC_CONDITIONS - [TASK_LOGIC_CONDITIONS] = { - .taskName = "LOGIC", - .taskFunc = logicConditionUpdateTask, - .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec - .staticPriority = TASK_PRIORITY_IDLE, - }, -#endif -#ifdef USE_GLOBAL_FUNCTIONS - [TASK_GLOBAL_FUNCTIONS] = { - .taskName = "G_FNK", - .taskFunc = globalFunctionsUpdateTask, +#ifdef USE_PROGRAMMING_FRAMEWORK + [TASK_PROGRAMMING_FRAMEWORK] = { + .taskName = "PROGRAMMING", + .taskFunc = programmingFrameworkUpdateTask, .desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec .staticPriority = TASK_PRIORITY_IDLE, }, diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index 24aab18727..b24b78c911 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -29,7 +29,7 @@ FILE_COMPILE_FOR_SPEED #include "common/filter.h" #include "common/maths.h" #include "common/utils.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" #include "config/feature.h" #include "config/parameter_group.h" @@ -479,7 +479,7 @@ void FAST_CODE mixTable(const float dT) int16_t throttleMin, throttleMax; // Find min and max throttle based on condition. -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) { throttleRangeMin = throttleIdleValue; throttleRangeMax = motorConfig()->maxthrottle; @@ -514,7 +514,7 @@ void FAST_CODE mixTable(const float dT) throttleRangeMax = motorConfig()->maxthrottle; // Throttle scaling to limit max throttle when battery is full - #ifdef USE_GLOBAL_FUNCTIONS + #ifdef USE_PROGRAMMING_FRAMEWORK mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(motorConfig()->throttleScale)) + throttleRangeMin; #else mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * motorConfig()->throttleScale) + throttleRangeMin; diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index a9e621285e..2a48c71946 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -57,7 +57,7 @@ FILE_COMPILE_FOR_SPEED #include "sensors/acceleration.h" #include "sensors/compass.h" #include "sensors/pitotmeter.h" -#include "common/global_functions.h" +#include "programming/global_functions.h" typedef struct { float kP; // Proportional gain @@ -958,7 +958,7 @@ void FAST_CODE pidController(float dT) if (axis == FD_YAW && headingHoldState == HEADING_HOLD_ENABLED) { rateTarget = pidHeadingHold(dT); } else { -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK rateTarget = pidRcCommandToRate(getRcCommandOverride(rcCommand, axis), currentControlRateProfile->stabilized.rates[axis]); #else rateTarget = pidRcCommandToRate(rcCommand[axis], currentControlRateProfile->stabilized.rates[axis]); diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 375eacb288..dbd910e273 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -28,7 +28,7 @@ #include "common/axis.h" #include "common/filter.h" #include "common/maths.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "config/config_reset.h" #include "config/feature.h" @@ -75,7 +75,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance) .inputSource = 0, .rate = 0, .speed = 0 -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK ,.conditionId = -1 #endif ); @@ -266,7 +266,7 @@ void servoMixer(float dT) input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0; input[INPUT_MAX] = 500; -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK input[INPUT_GVAR_0] = constrain(gvGet(0), -1000, 1000); input[INPUT_GVAR_1] = constrain(gvGet(1), -1000, 1000); input[INPUT_GVAR_2] = constrain(gvGet(2), -1000, 1000); @@ -318,7 +318,7 @@ void servoMixer(float dT) /* * Check if conditions for a rule are met, not all conditions apply all the time */ - #ifdef USE_LOGIC_CONDITIONS + #ifdef USE_PROGRAMMING_FRAMEWORK if (!logicConditionGetValue(currentServoMixer[i].conditionId)) { continue; } diff --git a/src/main/flight/servos.h b/src/main/flight/servos.h index f8ca7b5112..14df882289 100644 --- a/src/main/flight/servos.h +++ b/src/main/flight/servos.h @@ -18,7 +18,7 @@ #pragma once #include "config/parameter_group.h" -#include "common/logic_condition.h" +#include "programming/logic_condition.h" #define MAX_SUPPORTED_SERVOS 16 @@ -105,7 +105,7 @@ typedef struct servoMixer_s { uint8_t inputSource; // input channel for this rule int16_t rate; // range [-1000;+1000] ; can be used to adjust a rate 0-1000% and a direction uint8_t speed; // reduces the speed of the rule, 0=unlimited speed -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK int8_t conditionId; #endif } servoMixer_t; diff --git a/src/main/common/global_functions.c b/src/main/programming/global_functions.c similarity index 98% rename from src/main/common/global_functions.c rename to src/main/programming/global_functions.c index 5e12bf9761..a9929e6623 100644 --- a/src/main/common/global_functions.c +++ b/src/main/programming/global_functions.c @@ -28,13 +28,13 @@ #include "common/utils.h" #include "common/maths.h" -#include "common/global_functions.h" -#include "common/logic_condition.h" +#include "programming/global_functions.h" +#include "programming/logic_condition.h" #include "io/vtx.h" #include "drivers/vtx_common.h" -#ifdef USE_GLOBAL_FUNCTIONS +#ifdef USE_PROGRAMMING_FRAMEWORK #include "common/axis.h" diff --git a/src/main/common/global_functions.h b/src/main/programming/global_functions.h similarity index 98% rename from src/main/common/global_functions.h rename to src/main/programming/global_functions.h index f8e0128eab..adcaec001b 100644 --- a/src/main/common/global_functions.h +++ b/src/main/programming/global_functions.h @@ -24,7 +24,7 @@ #pragma once #include "config/parameter_group.h" -#include "common/logic_condition.h" +#include "programming/logic_condition.h" #define MAX_GLOBAL_FUNCTIONS 8 diff --git a/src/main/common/global_variables.c b/src/main/programming/global_variables.c similarity index 96% rename from src/main/common/global_variables.c rename to src/main/programming/global_variables.c index 72230a97ae..df2faace76 100644 --- a/src/main/common/global_variables.c +++ b/src/main/programming/global_variables.c @@ -26,13 +26,13 @@ FILE_COMPILE_FOR_SIZE -#ifdef USE_LOGIC_CONDITIONS +#ifdef USE_PROGRAMMING_FRAMEWORK #include #include "config/config_reset.h" #include "config/parameter_group.h" #include "config/parameter_group_ids.h" -#include "common/global_variables.h" +#include "programming/global_variables.h" #include "common/maths.h" #include "build/build_config.h" diff --git a/src/main/common/global_variables.h b/src/main/programming/global_variables.h similarity index 100% rename from src/main/common/global_variables.h rename to src/main/programming/global_variables.h diff --git a/src/main/common/logic_condition.c b/src/main/programming/logic_condition.c similarity index 99% rename from src/main/common/logic_condition.c rename to src/main/programming/logic_condition.c index 7ba9dd2f1b..d42d62fa71 100644 --- a/src/main/common/logic_condition.c +++ b/src/main/programming/logic_condition.c @@ -28,11 +28,11 @@ #include "config/parameter_group.h" #include "config/parameter_group_ids.h" -#include "common/logic_condition.h" -#include "common/global_variables.h" +#include "programming/logic_condition.h" +#include "programming/global_variables.h" #include "common/utils.h" #include "rx/rx.h" -#include "maths.h" +#include "common/maths.h" #include "fc/fc_core.h" #include "fc/rc_controls.h" #include "fc/runtime_config.h" diff --git a/src/main/common/logic_condition.h b/src/main/programming/logic_condition.h similarity index 100% rename from src/main/common/logic_condition.h rename to src/main/programming/logic_condition.h diff --git a/src/main/programming/programming_task.c b/src/main/programming/programming_task.c new file mode 100644 index 0000000000..1447ffd231 --- /dev/null +++ b/src/main/programming/programming_task.c @@ -0,0 +1,35 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#include "platform.h" + +FILE_COMPILE_FOR_SIZE + +#include "programming/logic_condition.h" +#include "programming/global_functions.h" + +void programmingFrameworkUpdateTask(timeUs_t currentTimeUs) { + logicConditionUpdateTask(currentTimeUs); + globalFunctionsUpdateTask(currentTimeUs); +} \ No newline at end of file diff --git a/src/main/programming/programming_task.h b/src/main/programming/programming_task.h new file mode 100644 index 0000000000..f19e3f184b --- /dev/null +++ b/src/main/programming/programming_task.h @@ -0,0 +1,27 @@ +/* + * This file is part of INAV Project. + * + * This Source Code Form is subject to the terms of the Mozilla Public + * License, v. 2.0. If a copy of the MPL was not distributed with this file, + * You can obtain one at http://mozilla.org/MPL/2.0/. + * + * Alternatively, the contents of this file may be used under the terms + * of the GNU General Public License Version 3, as described below: + * + * This file is free software: you may copy, redistribute and/or modify + * it under the terms of the GNU General Public License as published by the + * Free Software Foundation, either version 3 of the License, or (at your + * option) any later version. + * + * This file is distributed in the hope that it will be useful, but + * WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU General + * Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see http://www.gnu.org/licenses/. + */ + +#pragma once + +void programmingFrameworkUpdateTask(timeUs_t currentTimeUs); \ No newline at end of file diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index a9d13ef5ef..99ebc68193 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -110,11 +110,8 @@ typedef enum { #ifdef USE_VTX_CONTROL TASK_VTXCTRL, #endif -#ifdef USE_LOGIC_CONDITIONS - TASK_LOGIC_CONDITIONS, -#endif -#ifdef USE_GLOBAL_FUNCTIONS - TASK_GLOBAL_FUNCTIONS, +#ifdef USE_PROGRAMMING_FRAMEWORK + TASK_PROGRAMMING_FRAMEWORK, #endif #ifdef USE_RPM_FILTER TASK_RPM_FILTER, diff --git a/src/main/target/common.h b/src/main/target/common.h index d79dad8a62..a6ff91b038 100755 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -162,8 +162,7 @@ #define USE_VTX_FFPV #ifndef STM32F3 //F3 series does not have enoug RAM to support logic conditions -#define USE_LOGIC_CONDITIONS -#define USE_GLOBAL_FUNCTIONS +#define USE_PROGRAMMING_FRAMEWORK #define USE_CLI_BATCH #endif From 206aef3197907a07ff8916c86ac2a6f36a3c5c51 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 9 Jul 2020 09:39:51 +0100 Subject: [PATCH 15/16] [DOC] add additional descriptions to settings.yaml --- src/main/fc/settings.yaml | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ce545ab777..e73844ccab 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -357,6 +357,8 @@ groups: members: - name: rangefinder_hardware table: rangefinder_hardware + description: "Selection of rangefinder hardware." + default_value: "NONE" - name: rangefinder_median_filter description: "3-point median filtering for rangefinder readouts" default_value: "OFF" @@ -369,6 +371,8 @@ groups: condition: USE_OPFLOW members: - name: opflow_hardware + description: "Selection of OPFLOW hardware." + default: "NONE" table: opflow_hardware - name: opflow_scale min: 0 @@ -475,6 +479,8 @@ groups: condition: USE_PITOT members: - name: pitot_hardware + description: "Selection of pitot hardware." + default_value: "NONE" table: pitot_hardware - name: pitot_lpf_milli_hz min: 0 @@ -488,6 +494,8 @@ groups: headers: ["rx/rx.h", "rx/spektrum.h"] members: - name: receiver_type + description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`" + default_value: "`TARGET dependent`" field: receiverType table: receiver_type - name: min_check @@ -576,6 +584,8 @@ groups: field: halfDuplex type: bool - name: msp_override_channels + description: "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." + default_value: "0" field: mspOverrideChannels condition: USE_MSP_RC_OVERRIDE min: 0 @@ -1177,6 +1187,8 @@ groups: type: generalSettings_t members: - name: applied_defaults + description: "Internal (configurator) hint. Should not be changed manually" + default_value: "0" field: appliedDefaults type: uint8_t min: 0 @@ -1827,6 +1839,8 @@ groups: field: use_gps_velned type: bool - name: inav_allow_dead_reckoning + description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation" + default_value: "OFF" field: allow_dead_reckoning type: bool - name: inav_reset_altitude @@ -2093,7 +2107,7 @@ groups: min: 1000 max: 2000 - name: nav_mc_auto_disarm_delay - description: "" + description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)" default_value: "2000" field: mc.auto_disarm_delay min: 100 @@ -2820,6 +2834,8 @@ groups: condition: USE_UNDERCLOCK type: bool - name: debug_mode + description: "Defines debug values exposed in debug variables (developer / debugging setting)" + default_value: "NONE" table: debug_modes - name: throttle_tilt_comp_str description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled." From 4673eb435e74816e9853a79b8786a81ac2f3e734 Mon Sep 17 00:00:00 2001 From: Jonathan Hudson Date: Thu, 9 Jul 2020 09:45:42 +0100 Subject: [PATCH 16/16] [DOC] add `vtx_max_power_override` description --- src/main/fc/settings.yaml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index e73844ccab..5ab9066e3d 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2949,6 +2949,8 @@ groups: min: VTX_SETTINGS_MIN_CHANNEL max: VTX_SETTINGS_MAX_CHANNEL - name: vtx_max_power_override + description: "Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities" + default_value: "0" field: maxPowerOverride min: 0 max: 10000