From eab816bf74f2d89188601aeb05516bd390867bd0 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 10 May 2021 11:25:38 +0100 Subject: [PATCH 01/67] Initial build --- docs/Settings.md | 1 + src/main/fc/settings.yaml | 8 ++++- src/main/navigation/navigation.c | 5 ++-- src/main/navigation/navigation.h | 1 + src/main/navigation/navigation_fw_launch.c | 35 ++++++++++++++++++++-- 5 files changed, 45 insertions(+), 5 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 22ad622c92..63ea9a1a07 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -306,6 +306,7 @@ | nav_fw_launch_climb_angle | 18 | 5 | 45 | Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | | nav_fw_launch_detect_time | 40 | 10 | 1000 | Time for which thresholds have to breached to consider launch happened [ms] | | nav_fw_launch_end_time | 3000 | 0 | 5000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] | +| nav_fw_launch_idle_motor_delay | 0 | 0 | 20000 | Delay between raising throttle and motor starting at idle throttle (ms) | | nav_fw_launch_idle_thr | 1000 | 1000 | 2000 | 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 | 0 | 60000 | 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 | 5 | 180 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index a7156d480d..8c1b417a72 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -77,7 +77,7 @@ tables: enum: videoSystem_e - name: osd_telemetry values: ["OFF", "ON","TEST"] - enum: osd_telemetry_e + enum: osd_telemetry_e - name: osd_alignment values: ["LEFT", "RIGHT"] enum: osd_alignment_e @@ -2670,6 +2670,12 @@ groups: field: fw.launch_idle_throttle min: 1000 max: 2000 + - name: nav_fw_launch_idle_motor_delay + description: "Delay between raising throttle and motor starting at idle throttle (ms)" + default_value: 0 + field: fw.launch_idle_motor_timer + min: 0 + max: 20000 - name: nav_fw_launch_motor_delay description: "Delay between detected launch and launch sequence start and throttling up (ms)" default_value: 500 diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index fd7e0c90d3..a258fa58cc 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -185,6 +185,7 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig, .launch_throttle = SETTING_NAV_FW_LAUNCH_THR_DEFAULT, .launch_idle_throttle = SETTING_NAV_FW_LAUNCH_IDLE_THR_DEFAULT, // Motor idle or MOTOR_STOP .launch_motor_timer = SETTING_NAV_FW_LAUNCH_MOTOR_DELAY_DEFAULT, // ms + .launch_idle_motor_timer = SETTING_NAV_FW_LAUNCH_IDLE_MOTOR_DELAY_DEFAULT, // ms .launch_motor_spinup_time = SETTING_NAV_FW_LAUNCH_SPINUP_TIME_DEFAULT, // ms, time to gredually increase throttle from idle to launch .launch_end_time = SETTING_NAV_FW_LAUNCH_END_TIME_DEFAULT, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode .launch_min_time = SETTING_NAV_FW_LAUNCH_MIN_TIME_DEFAULT, // ms, min time in launch mode @@ -2578,11 +2579,11 @@ void updateClimbRateToAltitudeController(float desiredClimbRate, climbRateToAlti } else { - /* + /* * If max altitude is set, reset climb rate if altitude is reached and climb rate is > 0 * In other words, when altitude is reached, allow it only to shrink */ - if (navConfig()->general.max_altitude > 0 && + if (navConfig()->general.max_altitude > 0 && altitudeToUse >= navConfig()->general.max_altitude && desiredClimbRate > 0 ) { diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h index 1809226452..98a88e23a7 100755 --- a/src/main/navigation/navigation.h +++ b/src/main/navigation/navigation.h @@ -263,6 +263,7 @@ typedef struct navConfig_s { uint16_t launch_idle_throttle; // Throttle to keep at launch idle uint16_t launch_throttle; // Launch throttle uint16_t launch_motor_timer; // Time to wait before setting launch_throttle (ms) + uint16_t launch_idle_motor_timer; // Time to wait before motor starts at_idle throttle (ms) uint16_t launch_motor_spinup_time; // Time to speed-up motors from idle to launch_throttle (ESC desync prevention) uint16_t launch_end_time; // Time to make the transition from launch angle to leveled and throttle transition from launch throttle to the stick position uint16_t launch_min_time; // Minimum time in launch mode to prevent possible bump of the sticks from leaving launch mode early diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 086d9a378d..9a3de29a50 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -54,6 +54,7 @@ #define LAUNCH_MOTOR_IDLE_SPINUP_TIME 1500 // ms #define UNUSED(x) ((void)(x)) #define FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE "RAISE THE THROTTLE" +#define FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE "WAITING FOR IDLE" #define FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION "READY" #define FW_LAUNCH_MESSAGE_TEXT_IN_PROGRESS "MOVE THE STICKS TO ABORT" #define FW_LAUNCH_MESSAGE_TEXT_FINISHING "FINISHING" @@ -61,6 +62,7 @@ typedef enum { FW_LAUNCH_MESSAGE_TYPE_NONE = 0, FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE, + FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE, FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION, FW_LAUNCH_MESSAGE_TYPE_IN_PROGRESS, FW_LAUNCH_MESSAGE_TYPE_FINISHING @@ -78,6 +80,7 @@ typedef enum { typedef enum { FW_LAUNCH_STATE_IDLE = 0, FW_LAUNCH_STATE_WAIT_THROTTLE, + FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, FW_LAUNCH_STATE_MOTOR_IDLE, FW_LAUNCH_STATE_WAIT_DETECTION, FW_LAUNCH_STATE_DETECTED, @@ -90,6 +93,7 @@ typedef enum { static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs_t currentTimeUs); +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_DETECTION(timeUs_t currentTimeUs); static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_DETECTED(timeUs_t currentTimeUs); @@ -125,19 +129,28 @@ static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE [FW_LAUNCH_STATE_WAIT_THROTTLE] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE, .onEvent = { - [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE, + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, [FW_LAUNCH_EVENT_GOTO_DETECTION] = FW_LAUNCH_STATE_WAIT_DETECTION }, .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE }, + [FW_LAUNCH_STATE_IDLE_MOTOR_DELAY] = { + .onEntry = fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY, + .onEvent = { + [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_MOTOR_IDLE, + [FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE + }, + .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE + }, + [FW_LAUNCH_STATE_MOTOR_IDLE] = { .onEntry = fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE, .onEvent = { [FW_LAUNCH_EVENT_SUCCESS] = FW_LAUNCH_STATE_WAIT_DETECTION, [FW_LAUNCH_EVENT_THROTTLE_LOW] = FW_LAUNCH_STATE_WAIT_THROTTLE }, - .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE + .messageType = FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE }, [FW_LAUNCH_STATE_WAIT_DETECTION] = { @@ -287,6 +300,21 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_WAIT_THROTTLE(timeUs return FW_LAUNCH_EVENT_NONE; } +static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(timeUs_t currentTimeUs) +{ + if (isThrottleLow()) { + return FW_LAUNCH_EVENT_THROTTLE_LOW; // go back to FW_LAUNCH_STATE_WAIT_THROTTLE + } + + applyThrottleIdleLogic(true); + + if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) { + return FW_LAUNCH_EVENT_SUCCESS; + } + + return FW_LAUNCH_EVENT_NONE; +} + static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_MOTOR_IDLE(timeUs_t currentTimeUs) { if (isThrottleLow()) { @@ -476,6 +504,9 @@ const char * fixedWingLaunchStateMessage(void) case FW_LAUNCH_MESSAGE_TYPE_WAIT_THROTTLE: return FW_LAUNCH_MESSAGE_TEXT_WAIT_THROTTLE; + case FW_LAUNCH_MESSAGE_TYPE_WAIT_IDLE: + return FW_LAUNCH_MESSAGE_TEXT_WAIT_IDLE; + case FW_LAUNCH_MESSAGE_TYPE_WAIT_DETECTION: return FW_LAUNCH_MESSAGE_TEXT_WAIT_DETECTION; From 4bda21005d59c859b7e8e9f22f54749007da1c17 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 10 May 2021 18:47:50 +0100 Subject: [PATCH 02/67] Add motor idle start warning beeper --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- src/main/io/beeper.c | 13 +++++++++---- src/main/io/beeper.h | 1 + src/main/navigation/navigation_fw_launch.c | 10 +++++++++- 5 files changed, 21 insertions(+), 7 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 63ea9a1a07..dee666529e 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -306,7 +306,7 @@ | nav_fw_launch_climb_angle | 18 | 5 | 45 | Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | | nav_fw_launch_detect_time | 40 | 10 | 1000 | Time for which thresholds have to breached to consider launch happened [ms] | | nav_fw_launch_end_time | 3000 | 0 | 5000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] | -| nav_fw_launch_idle_motor_delay | 0 | 0 | 20000 | Delay between raising throttle and motor starting at idle throttle (ms) | +| nav_fw_launch_idle_motor_delay | 0 | 0 | 60000 | Delay between raising throttle and motor starting at idle throttle (ms) | | nav_fw_launch_idle_thr | 1000 | 1000 | 2000 | 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 | 0 | 60000 | 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 | 5 | 180 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 8c1b417a72..00a94d99b2 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2675,7 +2675,7 @@ groups: default_value: 0 field: fw.launch_idle_motor_timer min: 0 - max: 20000 + max: 60000 - name: nav_fw_launch_motor_delay description: "Delay between detected launch and launch sequence start and throttling up (ms)" default_value: 500 diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 999cee97d2..7441ee15b9 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -132,6 +132,10 @@ static const uint8_t beep_launchModeBeep[] = { static const uint8_t beep_launchModeLowThrottleBeep[] = { 5, 5, 5, 5, 3, 100, BEEPER_COMMAND_STOP }; +// 4 short beeps and a pause. Warning motor about to start at idle throttle +static const uint8_t beep_launchModeIdleStartBeep[] = { + 5, 5, 5, 5, 5, 5, 5, 80, BEEPER_COMMAND_STOP +}; // short beeps static const uint8_t beep_hardwareFailure[] = { 10, 10, BEEPER_COMMAND_STOP @@ -196,11 +200,12 @@ typedef struct beeperTableEntry_s { { BEEPER_ENTRY(BEEPER_USB, 18, NULL, "ON_USB") }, { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_ENABLED, 19, beep_launchModeBeep, "LAUNCH_MODE") }, { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_LOW_THROTTLE, 20, beep_launchModeLowThrottleBeep, "LAUNCH_MODE_LOW_THROTTLE") }, - { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 21, beep_camOpenBeep, "CAM_CONNECTION_OPEN") }, - { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 22, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") }, + { BEEPER_ENTRY(BEEPER_LAUNCH_MODE_IDLE_START, 21, beep_launchModeIdleStartBeep, "LAUNCH_MODE_IDLE_START") }, + { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_OPEN, 22, beep_camOpenBeep, "CAM_CONNECTION_OPEN") }, + { BEEPER_ENTRY(BEEPER_CAM_CONNECTION_CLOSE, 23, beep_camCloseBeep, "CAM_CONNECTION_CLOSED") }, - { BEEPER_ENTRY(BEEPER_ALL, 23, NULL, "ALL") }, - { BEEPER_ENTRY(BEEPER_PREFERENCE, 24, NULL, "PREFERED") }, + { BEEPER_ENTRY(BEEPER_ALL, 24, NULL, "ALL") }, + { BEEPER_ENTRY(BEEPER_PREFERENCE, 25, NULL, "PREFERED") }, }; static const beeperTableEntry_t *currentBeeperEntry = NULL; diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 38f38b236e..e87abdadd5 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -44,6 +44,7 @@ typedef enum { BEEPER_USB, // Some boards have beeper powered USB connected BEEPER_LAUNCH_MODE_ENABLED, // Fixed-wing launch mode enabled BEEPER_LAUNCH_MODE_LOW_THROTTLE, // Fixed-wing launch mode enabled, but throttle is low + BEEPER_LAUNCH_MODE_IDLE_START, // Fixed-wing launch mode enabled, motor about to start at idle after set delay BEEPER_CAM_CONNECTION_OPEN, // When the 5 key simulation stated BEEPER_CAM_CONNECTION_CLOSE, // When the 5 key simulation stop diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 9a3de29a50..de86475f41 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -115,6 +115,7 @@ typedef struct fixedWingLaunchData_s { } fixedWingLaunchData_t; static EXTENDED_FASTRAM fixedWingLaunchData_t fwLaunch; +static bool idleMotorAboutToStart; static const fixedWingLaunchStateDescriptor_t launchStateMachine[FW_LAUNCH_STATE_COUNT] = { @@ -309,8 +310,11 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_IDLE_MOTOR_DELAY(tim applyThrottleIdleLogic(true); if (currentStateElapsedMs(currentTimeUs) > navConfig()->fw.launch_idle_motor_timer) { + idleMotorAboutToStart = false; return FW_LAUNCH_EVENT_SUCCESS; } + // 5 second warning motor about to start at idle, changes Beeper sound + idleMotorAboutToStart = navConfig()->fw.launch_idle_motor_timer - currentStateElapsedMs(currentTimeUs) < 5000; return FW_LAUNCH_EVENT_NONE; } @@ -469,7 +473,11 @@ void applyFixedWingLaunchController(timeUs_t currentTimeUs) beeper(BEEPER_LAUNCH_MODE_LOW_THROTTLE); } else { - beeper(BEEPER_LAUNCH_MODE_ENABLED); + if (idleMotorAboutToStart) { + beeper(BEEPER_LAUNCH_MODE_IDLE_START); + } else { + beeper(BEEPER_LAUNCH_MODE_ENABLED); + } } } From 161ad10b5a0fac4a8cd9e1b1fe83c7d216948fab Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 14 May 2021 16:38:06 +0200 Subject: [PATCH 03/67] rssi alarm (cherry picked from commit ac60206909a91e6094439f8a89aefd2126c51562) --- src/main/fc/settings.yaml | 7 +++++++ src/main/io/osd.c | 5 ++++- src/main/io/osd.h | 1 + 3 files changed, 12 insertions(+), 1 deletion(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index ac33a15f3d..bac68a39b1 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3109,6 +3109,13 @@ groups: field: link_quality_alarm min: 0 max: 100 + - name: osd_rssi_dbm_alarm + condition: USE_SERIALRX_CRSF + description: "RSSI-dBm indicator blinks below this value [dBm]. 0 disables this alarm" + default_value: -100 + field: rssi_dbm_alarm + min: -130 + max: 0 - name: osd_temp_label_align description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" default_value: "LEFT" diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8da246f8c1..2e326435f3 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -194,7 +194,7 @@ static bool osdDisplayHasCanvas; #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 3); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0); static int digitCount(int32_t value) @@ -1858,6 +1858,8 @@ static bool osdDrawSingleElement(uint8_t item) } if (!failsafeIsReceivingRxData()){ TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); + } else if (osdConfig()->rssi_dbm_alarm && rssi < osdConfig()->rssi_dbm_alarm) { + TEXT_ATTRIBUTES_ADD_BLINK(elemAttr); } break; } @@ -2881,6 +2883,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, + .rssi_dbm_alarm = SETTING_OSD_RSSI_DMB_ALARM_DEFAULT, #endif #ifdef USE_TEMPERATURE_SENSOR .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 1dcf384065..053f418c04 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -312,6 +312,7 @@ typedef struct osdConfig_s { #ifdef USE_SERIALRX_CRSF int8_t snr_alarm; //CRSF SNR alarm in dB int8_t link_quality_alarm; + int8_t rssi_dbm_alarm; // in dBm #endif #ifdef USE_BARO int16_t baro_temp_alarm_min; From e5be38e1f398ced9b7b305714136adf9dad289ed Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 14 May 2021 16:43:29 +0200 Subject: [PATCH 04/67] build error --- src/main/fc/settings.yaml | 4 ++-- src/main/io/osd.c | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index bac68a39b1..9e825a909e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3111,8 +3111,8 @@ groups: max: 100 - name: osd_rssi_dbm_alarm condition: USE_SERIALRX_CRSF - description: "RSSI-dBm indicator blinks below this value [dBm]. 0 disables this alarm" - default_value: -100 + description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm" + default_value: 0 field: rssi_dbm_alarm min: -130 max: 0 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 2e326435f3..888a7e035a 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2883,7 +2883,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .snr_alarm = SETTING_OSD_SNR_ALARM_DEFAULT, .crsf_lq_format = SETTING_OSD_CRSF_LQ_FORMAT_DEFAULT, .link_quality_alarm = SETTING_OSD_LINK_QUALITY_ALARM_DEFAULT, - .rssi_dbm_alarm = SETTING_OSD_RSSI_DMB_ALARM_DEFAULT, + .rssi_dbm_alarm = SETTING_OSD_RSSI_DBM_ALARM_DEFAULT, #endif #ifdef USE_TEMPERATURE_SENSOR .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT, From 2b3c256e7bdb52e77b872463f72acff82f7c7f23 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 14 May 2021 22:17:31 +0200 Subject: [PATCH 05/67] docs --- docs/Settings.md | 1 + 1 file changed, 1 insertion(+) diff --git a/docs/Settings.md b/docs/Settings.md index 7d3be48764..9d1950a79c 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -438,6 +438,7 @@ | osd_right_sidebar_scroll_step | 0 | | 255 | Same as left_sidebar_scroll_step, but for the right sidebar | | osd_row_shiftdown | 0 | 0 | 1 | Number of rows to shift the OSD display (increase if top rows are cut off) | | osd_rssi_alarm | 20 | 0 | 100 | Value below which to make the OSD RSSI indicator blink | +| osd_rssi_dbm_alarm | 0 | -130 | 0 | RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm | | osd_sidebar_height | 3 | 0 | 5 | Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) | | osd_sidebar_horizontal_offset | 0 | -128 | 127 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | | osd_sidebar_scroll_arrows | OFF | | | | From 016dc2883b817f3125ab90ae6f70a43645828269 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Fri, 14 May 2021 22:20:01 +0200 Subject: [PATCH 06/67] int8 range --- 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 9e825a909e..c36b9155e7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3114,7 +3114,7 @@ groups: description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm" default_value: 0 field: rssi_dbm_alarm - min: -130 + min: -128 max: 0 - name: osd_temp_label_align description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" From 1a8e9319e79c8df04420c3829ad1a430642ac66b Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 15 May 2021 08:52:53 +0200 Subject: [PATCH 07/67] int16 --- src/main/fc/settings.yaml | 2 +- src/main/io/osd.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index c36b9155e7..9e825a909e 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3114,7 +3114,7 @@ groups: description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm" default_value: 0 field: rssi_dbm_alarm - min: -128 + min: -130 max: 0 - name: osd_temp_label_align description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`" diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 053f418c04..26f862e51c 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -312,7 +312,7 @@ typedef struct osdConfig_s { #ifdef USE_SERIALRX_CRSF int8_t snr_alarm; //CRSF SNR alarm in dB int8_t link_quality_alarm; - int8_t rssi_dbm_alarm; // in dBm + int16_t rssi_dbm_alarm; // in dBm #endif #ifdef USE_BARO int16_t baro_temp_alarm_min; From 6c18158dca43e2bda62ec1b9e6622eeca7668dbe Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sat, 15 May 2021 09:19:56 +0200 Subject: [PATCH 08/67] Increase the max range of gyro antialiasing filter to 1000Hz --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- src/main/sensors/gyro.c | 2 +- src/main/sensors/gyro.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 1fe695deca..f5c380fb54 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -152,7 +152,7 @@ | gyro_abg_alpha | 0 | 0 | 1 | Alpha factor for Gyro Alpha-Beta-Gamma filter | | gyro_abg_boost | 0.35 | 0 | 2 | Boost factor for Gyro Alpha-Beta-Gamma filter | | gyro_abg_half_life | 0.5 | 0 | 10 | Sample half-life for Gyro Alpha-Beta-Gamma filter | -| gyro_anti_aliasing_lpf_hz | 250 | | 255 | Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz | +| gyro_anti_aliasing_lpf_hz | 250 | | 1000 | Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz | | gyro_anti_aliasing_lpf_type | PT1 | | | Specifies the type of the software LPF of the gyro signals. | | gyro_dyn_lpf_curve_expo | 5 | 1 | 10 | Expo value for the throttle-to-frequency mapping for Dynamic LPF | | gyro_dyn_lpf_max_hz | 500 | 40 | 1000 | Maximum frequency of the gyro Dynamic LPF | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 26cc4d446f..b4d469da61 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -214,7 +214,7 @@ groups: description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz" default_value: 250 field: gyro_anti_aliasing_lpf_hz - max: 255 + max: 1000 - name: gyro_anti_aliasing_lpf_type description: "Specifies the type of the software LPF of the gyro signals." default_value: "PT1" diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index e3ec90d5d4..f7d1a3ad18 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -111,7 +111,7 @@ STATIC_FASTRAM alphaBetaGammaFilter_t abgFilter[XYZ_AXIS_COUNT]; #endif -PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 13); +PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 14); PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig, .gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT, diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index e018e1a79a..f00d828f32 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -63,7 +63,7 @@ typedef struct gyroConfig_s { uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. uint16_t looptime; // imu loop time in us uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. - uint8_t gyro_anti_aliasing_lpf_hz; + uint16_t gyro_anti_aliasing_lpf_hz; uint8_t gyro_anti_aliasing_lpf_type; #ifdef USE_DUAL_GYRO uint8_t gyro_to_use; From 01ac93a164318094932d25e2ad0fd7f6485f18cf Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 19 May 2021 15:24:20 +0200 Subject: [PATCH 09/67] disable autotrim osd message --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 888a7e035a..6e4060ac54 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -3867,7 +3867,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter // by OSD_FLYMODE. messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_ALTITUDE_HOLD); } - if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM)) { + if (IS_RC_MODE_ACTIVE(BOXAUTOTRIM) && !feature(FEATURE_FW_AUTOTRIM)) { messages[messageCount++] = OSD_MESSAGE_STR(OSD_MSG_AUTOTRIM); } if (IS_RC_MODE_ACTIVE(BOXAUTOTUNE)) { From 981bb268fdd4fc2264f479d41829bae3edee85bc Mon Sep 17 00:00:00 2001 From: OptimusTi Date: Wed, 19 May 2021 21:42:32 -0400 Subject: [PATCH 10/67] Shift one char left Shift CRSF Link Elements one character to the left to avoid. Items may get cut from some DVRs when close to the edges. --- src/main/io/osd.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6e4060ac54..100fe7acd2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2991,10 +2991,10 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); #ifdef USE_SERIALRX_CRSF - osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(24, 12); - osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(24, 11); - osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(25, 9); - osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(25, 10); + osdLayoutsConfig->item_pos[0][OSD_CRSF_RSSI_DBM] = OSD_POS(23, 12); + osdLayoutsConfig->item_pos[0][OSD_CRSF_LQ] = OSD_POS(23, 11); + osdLayoutsConfig->item_pos[0][OSD_CRSF_SNR_DB] = OSD_POS(24, 9); + osdLayoutsConfig->item_pos[0][OSD_CRSF_TX_POWER] = OSD_POS(24, 10); #endif osdLayoutsConfig->item_pos[0][OSD_ONTIME] = OSD_POS(23, 8); From ec7f51b9ccade61c1de2fb9d4273bcc3ff145f4a Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Fri, 21 May 2021 09:40:15 +0200 Subject: [PATCH 11/67] By default, do not display sidebards and AHI --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6e4060ac54..88d77fdb02 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2984,8 +2984,8 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) // OSD_VARIO_NUM at the right of OSD_VARIO osdLayoutsConfig->item_pos[0][OSD_VARIO_NUM] = OSD_POS(24, 7); osdLayoutsConfig->item_pos[0][OSD_HOME_DIR] = OSD_POS(14, 11); - osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; - osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6) | OSD_VISIBLE_FLAG; + osdLayoutsConfig->item_pos[0][OSD_ARTIFICIAL_HORIZON] = OSD_POS(8, 6); + osdLayoutsConfig->item_pos[0][OSD_HORIZON_SIDEBARS] = OSD_POS(8, 6); osdLayoutsConfig->item_pos[0][OSD_CRAFT_NAME] = OSD_POS(20, 2); osdLayoutsConfig->item_pos[0][OSD_VTX_CHANNEL] = OSD_POS(8, 6); From 072d5ba76138b4fdbdeb9719599cc41b935e97b6 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Sat, 22 May 2021 16:47:42 +0200 Subject: [PATCH 12/67] Fix integer regex deprecation warnings (#7009) --- src/utils/settings.rb | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/utils/settings.rb b/src/utils/settings.rb index 877e325fcd..e0b7a75898 100755 --- a/src/utils/settings.rb +++ b/src/utils/settings.rb @@ -907,8 +907,8 @@ class Generator unsigned = !$~[:unsigned].empty? bitsize = $~[:bitsize].to_i type_range = unsigned ? 0..(2**bitsize-1) : (-2**(bitsize-1)+1)..(2**(bitsize-1)-1) - min = type_range.min if min =~ /\AU?INT\d+_MIN\Z/ - max = type_range.max if max =~ /\AU?INT\d+_MAX\Z/ + min = type_range.min if min.to_s =~ /\AU?INT\d+_MIN\Z/ + max = type_range.max if max.to_s =~ /\AU?INT\d+_MAX\Z/ raise "Member #{name} default value has an invalid type, integer or symbol expected" unless default_value.is_a? Integer or default_value.is_a? Symbol raise "Member #{name} default value is outside type's storage range, min #{type_range.min}, max #{type_range.max}" unless default_value.is_a? Symbol or type_range === default_value raise "Numeric member #{name} doesn't have maximum value defined" unless member.has_key? 'max' From 6fb25e37ff3891afe004fd06dcf6ac92dde711d3 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 22 May 2021 21:54:43 +0200 Subject: [PATCH 13/67] compensate ahi for pitch trim angle --- src/main/io/osd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6e4060ac54..40fceeb297 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2031,6 +2031,7 @@ static bool osdDrawSingleElement(uint8_t item) pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); #endif pitchAngle -= DEGREES_TO_RADIANS(osdConfig()->camera_uptilt); + pitchAngle += DEGREES_TO_RADIANS(pidProfile()->fixedWingLevelTrim); if (osdConfig()->ahi_reverse_roll) { rollAngle = -rollAngle; } From bdd4e1315f68109a5cda708ca61a37071a2aee67 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 22 May 2021 22:03:19 +0200 Subject: [PATCH 14/67] fix snr osd width --- src/main/io/osd.c | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6e4060ac54..0513cfa8dc 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1894,15 +1894,13 @@ static bool osdDrawSingleElement(uint8_t item) int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); snrUpdated = millis(); - const char* showsnr = "-20"; - const char* hidesnr = " "; if (snrFiltered > osdConfig()->snr_alarm) { if (cmsInMenu) { buff[0] = SYM_SNR; - tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); + tfp_sprintf(buff + 1, "%s%c", '-20', SYM_DB); } else { buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); + tfp_sprintf(buff + 1, "%s%c", ' ', SYM_BLANK); } } else if (snrFiltered <= osdConfig()->snr_alarm) { buff[0] = SYM_SNR; From b2dd7eec6d1fb422f7a5269719c1a417bb1dff19 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 22 May 2021 22:36:39 +0200 Subject: [PATCH 15/67] build error --- src/main/io/osd.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0513cfa8dc..2eac7afb95 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1894,13 +1894,15 @@ static bool osdDrawSingleElement(uint8_t item) int8_t snrFiltered = pt1FilterApply4(&snrFilterState, rxLinkStatistics.uplinkSNR, 0.5f, MS2S(millis() - snrUpdated)); snrUpdated = millis(); + const char* showsnr = "-20"; + const char* hidesnr = " "; if (snrFiltered > osdConfig()->snr_alarm) { if (cmsInMenu) { buff[0] = SYM_SNR; - tfp_sprintf(buff + 1, "%s%c", '-20', SYM_DB); + tfp_sprintf(buff + 1, "%s%c", showsnr, SYM_DB); } else { buff[0] = SYM_BLANK; - tfp_sprintf(buff + 1, "%s%c", ' ', SYM_BLANK); + tfp_sprintf(buff + 1, "%s%c", hidesnr, SYM_BLANK); } } else if (snrFiltered <= osdConfig()->snr_alarm) { buff[0] = SYM_SNR; From 527886e877ce9707b95d74ee93c77b88d7f0e661 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sun, 23 May 2021 15:15:23 +0200 Subject: [PATCH 16/67] fix minor bug where fixedWingLevelTrim is applied 1.1 times --- src/main/flight/pid.c | 16 +--------------- 1 file changed, 1 insertion(+), 15 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 6f6222d901..f2cd49deb1 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -616,21 +616,6 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h DEBUG_SET(DEBUG_AUTOLEVEL, 1, fixedWingLevelTrim * 10); DEBUG_SET(DEBUG_AUTOLEVEL, 2, getEstimatedActualVelocity(Z)); - /* - * fixedWingLevelTrim has opposite sign to rcCommand. - * Positive rcCommand means nose should point downwards - * Negative rcCommand mean nose should point upwards - * This is counter intuitive and a natural way suggests that + should mean UP - * This is why fixedWingLevelTrim has opposite sign to rcCommand - * Positive fixedWingLevelTrim means nose should point upwards - * Negative fixedWingLevelTrim means nose should point downwards - */ - angleTarget -= fixedWingLevelTrim; - DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10); - } - - //PITCH trim applied by a AutoLevel flight mode and manual pitch trimming - if (axis == FD_PITCH && STATE(AIRPLANE)) { /* * fixedWingLevelTrim has opposite sign to rcCommand. * Positive rcCommand means nose should point downwards @@ -641,6 +626,7 @@ static void pidLevel(pidState_t *pidState, flight_dynamics_index_t axis, float h * Negative fixedWingLevelTrim means nose should point downwards */ angleTarget -= DEGREES_TO_DECIDEGREES(fixedWingLevelTrim); + DEBUG_SET(DEBUG_AUTOLEVEL, 3, angleTarget * 10); } #ifdef USE_SECONDARY_IMU From cee8b2cc83e3c412ee78d75059349ad89cafbde7 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sun, 23 May 2021 16:11:34 +0200 Subject: [PATCH 17/67] add setting to disable ahi camera uptilt compensation. --- docs/Settings.md | 3 ++- src/main/fc/settings.yaml | 7 ++++++- src/main/io/osd.c | 5 +++-- src/main/io/osd.h | 1 + 4 files changed, 12 insertions(+), 4 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c2f51dcb23..472dd45a65 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -391,6 +391,7 @@ | opflow_hardware | NONE | | | Selection of OPFLOW hardware. | | opflow_scale | 10.5 | 0 | 10000 | | | osd_ahi_bordered | OFF | | | Shows a border/corners around the AHI region (pixel OSD only) | +| osd_ahi_camera_uptilt_comp | ON | | | When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. | | osd_ahi_height | 162 | | 255 | AHI height in pixels (pixel OSD only) | | osd_ahi_max_pitch | 20 | 10 | 90 | Max pitch, in degrees, for OSD artificial horizon | | osd_ahi_reverse_roll | OFF | | | | @@ -402,7 +403,7 @@ | osd_baro_temp_alarm_min | -200 | -550 | 1250 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | | osd_camera_fov_h | 135 | 60 | 150 | Horizontal field of view for the camera in degres | | osd_camera_fov_v | 85 | 30 | 120 | Vertical field of view for the camera in degres | -| osd_camera_uptilt | 0 | -40 | 80 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal | +| osd_camera_uptilt | 0 | -40 | 80 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled). | | osd_coordinate_digits | 9 | 8 | 11 | | | osd_crosshairs_style | DEFAULT | | | To set the visual type for the crosshair | | osd_crsf_lq_format | TYPE1 | | | To select LQ format | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 435398b1fd..efc324b1c7 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3177,11 +3177,16 @@ groups: 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" + description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled)." default_value: 0 field: camera_uptilt min: -40 max: 80 + - name: osd_ahi_camera_uptilt_comp + description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees." + default_value: ON + field: ahi_camera_uptilt_comp + type: bool - name: osd_camera_fov_h description: "Horizontal field of view for the camera in degres" default_value: 135 diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 6e4060ac54..06f45f8747 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -194,7 +194,7 @@ static bool osdDisplayHasCanvas; #define AH_MAX_PITCH_DEFAULT 20 // Specify default maximum AHI pitch value displayed (degrees) -PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(osdConfig_t, osdConfig, PG_OSD_CONFIG, 4); PG_REGISTER_WITH_RESET_FN(osdLayoutsConfig_t, osdLayoutsConfig, PG_OSD_LAYOUTS_CONFIG, 0); static int digitCount(int32_t value) @@ -2030,7 +2030,7 @@ static bool osdDrawSingleElement(uint8_t item) rollAngle = DECIDEGREES_TO_RADIANS(attitude.values.roll); pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); #endif - pitchAngle -= DEGREES_TO_RADIANS(osdConfig()->camera_uptilt); + pitchAngle -= osdConfig()->ahi_camera_uptilt_comp ? DEGREES_TO_RADIANS(osdConfig()->camera_uptilt) : 0; if (osdConfig()->ahi_reverse_roll) { rollAngle = -rollAngle; } @@ -2897,6 +2897,7 @@ PG_RESET_TEMPLATE(osdConfig_t, osdConfig, .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT, .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT, .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_DEFAULT, + .ahi_camera_uptilt_comp = SETTING_OSD_AHI_CAMERA_UPTILT_COMP_DEFAULT, .camera_fov_h = SETTING_OSD_CAMERA_FOV_H_DEFAULT, .camera_fov_v = SETTING_OSD_CAMERA_FOV_V_DEFAULT, .hud_margin_h = SETTING_OSD_HUD_MARGIN_H_DEFAULT, diff --git a/src/main/io/osd.h b/src/main/io/osd.h index ed549e2735..38557f0cb5 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -332,6 +332,7 @@ typedef struct osdConfig_s { uint8_t crosshairs_style; // from osd_crosshairs_style_e int8_t horizon_offset; int8_t camera_uptilt; + bool ahi_camera_uptilt_comp; uint8_t camera_fov_h; uint8_t camera_fov_v; uint8_t hud_margin_h; From 25658677f967630c31b2286a28e1c85e4f737c4f Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sun, 23 May 2021 16:12:40 +0200 Subject: [PATCH 18/67] default to off --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 472dd45a65..bcceae0084 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -391,7 +391,7 @@ | opflow_hardware | NONE | | | Selection of OPFLOW hardware. | | opflow_scale | 10.5 | 0 | 10000 | | | osd_ahi_bordered | OFF | | | Shows a border/corners around the AHI region (pixel OSD only) | -| osd_ahi_camera_uptilt_comp | ON | | | When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. | +| osd_ahi_camera_uptilt_comp | OFF | | | When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. | | osd_ahi_height | 162 | | 255 | AHI height in pixels (pixel OSD only) | | osd_ahi_max_pitch | 20 | 10 | 90 | Max pitch, in degrees, for OSD artificial horizon | | osd_ahi_reverse_roll | OFF | | | | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index efc324b1c7..16d5f9dcdb 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3184,7 +3184,7 @@ groups: max: 80 - name: osd_ahi_camera_uptilt_comp description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees." - default_value: ON + default_value: OFF field: ahi_camera_uptilt_comp type: bool - name: osd_camera_fov_h From a3bdf67b4a32486cb3f1c8b890253fef6be2d2ac Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sun, 23 May 2021 19:46:28 +0200 Subject: [PATCH 19/67] use current (autolevel-adjusted) fixedWingLevelTrim instead of saved value --- src/main/flight/pid.c | 5 +++++ src/main/flight/pid.h | 1 + src/main/io/osd.c | 2 +- 3 files changed, 7 insertions(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index f2cd49deb1..169d36e5a4 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1341,3 +1341,8 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs) previousArmingState = !!ARMING_FLAG(ARMED); } + +float getFixedWingLevelTrim(void) +{ + return STATE(AIRPLANE) ? fixedWingLevelTrim : 0; +} diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 0d4719acb8..734007b481 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -233,3 +233,4 @@ void autotuneFixedWingUpdate(const flight_dynamics_index_t axis, float desiredRa pidType_e pidIndexGetType(pidIndex_e pidIndex); void updateFixedWingLevelTrim(timeUs_t currentTimeUs); +float getFixedWingLevelTrim(void); diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 40fceeb297..7bcc7e14c7 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2031,7 +2031,7 @@ static bool osdDrawSingleElement(uint8_t item) pitchAngle = DECIDEGREES_TO_RADIANS(attitude.values.pitch); #endif pitchAngle -= DEGREES_TO_RADIANS(osdConfig()->camera_uptilt); - pitchAngle += DEGREES_TO_RADIANS(pidProfile()->fixedWingLevelTrim); + pitchAngle += DEGREES_TO_RADIANS(getFixedWingLevelTrim()); if (osdConfig()->ahi_reverse_roll) { rollAngle = -rollAngle; } From db3300bd85af2d0a541d4fc7427dd893a0ec672d Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Mon, 24 May 2021 16:08:31 +0200 Subject: [PATCH 20/67] Fix bug that D-term was not active on fw --- src/main/flight/pid.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 6f6222d901..1d682623ec 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -795,7 +795,7 @@ static void NOINLINE pidApplyFixedWingRateController(pidState_t *pidState, fligh pidState->errorGyroIf = constrainf(pidState->errorGyroIf, -pidProfile()->fixedWingItermThrowLimit, pidProfile()->fixedWingItermThrowLimit); } - axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf, -pidState->pidSumLimit, +pidState->pidSumLimit); + axisPID[axis] = constrainf(newPTerm + newFFTerm + pidState->errorGyroIf + newDTerm, -pidState->pidSumLimit, +pidState->pidSumLimit); #ifdef USE_AUTOTUNE_FIXED_WING if (FLIGHT_MODE(AUTO_TUNE) && !FLIGHT_MODE(MANUAL_MODE)) { From 660facb91c5fd95a92295e16255aab844949d109 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Tue, 25 May 2021 00:06:14 +0200 Subject: [PATCH 21/67] Convert settings docs to a list --- docs/Settings.md | 6186 ++++++++++++++++++++++++++++++---- src/utils/update_cli_docs.py | 37 +- 2 files changed, 5639 insertions(+), 584 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index c2f51dcb23..8fec921ec7 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1,568 +1,5624 @@ # CLI Variable Reference -| Variable Name | Default Value | Min | Max | Description | -| ------------- | ------------- | --- | --- | ----------- | -| 3d_deadband_high | 1514 | PWM_RANGE_MIN | PWM_RANGE_MAX | 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 | PWM_RANGE_MIN | PWM_RANGE_MAX | 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 | 0 | 200 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. | -| 3d_neutral | 1460 | PWM_RANGE_MIN | PWM_RANGE_MAX | Neutral (stop) throttle value for 3D mode | -| acc_event_threshold_high | 0 | 0 | 65535 | 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 | 0 | 900 | 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 | 0 | 65535 | 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 | 0 | 200 | 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. | -| acc_notch_cutoff | 1 | 1 | 255 | | -| acc_notch_hz | 0 | 0 | 255 | | -| accgain_x | 4096 | 1 | 8192 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_y | 4096 | 1 | 8192 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| accgain_z | 4096 | 1 | 8192 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. | -| acczero_x | 0 | -32768 | 32767 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_y | 0 | -32768 | 32767 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| acczero_z | 0 | -32768 | 32767 | Calculated value after '6 position avanced calibration'. See Wiki page. | -| airmode_throttle_threshold | 1300 | 1000 | 2000 | Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used | -| airmode_type | STICK_CENTER | | | Defines the Airmode state handling type. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `airmode_throttle_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER_ONCE** or **STICK_CENTER** modes. | -| airspeed_adc_channel | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | 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 | -1800 | 3600 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_roll | 0 | -1800 | 3600 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc | -| align_board_yaw | 0 | -1800 | 3600 | 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 | -1800 | 3600 | Same as align_mag_roll, but for the pitch axis. | -| align_mag_roll | 0 | -1800 | 3600 | 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 | -1800 | 3600 | Same as align_mag_roll, but for the yaw axis. | -| align_opflow | CW0FLIP | | | Optical flow module alignment (default CW0_DEG_FLIP) | -| alt_hold_deadband | 50 | 10 | 250 | Defines the deadband of throttle during alt_hold [r/c points] | -| antigravity_accelerator | 1 | 1 | 20 | | -| antigravity_cutoff_lpf_hz | 15 | 1 | 30 | 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 | 1 | 20 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements | -| applied_defaults | 0 | 0 | 3 | Internal (configurator) hint. Should not be changed manually | -| baro_cal_tolerance | 150 | 0 | 1000 | 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 | 0 | 12 | Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected. | -| 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 | 0 | 4294967295 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. | -| battery_capacity_critical | 0 | 0 | 4294967295 | 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 | 0 | 4294967295 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. | -| blackbox_device | _target default_ | | | Selection of where to write blackbox data | -| blackbox_rate_denom | 1 | 1 | 65535 | Blackbox logging rate denominator. See blackbox_rate_num. | -| blackbox_rate_num | 1 | 1 | 65535 | 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 | 0 | 4294967295 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit | -| current_adc_channel | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled | -| current_meter_offset | _target default_ | -32768 | 32767 | This sets the output offset voltage of the current sensor in millivolts. | -| current_meter_scale | _target default_ | -10000 | 10000 | 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. | -| d_boost_factor | 1.25 | 1 | 3 | | -| d_boost_gyro_delta_lpf_hz | 80 | 10 | 250 | | -| d_boost_max_at_acceleration | 7500 | 1000 | 16000 | | -| deadband | 5 | 0 | 32 | 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. | -| debug_mode | NONE | | | Defines debug values exposed in debug variables (developer / debugging setting) | -| 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 | -| dji_esc_temp_source | ESC | | | Re-purpose the ESC temperature field for IMU/BARO temperature | -| dji_use_name_for_messages | ON | | | Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance | -| dji_workarounds | 1 | 0 | 255 | Enables workarounds for different versions of MSP protocol used | -| dshot_beeper_enabled | ON | | | Whether using DShot motors as beepers is enabled | -| dshot_beeper_tone | 1 | 1 | 5 | Sets the DShot beeper tone | -| dterm_lpf2_hz | 0 | 0 | 500 | 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 | 0 | 500 | 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 | 30 | 1000 | 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 | 1 | 1000 | 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 | -| eleres_freq | 435 | 415 | 450 | | -| eleres_loc_delay | 240 | 30 | 1800 | | -| eleres_loc_en | OFF | | | | -| eleres_loc_power | 7 | 0 | 7 | | -| eleres_signature | 0 | | 4294967295 | | -| eleres_telemetry_en | OFF | | | | -| eleres_telemetry_power | 7 | 0 | 7 | | -| esc_sensor_listen_only | OFF | | | Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case | -| failsafe_delay | 5 | 0 | 200 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). | -| failsafe_fw_pitch_angle | 100 | -800 | 800 | 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 | -800 | 800 | 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 | -1000 | 1000 | 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 | 20 | 65535 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. | -| failsafe_lights_flash_period | 1000 | 40 | 65535 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. | -| failsafe_min_distance | 0 | 0 | 65000 | 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 | 0 | 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 | 0 | 200 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). | -| failsafe_stick_threshold | 50 | 0 | 500 | 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 | PWM_RANGE_MIN | PWM_RANGE_MAX | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). | -| failsafe_throttle_low_delay | 0 | 0 | 300 | 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 | FLAPERON_THROW_MIN | FLAPERON_THROW_MAX | 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. | -| fpv_mix_degrees | 0 | 0 | 50 | | -| frsky_coordinates_format | 0 | 0 | FRSKY_FORMAT_NMEA | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA | -| frsky_default_latitude | 0 | -90 | 90 | 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 | -180 | 180 | 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 | FRSKY_VFAS_PRECISION_LOW | FRSKY_VFAS_PRECISION_HIGH | 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 | 100 | 5000 | 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 | 0 | 100 | FF to P gain (strength relationship) [%] | -| fw_autotune_max_rate_deflection | 80 | 50 | 100 | The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`. | -| fw_autotune_min_stick | 50 | 0 | 100 | Minimum stick input [%] to consider overshoot/undershoot detection | -| fw_autotune_p_to_d_gain | 0 | 0 | 200 | P to D gain (strength relationship) [%] | -| fw_autotune_rate_adjustment | AUTO | | | `AUTO` and `LIMIT` adjust the rates to match the capabilities of the airplane, with `LIMIT` they are never increased above the starting rates setting. `FIXED` does not adjust the rates. Rates are not changed when tuning in `ANGLE` mode. | -| fw_d_level | 75 | 0 | 200 | Fixed-wing attitude stabilisation HORIZON transition point | -| fw_d_pitch | 0 | 0 | 200 | Fixed wing rate stabilisation D-gain for PITCH | -| fw_d_roll | 0 | 0 | 200 | Fixed wing rate stabilisation D-gain for ROLL | -| fw_d_yaw | 0 | 0 | 200 | Fixed wing rate stabilisation D-gain for YAW | -| fw_ff_pitch | 50 | 0 | 200 | Fixed-wing rate stabilisation FF-gain for PITCH | -| fw_ff_roll | 50 | 0 | 200 | Fixed-wing rate stabilisation FF-gain for ROLL | -| fw_ff_yaw | 60 | 0 | 200 | Fixed-wing rate stabilisation FF-gain for YAW | -| fw_i_level | 5 | 0 | 200 | Fixed-wing attitude stabilisation low-pass filter cutoff | -| fw_i_pitch | 7 | 0 | 200 | Fixed-wing rate stabilisation I-gain for PITCH | -| fw_i_roll | 7 | 0 | 200 | Fixed-wing rate stabilisation I-gain for ROLL | -| fw_i_yaw | 10 | 0 | 200 | Fixed-wing rate stabilisation I-gain for YAW | -| fw_iterm_limit_stick_position | 0.5 | 0 | 1 | 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 | FW_ITERM_THROW_LIMIT_MIN | FW_ITERM_THROW_LIMIT_MAX | 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_level_pitch_deadband | 5 | 0 | 20 | Deadband for automatic leveling when AUTOLEVEL mode is used. | -| fw_level_pitch_gain | 5 | 0 | 20 | I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations | -| fw_level_pitch_trim | 0 | -10 | 10 | Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level | -| 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 | 0 | 450 | 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 | 0 | 200 | Fixed-wing attitude stabilisation P-gain | -| fw_p_pitch | 5 | 0 | 200 | Fixed-wing rate stabilisation P-gain for PITCH | -| fw_p_roll | 5 | 0 | 200 | Fixed-wing rate stabilisation P-gain for ROLL | -| fw_p_yaw | 6 | 0 | 200 | Fixed-wing rate stabilisation P-gain for YAW | -| fw_reference_airspeed | 1500 | 300 | 6000 | 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 | 0 | 5000 | 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_pitch_gain | 1 | 0 | 2 | Gain required to keep constant pitch angle during coordinated turns (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter | -| fw_turn_assist_yaw_gain | 1 | 0 | 2 | 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_yaw_iterm_freeze_bank_angle | 0 | 0 | 90 | Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled. | -| 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 | 5 | 10 | 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_abg_alpha | 0 | 0 | 1 | Alpha factor for Gyro Alpha-Beta-Gamma filter | -| gyro_abg_boost | 0.35 | 0 | 2 | Boost factor for Gyro Alpha-Beta-Gamma filter | -| gyro_abg_half_life | 0.5 | 0 | 10 | Sample half-life for Gyro Alpha-Beta-Gamma filter | -| gyro_anti_aliasing_lpf_hz | 250 | | 1000 | Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz | -| gyro_anti_aliasing_lpf_type | PT1 | | | Specifies the type of the software LPF of the gyro signals. | -| gyro_dyn_lpf_curve_expo | 5 | 1 | 10 | Expo value for the throttle-to-frequency mapping for Dynamic LPF | -| gyro_dyn_lpf_max_hz | 500 | 40 | 1000 | Maximum frequency of the gyro Dynamic LPF | -| gyro_dyn_lpf_min_hz | 200 | 40 | 400 | Minimum frequency of the gyro Dynamic LPF | -| gyro_hardware_lpf | 256HZ | | | Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. | -| gyro_main_lpf_hz | 60 | 0 | 500 | Software based gyro main lowpass filter. Value is cutoff frequency (Hz) | -| gyro_main_lpf_type | BIQUAD | | | Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. | -| gyro_notch_cutoff | 1 | 1 | 500 | | -| gyro_notch_hz | 0 | | 500 | | -| gyro_to_use | 0 | 0 | 1 | | -| gyro_use_dyn_lpf | OFF | | | Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position. | -| 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 | HEADING_HOLD_RATE_LIMIT_MIN | HEADING_HOLD_RATE_LIMIT_MAX | 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 | 0 | 120 | 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 | 0 | 255 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. | -| idle_power | 0 | 0 | 65535 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit | -| imu2_align_pitch | 0 | -1800 | 3600 | Pitch alignment for Secondary IMU. 1/10 of a degree | -| imu2_align_roll | 0 | -1800 | 3600 | Roll alignment for Secondary IMU. 1/10 of a degree | -| imu2_align_yaw | 0 | -1800 | 3600 | Yaw alignment for Secondary IMU. 1/10 of a degree | -| imu2_gain_acc_x | 0 | -32768 | 32767 | Secondary IMU ACC calibration data | -| imu2_gain_acc_y | 0 | -32768 | 32767 | Secondary IMU ACC calibration data | -| imu2_gain_acc_z | 0 | -32768 | 32767 | Secondary IMU ACC calibration data | -| imu2_gain_mag_x | 0 | -32768 | 32767 | Secondary IMU MAG calibration data | -| imu2_gain_mag_y | 0 | -32768 | 32767 | Secondary IMU MAG calibration data | -| imu2_gain_mag_z | 0 | -32768 | 32767 | Secondary IMU MAG calibration data | -| imu2_hardware | NONE | | | Selection of a Secondary IMU hardware type. NONE disables this functionality | -| imu2_radius_acc | 0 | -32768 | 32767 | Secondary IMU MAG calibration data | -| imu2_radius_mag | 0 | -32768 | 32767 | Secondary IMU MAG calibration data | -| imu2_use_for_osd_ahi | OFF | | | If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon | -| imu2_use_for_osd_heading | OFF | | | If set to ON, Secondary IMU data will be used for Analog OSD heading | -| imu2_use_for_stabilized | OFF | | | If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH) | -| imu_acc_ignore_rate | 0 | 0 | 20 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes | -| imu_acc_ignore_slope | 0 | 0 | 5 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) | -| imu_dcm_ki | 50 | | 65535 | Inertial Measurement Unit KI Gain for accelerometer measurements | -| imu_dcm_ki_mag | 0 | | 65535 | Inertial Measurement Unit KI Gain for compass measurements | -| imu_dcm_kp | 2500 | | 65535 | Inertial Measurement Unit KP Gain for accelerometer measurements | -| imu_dcm_kp_mag | 10000 | | 65535 | Inertial Measurement Unit KP Gain for compass measurements | -| inav_allow_dead_reckoning | OFF | | | Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation | -| 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 | 0 | 9999 | Uncertainty value for barometric sensor [cm] | -| inav_gravity_cal_tolerance | 5 | 0 | 255 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. | -| inav_max_eph_epv | 1000 | 0 | 9999 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] | -| inav_max_surface_altitude | 200 | 0 | 1000 | 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_no_baro | OFF | | | | -| 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.01 | 0 | 1 | Weight for accelerometer drift estimation | -| inav_w_xy_flow_p | 1.0 | 0 | 100 | | -| inav_w_xy_flow_v | 2.0 | 0 | 100 | | -| inav_w_xy_gps_p | 1.0 | 0 | 10 | Weight of GPS coordinates in estimated UAV position and speed. | -| inav_w_xy_gps_v | 2.0 | 0 | 10 | Weight of GPS velocity data in estimated UAV speed | -| inav_w_xy_res_v | 0.5 | 0 | 10 | Decay coefficient for estimated velocity when GPS reference for position is lost | -| inav_w_xyz_acc_p | 1.0 | 0 | 1 | | -| inav_w_z_baro_p | 0.35 | 0 | 10 | Weight of barometer measurements in estimated altitude and climb rate | -| inav_w_z_gps_p | 0.2 | 0 | 10 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes | -| inav_w_z_gps_v | 0.1 | 0 | 10 | 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.5 | 0 | 10 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost | -| inav_w_z_surface_p | 3.5 | 0 | 100 | | -| inav_w_z_surface_v | 6.1 | 0 | 100 | | -| iterm_windup | 50 | 0 | 90 | 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 | | | | -| limit_attn_filter_cutoff | 1.2 | | 100 | Throttle attenuation PI control output filter cutoff frequency | -| limit_burst_current | 0 | | 4000 | Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable | -| limit_burst_current_falldown_time | 0 | | 3000 | Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current` | -| limit_burst_current_time | 0 | | 3000 | Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced | -| limit_burst_power | 0 | | 40000 | Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable | -| limit_burst_power_falldown_time | 0 | | 3000 | Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power` | -| limit_burst_power_time | 0 | | 3000 | Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced | -| limit_cont_current | 0 | | 4000 | Continous current limit (dA), set to 0 to disable | -| limit_cont_power | 0 | | 40000 | Continous power limit (dW), set to 0 to disable | -| limit_pi_i | 100 | | 10000 | Throttle attenuation PI control I term | -| limit_pi_p | 100 | | 10000 | Throttle attenuation PI control P term | -| log_level | ERROR | | | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. | -| log_topics | 0 | 0 | 4294967295 | Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage. | -| looptime | 1000 | | 9000 | 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 | 20 | 120 | Adjust how long time the Calibration of mag will last. | -| mag_declination | 0 | -18000 | 18000 | 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 | 0 | 0 | 1 | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target | -| maggain_x | 1024 | -32768 | 32767 | Magnetometer calibration X gain. If 1024, no calibration or calibration failed | -| maggain_y | 1024 | -32768 | 32767 | Magnetometer calibration Y gain. If 1024, no calibration or calibration failed | -| maggain_z | 1024 | -32768 | 32767 | Magnetometer calibration Z gain. If 1024, no calibration or calibration failed | -| magzero_x | 0 | -32768 | 32767 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_y | 0 | -32768 | 32767 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. | -| magzero_z | 0 | -32768 | 32767 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. | -| manual_pitch_rate | 100 | 0 | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% | -| manual_rc_expo | 70 | 0 | 100 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] | -| manual_rc_yaw_expo | 20 | 0 | 100 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] | -| manual_roll_rate | 100 | 0 | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% | -| manual_yaw_rate | 100 | 0 | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% | -| mavlink_ext_status_rate | 2 | 0 | 255 | | -| mavlink_extra1_rate | 10 | 0 | 255 | | -| mavlink_extra2_rate | 2 | 0 | 255 | | -| mavlink_extra3_rate | 1 | 0 | 255 | | -| mavlink_pos_rate | 2 | 0 | 255 | | -| mavlink_rc_chan_rate | 5 | 0 | 255 | | -| mavlink_version | 2 | 1 | 2 | Version of MAVLink to use | -| max_angle_inclination_pit | 300 | 100 | 900 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° | -| max_angle_inclination_rll | 300 | 100 | 900 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° | -| max_check | 1900 | PWM_RANGE_MIN | PWM_RANGE_MAX | 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 | PWM_RANGE_MIN | PWM_RANGE_MAX | 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_cd_lpf_hz | 30 | 0 | 200 | 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 | 0 | 200 | Multicopter Control Derivative gain for PITCH | -| mc_cd_roll | 60 | 0 | 200 | Multicopter Control Derivative gain for ROLL | -| mc_cd_yaw | 60 | 0 | 200 | Multicopter Control Derivative gain for YAW | -| mc_d_level | 75 | 0 | 200 | Multicopter attitude stabilisation HORIZON transition point | -| mc_d_pitch | 23 | 0 | 200 | Multicopter rate stabilisation D-gain for PITCH | -| mc_d_roll | 23 | 0 | 200 | Multicopter rate stabilisation D-gain for ROLL | -| mc_d_yaw | 0 | 0 | 200 | Multicopter rate stabilisation D-gain for YAW | -| mc_i_level | 15 | 0 | 200 | Multicopter attitude stabilisation low-pass filter cutoff | -| mc_i_pitch | 30 | 0 | 200 | Multicopter rate stabilisation I-gain for PITCH | -| mc_i_roll | 30 | 0 | 200 | Multicopter rate stabilisation I-gain for ROLL | -| mc_i_yaw | 45 | 0 | 200 | Multicopter rate stabilisation I-gain for YAW | -| mc_iterm_relax | RP | | | | -| mc_iterm_relax_cutoff | 15 | 1 | 100 | | -| mc_p_level | 20 | 0 | 200 | Multicopter attitude stabilisation P-gain | -| mc_p_pitch | 40 | 0 | 200 | Multicopter rate stabilisation P-gain for PITCH | -| mc_p_roll | 40 | 0 | 200 | Multicopter rate stabilisation P-gain for ROLL | -| mc_p_yaw | 85 | 0 | 200 | Multicopter rate stabilisation P-gain for YAW | -| min_check | 1100 | PWM_RANGE_MIN | PWM_RANGE_MAX | 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 | 0 | PWM_RANGE_MAX | 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 | -1 | 32767 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. | -| moron_threshold | 32 | | 128 | 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 | 0 | 1000 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] | -| motor_decel_time | 0 | 0 | 1000 | 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_poles | 14 | 4 | 255 | The number of motor poles. Required to compute motor RPM | -| motor_pwm_protocol | ONESHOT125 | | | 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 | 50 | 32000 | 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. | -| msp_override_channels | 0 | 0 | 65535 | 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. | -| name | _empty_ | | | Craft name | -| nav_auto_climb_rate | 500 | 10 | 2000 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] | -| nav_auto_speed | 300 | 10 | 2000 | 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 | 100 | 2000 | 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 | 35 | 5 | 80 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll | -| nav_fw_climb_angle | 20 | 5 | 80 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_control_smoothness | 0 | 0 | 9 | How smoothly the autopilot controls the airplane to correct the navigation error | -| nav_fw_cruise_speed | 0 | 0 | 65535 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s | -| nav_fw_cruise_thr | 1400 | 1000 | 2000 | 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 | 0 | 60 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] | -| nav_fw_dive_angle | 15 | 5 | 80 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit | -| nav_fw_heading_p | 60 | 0 | 255 | P gain of Heading Hold controller (Fixedwing) | -| nav_fw_land_dive_angle | 2 | -20 | 20 | 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 | 1000 | 20000 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s | -| nav_fw_launch_climb_angle | 18 | 5 | 45 | Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit | -| nav_fw_launch_detect_time | 40 | 10 | 1000 | Time for which thresholds have to breached to consider launch happened [ms] | -| nav_fw_launch_end_time | 3000 | 0 | 5000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] | -| nav_fw_launch_idle_motor_delay | 0 | 0 | 60000 | Delay between raising throttle and motor starting at idle throttle (ms) | -| nav_fw_launch_idle_thr | 1000 | 1000 | 2000 | 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 | 0 | 60000 | 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 | 5 | 180 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] | -| nav_fw_launch_min_time | 0 | 0 | 60000 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. | -| nav_fw_launch_motor_delay | 500 | 0 | 5000 | Delay between detected launch and launch sequence start and throttling up (ms) | -| nav_fw_launch_spinup_time | 100 | 0 | 1000 | 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 | 1000 | 2000 | Launch throttle - throttle to be set during launch sequence (pwm units) | -| nav_fw_launch_timeout | 5000 | | 60000 | 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 | 100 | 10000 | Forward velocity threshold for swing-launch detection [cm/s] | -| nav_fw_loiter_radius | 7500 | 0 | 30000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] | -| nav_fw_max_thr | 1700 | 1000 | 2000 | Maximum throttle for flying wing in GPS assisted modes | -| nav_fw_min_thr | 1200 | 1000 | 2000 | Minimum throttle for flying wing in GPS assisted modes | -| nav_fw_pitch2thr | 10 | 0 | 100 | 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_pitch2thr_smoothing | 6 | 0 | 9 | How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh. | -| nav_fw_pitch2thr_threshold | 50 | 0 | 900 | Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees] | -| nav_fw_pos_hdg_d | 0 | 0 | 255 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_i | 2 | 0 | 255 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_p | 30 | 0 | 255 | P gain of heading PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_hdg_pidsum_limit | 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) | -| nav_fw_pos_xy_d | 8 | 0 | 255 | 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 | 0 | 255 | 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 | 0 | 255 | 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 | 10 | 0 | 255 | D gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_i | 5 | 0 | 255 | I gain of altitude PID controller (Fixedwing) | -| nav_fw_pos_z_p | 40 | 0 | 255 | P gain of altitude PID controller (Fixedwing) | -| nav_fw_yaw_deadband | 0 | 0 | 90 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course | -| nav_land_maxalt_vspd | 200 | 100 | 2000 | Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s] | -| nav_land_minalt_vspd | 50 | 50 | 500 | Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s] | -| nav_land_slowdown_maxalt | 2000 | 500 | 4000 | Defines at what altitude the descent velocity should start to ramp down from `nav_land_maxalt_vspd` to `nav_land_minalt_vspd` during the RTH landing phase [cm] | -| nav_land_slowdown_minalt | 500 | 50 | 1000 | Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm] | -| nav_manual_climb_rate | 200 | 10 | 2000 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] | -| nav_manual_speed | 500 | 10 | 2000 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] | -| nav_max_altitude | 0 | 0 | 65000 | Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled | -| nav_max_terrain_follow_alt | 100 | | 1000 | Max allowed above the ground altitude for terrain following mode | -| nav_mc_auto_disarm_delay | 2000 | 100 | 10000 | Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) | -| nav_mc_bank_angle | 30 | 15 | 45 | 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 | 15 | 60 | max angle that MR is allowed to bank in BOOST mode | -| nav_mc_braking_boost_disengage_speed | 100 | 0 | 1000 | BOOST will be disabled when speed goes below this value | -| nav_mc_braking_boost_factor | 100 | 0 | 200 | acceleration factor for BOOST phase | -| nav_mc_braking_boost_speed_threshold | 150 | 100 | 1000 | BOOST can be enabled when speed is above this value | -| nav_mc_braking_boost_timeout | 750 | 0 | 5000 | how long in ms BOOST phase can happen | -| nav_mc_braking_disengage_speed | 75 | 0 | 1000 | braking is disabled when speed goes below this value | -| nav_mc_braking_speed_threshold | 100 | 0 | 1000 | min speed in cm/s above which braking can happen | -| nav_mc_braking_timeout | 2000 | 100 | 5000 | timeout in ms for braking | -| nav_mc_heading_p | 60 | 0 | 255 | P gain of Heading Hold controller (Multirotor) | -| nav_mc_hover_thr | 1500 | 1000 | 2000 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. | -| nav_mc_pos_deceleration_time | 120 | 0 | 255 | 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 | 0 | 255 | Expo for PosHold control | -| nav_mc_pos_xy_p | 65 | 0 | 255 | 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 | 0 | 255 | P gain of altitude PID controller (Multirotor) | -| nav_mc_vel_xy_d | 100 | 0 | 255 | 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_dterm_attenuation | 90 | 0 | 100 | Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. | -| nav_mc_vel_xy_dterm_attenuation_end | 60 | 0 | 100 | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum | -| nav_mc_vel_xy_dterm_attenuation_start | 10 | 0 | 100 | A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins | -| nav_mc_vel_xy_dterm_lpf_hz | 2 | 0 | 100 | | -| nav_mc_vel_xy_ff | 40 | 0 | 255 | | -| nav_mc_vel_xy_i | 15 | 0 | 255 | 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 | 0 | 255 | 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 | 0 | 255 | D gain of velocity PID controller | -| nav_mc_vel_z_i | 50 | 0 | 255 | I gain of velocity PID controller | -| nav_mc_vel_z_p | 100 | 0 | 255 | P gain of velocity PID controller | -| nav_mc_wp_slowdown | ON | | | When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes. | -| nav_min_rth_distance | 500 | 0 | 5000 | 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 | ALL_NAV | | | When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV | -| nav_position_timeout | 5 | 0 | 10 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) | -| nav_rth_abort_threshold | 50000 | | 65000 | 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_control_override | OFF | | | If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the RTH climb phase using full pitch or roll stick held for > 1 second. RTH altitude is reset to the current altitude using pitch down stick. RTH CLIMB FIRST is overridden using right roll stick so craft turns and heads directly to home (CLIMB FIRST override only works for fixed wing) | -| 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 | | 65000 | 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 or ON_FW_SPIRAL aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF aircraft will turn and head home immediately climbing on the way. For a fixed wing ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate, turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor) | -| 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 | | 65000 | 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_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_load_on_boot | OFF | | | If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup. | -| nav_wp_radius | 100 | 10 | 10000 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius | -| nav_wp_safe_distance | 10000 | | 65000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. | -| opflow_hardware | NONE | | | Selection of OPFLOW hardware. | -| opflow_scale | 10.5 | 0 | 10000 | | -| osd_ahi_bordered | OFF | | | Shows a border/corners around the AHI region (pixel OSD only) | -| osd_ahi_height | 162 | | 255 | AHI height in pixels (pixel OSD only) | -| osd_ahi_max_pitch | 20 | 10 | 90 | Max pitch, in degrees, for OSD artificial horizon | -| osd_ahi_reverse_roll | OFF | | | | -| osd_ahi_style | DEFAULT | | | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. | -| osd_ahi_vertical_offset | -18 | -128 | 127 | AHI vertical offset from center (pixel OSD only) | -| osd_ahi_width | 132 | | 255 | AHI width in pixels (pixel OSD only) | -| osd_alt_alarm | 100 | 0 | 10000 | Value above which to make the OSD relative altitude indicator blink (meters) | -| osd_baro_temp_alarm_max | 600 | -550 | 1250 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_baro_temp_alarm_min | -200 | -550 | 1250 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) | -| osd_camera_fov_h | 135 | 60 | 150 | Horizontal field of view for the camera in degres | -| osd_camera_fov_v | 85 | 30 | 120 | Vertical field of view for the camera in degres | -| osd_camera_uptilt | 0 | -40 | 80 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal | -| osd_coordinate_digits | 9 | 8 | 11 | | -| osd_crosshairs_style | DEFAULT | | | To set the visual type for the crosshair | -| osd_crsf_lq_format | TYPE1 | | | To select LQ format | -| osd_current_alarm | 0 | 0 | 255 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. | -| osd_dist_alarm | 1000 | 0 | 50000 | Value above which to make the OSD distance from home indicator blink (meters) | -| osd_esc_temp_alarm_max | 900 | -550 | 1500 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_esc_temp_alarm_min | -200 | -550 | 1500 | 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_force_grid | OFF | | | Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) | -| osd_gforce_alarm | 5 | 0 | 20 | Value above which the OSD g force indicator will blink (g) | -| osd_gforce_axis_alarm_max | 5 | -20 | 20 | Value above which the OSD axis g force indicators will blink (g) | -| osd_gforce_axis_alarm_min | -5 | -20 | 20 | Value under which the OSD axis g force indicators will blink (g) | -| osd_home_position_arm_screen | ON | | | Should home position coordinates be displayed on the arming screen. | -| osd_horizon_offset | 0 | -2 | 2 | To vertically adjust the whole OSD and AHI and scrolling bars | -| osd_hud_homepoint | OFF | | | To 3D-display the home point location in the hud | -| osd_hud_homing | OFF | | | To display little arrows around the crossair showing where the home point is in the hud | -| osd_hud_margin_h | 3 | 0 | 4 | Left and right margins for the hud area | -| osd_hud_margin_v | 3 | 1 | 3 | Top and bottom margins for the hud area | -| osd_hud_radar_disp | 0 | 0 | 4 | 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 | -| osd_hud_radar_nearest | 0 | 0 | 4000 | 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. | -| osd_hud_radar_range_max | 4000 | 100 | 9990 | In meters, radar aircrafts further away than this will not be displayed in the hud | -| osd_hud_radar_range_min | 3 | 1 | 30 | In meters, radar aircrafts closer than this will not be displayed in the hud | -| osd_hud_wp_disp | 0 | 0 | 3 | 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) | -| osd_imu_temp_alarm_max | 600 | -550 | 1250 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_imu_temp_alarm_min | -200 | -550 | 1250 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) | -| osd_left_sidebar_scroll | NONE | | | | -| osd_left_sidebar_scroll_step | 0 | | 255 | How many units each sidebar step represents. 0 means the default value for the scroll type. | -| osd_link_quality_alarm | 70 | 0 | 100 | LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50% | -| osd_main_voltage_decimals | 1 | 1 | 2 | Number of decimals for the battery voltages displayed in the OSD [1-2]. | -| osd_neg_alt_alarm | 5 | 0 | 10000 | Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters) | -| osd_pan_servo_index | 0 | 0 | 10 | Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. | -| osd_pan_servo_pwm2centideg | 0 | -36 | 36 | Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction. | -| osd_plus_code_digits | 11 | 10 | 13 | Numer of plus code digits before shortening with `osd_plus_code_short`. Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm. | -| osd_plus_code_short | 0 | | | Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates. | -| osd_right_sidebar_scroll | NONE | | | | -| osd_right_sidebar_scroll_step | 0 | | 255 | Same as left_sidebar_scroll_step, but for the right sidebar | -| osd_row_shiftdown | 0 | 0 | 1 | Number of rows to shift the OSD display (increase if top rows are cut off) | -| osd_rssi_alarm | 20 | 0 | 100 | Value below which to make the OSD RSSI indicator blink | -| osd_rssi_dbm_alarm | 0 | -130 | 0 | RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm | -| osd_sidebar_height | 3 | 0 | 5 | Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) | -| osd_sidebar_horizontal_offset | 0 | -128 | 127 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. | -| osd_sidebar_scroll_arrows | OFF | | | | -| osd_snr_alarm | 4 | -20 | 10 | Value below which Crossfire SNR Alarm pops-up. (dB) | -| osd_speed_source | GROUND | | | Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR | -| osd_stats_energy_unit | MAH | | | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) | -| osd_stats_min_voltage_unit | BATTERY | | | Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats. | -| osd_telemetry | OFF | | | To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST` | -| 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 | 0 | 600 | 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 | AUTO | | | 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 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | 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 | 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | 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 | -| pinio_box1 | `BOX_PERMANENT_ID_NONE` | 0 | 255 | Mode assignment for PINIO#1 | -| pinio_box2 | `BOX_PERMANENT_ID_NONE` | 0 | 255 | Mode assignment for PINIO#1 | -| pinio_box3 | `BOX_PERMANENT_ID_NONE` | 0 | 255 | Mode assignment for PINIO#1 | -| pinio_box4 | `BOX_PERMANENT_ID_NONE` | 0 | 255 | Mode assignment for PINIO#1 | -| pitch_rate | 20 | 6 | 180 | 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. | -| pitot_hardware | NONE | | | Selection of pitot hardware. | -| pitot_lpf_milli_hz | 350 | 0 | 10000 | | -| pitot_scale | 1.0 | 0 | 100 | | -| 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 | 10 | 2 | 250 | Stick deadband in [r/c points], applied after r/c deadband and expo | -| prearm_timeout | 10000 | 0 | 10000 | Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. | -| rangefinder_hardware | NONE | | | Selection of rangefinder hardware. | -| rangefinder_median_filter | OFF | | | 3-point median filtering for rangefinder readouts | -| rate_accel_limit_roll_pitch | 0 | | 500000 | 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 | | 500000 | 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 | 0 | 100 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) | -| rc_filter_frequency | 50 | 0 | 100 | 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 | 0 | 100 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) | -| reboot_character | 82 | 48 | 126 | Special character used to trigger reboot | -| receiver_type | _target default_ | | | Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL` | -| report_cell_voltage | OFF | | | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON | -| roll_rate | 20 | 6 | 180 | 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 | 1 | 3 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine | -| rpm_gyro_min_hz | 100 | 30 | 200 | 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 | 1 | 3000 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting | -| rssi_adc_channel | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled | -| rssi_channel | 0 | 0 | MAX_SUPPORTED_RC_CHANNEL_COUNT | RX channel containing the RSSI signal | -| rssi_max | 100 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. | -| rssi_min | 0 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX | 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 | 0 | 100 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation | -| rx_max_usec | 2115 | PWM_PULSE_MIN | PWM_PULSE_MAX | 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 | PWM_PULSE_MIN | PWM_PULSE_MAX | 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_spi_id | 0 | 0 | 0 | | -| rx_spi_protocol | _target default_ | | | | -| rx_spi_rf_channel_count | 0 | 0 | 8 | | -| safehome_max_distance | 20000 | 0 | 65000 | In order for a safehome to be used, it must be less than this distance (in cm) from the arming point. | -| safehome_usage_mode | RTH | | | Used to control when safehomes will be used. Possible values are `OFF`, `RTH` and `RTH_FS`. See [Safehome documentation](Safehomes.md#Safehome) for more information. | -| sbus_sync_interval | 3000 | 500 | 10000 | | -| sdcard_detect_inverted | _target default_ | | | 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 | AUTO | | | 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 | _target default_ | | | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. | -| servo_autotrim_rotation_limit | 15 | 1 | 60 | Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`. | -| servo_center_pulse | 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX | Servo midpoint | -| servo_lpf_hz | 20 | 0 | 400 | 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 | 50 | 498 | 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. | -| setpoint_kalman_enabled | OFF | | | Enable Kalman filter on the PID controller setpoint | -| setpoint_kalman_q | 100 | 1 | 16000 | Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds | -| setpoint_kalman_sharpness | 100 | 1 | 16000 | Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets | -| setpoint_kalman_w | 4 | 1 | 40 | Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response | -| sim_ground_station_number | _empty_ | | | 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 | -32767 | -32768 | 32767 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. | -| sim_pin | 0000 | | | PIN code for the SIM module | -| sim_transmit_flags | `SIM_TX_FLAG_FAILSAFE` | | 63 | Bitmask specifying text message transmit condition flags for the SIM module. 1: continuous transmission, 2: continuous transmission in failsafe mode, 4: continuous transmission when GPS signal quality is low, 8: acceleration events, 16: continuous transmission when altitude is below `sim_low_altitude` | -| sim_transmit_interval | 60 | SIM_MIN_TRANSMIT_INTERVAL | 65535 | Text message transmission interval in seconds for SIM module. Minimum value: 10 | -| small_angle | 25 | 0 | 180 | 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] | -| smartport_master_halfduplex | ON | | | | -| smartport_master_inverted | OFF | | | | -| smith_predictor_delay | 0 | 0 | 8 | Expected delay of the gyro signal. In milliseconds | -| smith_predictor_lpf_hz | 50 | 1 | 500 | Cutoff frequency for the Smith Predictor Low Pass Filter | -| smith_predictor_strength | 0.5 | 0 | 1 | The strength factor of a Smith Predictor of PID measurement. In percents | -| spektrum_sat_bind | `SPEKTRUM_SAT_BIND_DISABLED` | SPEKTRUM_SAT_BIND_DISABLED | SPEKTRUM_SAT_BIND_MAX | 0 = disabled. Used to bind the spektrum satellite to RX | -| srxl2_baud_fast | ON | | | | -| srxl2_unit_id | 1 | 0 | 15 | | -| stats | OFF | | | General switch of the statistics recording feature (a.k.a. odometer) | -| stats_total_dist | 0 | | 2147483647 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. | -| stats_total_energy | 0 | | 2147483647 | | -| stats_total_time | 0 | | 2147483647 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. | -| switch_disarm_delay | 250 | 0 | 1000 | Delay before disarming when requested by switch (ms) [0-1000] | -| telemetry_halfduplex | ON | | | 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 | 1 | 0 | 2 | 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 | 0 | 100 | Throttle exposition value | -| thr_mid | 50 | 0 | 100 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. | -| throttle_idle | 15 | 0 | 30 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. | -| throttle_scale | 1.0 | 0 | 1 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% | -| throttle_tilt_comp_str | 0 | 0 | 100 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. | -| tpa_breakpoint | 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX | See tpa_rate. | -| tpa_rate | 0 | 0 | 100 | 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. | -| turtle_mode_power_factor | 55 | 0 | 100 | Turtle mode power factor | -| 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 | -1440 | 1440 | 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 | _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled | -| vbat_cell_detect_voltage | 425 | 100 | 500 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units. | -| vbat_max_cell_voltage | 420 | 100 | 500 | 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 | 100 | 500 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) | -| vbat_scale | _target default_ | VBAT_SCALE_MIN | VBAT_SCALE_MAX | 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 | 100 | 500 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) | -| vtx_band | 4 | VTX_SETTINGS_NO_BAND | VTX_SETTINGS_MAX_BAND | 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 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL | 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_max_power_override | 0 | 0 | 10000 | 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 | -| vtx_pit_mode_chan | 1 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL | | -| vtx_power | 1 | VTX_SETTINGS_MIN_POWER | VTX_SETTINGS_MAX_POWER | VTX RF power level to use. The exact number of mw depends on the VTX hardware. | -| vtx_smartaudio_early_akk_workaround | ON | | | Enable workaround for early AKK SAudio-enabled VTX bug. | -| yaw_deadband | 5 | 0 | 100 | 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 | 0 | 0 | 200 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) | -| yaw_rate | 20 | 2 | 180 | 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 document is autogenerated. Do not edit it manually. + +### 3d_deadband_high + +High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) + +| Default | Min | Max | +| --- | --- | --- | +| 1514 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### 3d_deadband_low + +Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) + +| Default | Min | Max | +| --- | --- | --- | +| 1406 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### 3d_deadband_throttle + +Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 200 | + +--- + +### 3d_neutral + +Neutral (stop) throttle value for 3D mode + +| Default | Min | Max | +| --- | --- | --- | +| 1460 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### acc_event_threshold_high + +Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65535 | + +--- + +### acc_event_threshold_low + +Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 900 | + +--- + +### acc_event_threshold_neg_x + +Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65535 | + +--- + +### acc_hardware + +Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### acc_lpf_hz + +Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 0 | 200 | + +--- + +### acc_lpf_type + +Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. + +| Default | Min | Max | +| --- | --- | --- | +| BIQUAD | | | + +--- + +### acc_notch_cutoff + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 255 | + +--- + +### acc_notch_hz + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 255 | + +--- + +### accgain_x + +Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 4096 | 1 | 8192 | + +--- + +### accgain_y + +Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 4096 | 1 | 8192 | + +--- + +### accgain_z + +Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 4096 | 1 | 8192 | + +--- + +### acczero_x + +Calculated value after '6 position avanced calibration'. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### acczero_y + +Calculated value after '6 position avanced calibration'. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### acczero_z + +Calculated value after '6 position avanced calibration'. See Wiki page. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### airmode_throttle_threshold + +Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used + +| Default | Min | Max | +| --- | --- | --- | +| 1300 | 1000 | 2000 | + +--- + +### airmode_type + +Defines the Airmode state handling type. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `airmode_throttle_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER_ONCE** or **STICK_CENTER** modes. + +| Default | Min | Max | +| --- | --- | --- | +| STICK_CENTER | | | + +--- + +### airspeed_adc_channel + +ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | + +--- + +### align_acc + +When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. + +| Default | Min | Max | +| --- | --- | --- | +| DEFAULT | | | + +--- + +### align_board_pitch + +Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_board_roll + +Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_board_yaw + +Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_gyro + +When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. + +| Default | Min | Max | +| --- | --- | --- | +| DEFAULT | | | + +--- + +### align_mag + +When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. + +| Default | Min | Max | +| --- | --- | --- | +| DEFAULT | | | + +--- + +### align_mag_pitch + +Same as align_mag_roll, but for the pitch axis. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_mag_roll + +Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_mag_yaw + +Same as align_mag_roll, but for the yaw axis. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### align_opflow + +Optical flow module alignment (default CW0_DEG_FLIP) + +| Default | Min | Max | +| --- | --- | --- | +| CW0FLIP | | | + +--- + +### alt_hold_deadband + +Defines the deadband of throttle during alt_hold [r/c points] + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 10 | 250 | + +--- + +### antigravity_accelerator + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 20 | + +--- + +### antigravity_cutoff_lpf_hz + +Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 1 | 30 | + +--- + +### antigravity_gain + +Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 20 | + +--- + +### applied_defaults + +Internal (configurator) hint. Should not be changed manually + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 3 | + +--- + +### baro_cal_tolerance + +Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. + +| Default | Min | Max | +| --- | --- | --- | +| 150 | 0 | 1000 | + +--- + +### baro_hardware + +Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### baro_median_filter + +3-point median filtering for barometer readouts. No reason to change this setting + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### bat_cells + +Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 12 | + +--- + +### bat_voltage_src + +Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` + +| Default | Min | Max | +| --- | --- | --- | +| RAW | | | + +--- + +### battery_capacity + +Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4294967295 | + +--- + +### battery_capacity_critical + +If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4294967295 | + +--- + +### battery_capacity_unit + +Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). + +| Default | Min | Max | +| --- | --- | --- | +| MAH | | | + +--- + +### battery_capacity_warning + +If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4294967295 | + +--- + +### blackbox_device + +Selection of where to write blackbox data + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | | | + +--- + +### blackbox_rate_denom + +Blackbox logging rate denominator. See blackbox_rate_num. + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 65535 | + +--- + +### blackbox_rate_num + +Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 65535 | + +--- + +### cpu_underclock + +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 | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### cruise_power + +Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4294967295 | + +--- + +### current_adc_channel + +ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | + +--- + +### current_meter_offset + +This sets the output offset voltage of the current sensor in millivolts. + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | -32768 | 32767 | + +--- + +### current_meter_scale + +This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | -10000 | 10000 | + +--- + +### current_meter_type + +ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. + +| Default | Min | Max | +| --- | --- | --- | +| ADC | | | + +--- + +### d_boost_factor + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1.25 | 1 | 3 | + +--- + +### d_boost_gyro_delta_lpf_hz + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 80 | 10 | 250 | + +--- + +### d_boost_max_at_acceleration + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 7500 | 1000 | 16000 | + +--- + +### deadband + +These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 32 | + +--- + +### debug_mode + +Defines debug values exposed in debug variables (developer / debugging setting) + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### disarm_kill_switch + +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 | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### display_force_sw_blink + +OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### dji_esc_temp_source + +Re-purpose the ESC temperature field for IMU/BARO temperature + +| Default | Min | Max | +| --- | --- | --- | +| ESC | | | + +--- + +### dji_use_name_for_messages + +Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### dji_workarounds + +Enables workarounds for different versions of MSP protocol used + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 255 | + +--- + +### dshot_beeper_enabled + +Whether using DShot motors as beepers is enabled + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### dshot_beeper_tone + +Sets the DShot beeper tone + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 5 | + +--- + +### dterm_lpf2_hz + +Cutoff frequency for stage 2 D-term low pass filter + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 500 | + +--- + +### dterm_lpf2_type + +Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. + +| Default | Min | Max | +| --- | --- | --- | +| BIQUAD | | | + +--- + +### dterm_lpf_hz + +Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 500 | + +--- + +### dterm_lpf_type + +Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. + +| Default | Min | Max | +| --- | --- | --- | +| BIQUAD | | | + +--- + +### dynamic_gyro_notch_enabled + +Enable/disable dynamic gyro notch also known as Matrix Filter + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### dynamic_gyro_notch_min_hz + +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 | Min | Max | +| --- | --- | --- | +| 150 | 30 | 1000 | + +--- + +### dynamic_gyro_notch_q + +Q factor for dynamic notches + +| Default | Min | Max | +| --- | --- | --- | +| 120 | 1 | 1000 | + +--- + +### dynamic_gyro_notch_range + +Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers + +| Default | Min | Max | +| --- | --- | --- | +| MEDIUM | | | + +--- + +### eleres_freq + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 435 | 415 | 450 | + +--- + +### eleres_loc_delay + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 240 | 30 | 1800 | + +--- + +### eleres_loc_en + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### eleres_loc_power + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 7 | 0 | 7 | + +--- + +### eleres_signature + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 4294967295 | + +--- + +### eleres_telemetry_en + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### eleres_telemetry_power + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 7 | 0 | 7 | + +--- + +### esc_sensor_listen_only + +Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### failsafe_delay + +Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 200 | + +--- + +### failsafe_fw_pitch_angle + +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 | Min | Max | +| --- | --- | --- | +| 100 | -800 | 800 | + +--- + +### failsafe_fw_roll_angle + +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 | Min | Max | +| --- | --- | --- | +| -200 | -800 | 800 | + +--- + +### failsafe_fw_yaw_rate + +Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn + +| Default | Min | Max | +| --- | --- | --- | +| -45 | -1000 | 1000 | + +--- + +### failsafe_lights + +Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### failsafe_lights_flash_on_time + +Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 20 | 65535 | + +--- + +### failsafe_lights_flash_period + +Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | 40 | 65535 | + +--- + +### failsafe_min_distance + +If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65000 | + +--- + +### failsafe_min_distance_procedure + +What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). + +| Default | Min | Max | +| --- | --- | --- | +| DROP | | | + +--- + +### failsafe_mission + +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 | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### failsafe_off_delay + +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 | Min | Max | +| --- | --- | --- | +| 200 | 0 | 200 | + +--- + +### failsafe_procedure + +What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). + +| Default | Min | Max | +| --- | --- | --- | +| SET-THR | | | + +--- + +### failsafe_recovery_delay + +Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 200 | + +--- + +### failsafe_stick_threshold + +Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 500 | + +--- + +### failsafe_throttle + +Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### failsafe_throttle_low_delay + +If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 300 | + +--- + +### fixed_wing_auto_arm + +Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### flaperon_throw_offset + +Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. + +| Default | Min | Max | +| --- | --- | --- | +| 200 | FLAPERON_THROW_MIN | FLAPERON_THROW_MAX | + +--- + +### fpv_mix_degrees + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 50 | + +--- + +### frsky_coordinates_format + +D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | FRSKY_FORMAT_NMEA | + +--- + +### frsky_default_latitude + +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 | Min | Max | +| --- | --- | --- | +| 0 | -90 | 90 | + +--- + +### frsky_default_longitude + +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 | Min | Max | +| --- | --- | --- | +| 0 | -180 | 180 | + +--- + +### frsky_pitch_roll + +S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### frsky_unit + +Not used? [METRIC/IMPERIAL] + +| Default | Min | Max | +| --- | --- | --- | +| METRIC | | | + +--- + +### frsky_vfas_precision + +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 | Min | Max | +| --- | --- | --- | +| 0 | FRSKY_VFAS_PRECISION_LOW | FRSKY_VFAS_PRECISION_HIGH | + +--- + +### fw_autotune_ff_to_i_tc + +FF to I time (defines time for I to reach the same level of response as FF) [ms] + +| Default | Min | Max | +| --- | --- | --- | +| 600 | 100 | 5000 | + +--- + +### fw_autotune_ff_to_p_gain + +FF to P gain (strength relationship) [%] + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 100 | + +--- + +### fw_autotune_max_rate_deflection + +The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`. + +| Default | Min | Max | +| --- | --- | --- | +| 80 | 50 | 100 | + +--- + +### fw_autotune_min_stick + +Minimum stick input [%] to consider overshoot/undershoot detection + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 100 | + +--- + +### fw_autotune_p_to_d_gain + +P to D gain (strength relationship) [%] + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### fw_autotune_rate_adjustment + +`AUTO` and `LIMIT` adjust the rates to match the capabilities of the airplane, with `LIMIT` they are never increased above the starting rates setting. `FIXED` does not adjust the rates. Rates are not changed when tuning in `ANGLE` mode. + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### fw_d_level + +Fixed-wing attitude stabilisation HORIZON transition point + +| Default | Min | Max | +| --- | --- | --- | +| 75 | 0 | 200 | + +--- + +### fw_d_pitch + +Fixed wing rate stabilisation D-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### fw_d_roll + +Fixed wing rate stabilisation D-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### fw_d_yaw + +Fixed wing rate stabilisation D-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### fw_ff_pitch + +Fixed-wing rate stabilisation FF-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 200 | + +--- + +### fw_ff_roll + +Fixed-wing rate stabilisation FF-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 200 | + +--- + +### fw_ff_yaw + +Fixed-wing rate stabilisation FF-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 200 | + +--- + +### fw_i_level + +Fixed-wing attitude stabilisation low-pass filter cutoff + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 200 | + +--- + +### fw_i_pitch + +Fixed-wing rate stabilisation I-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 7 | 0 | 200 | + +--- + +### fw_i_roll + +Fixed-wing rate stabilisation I-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 7 | 0 | 200 | + +--- + +### fw_i_yaw + +Fixed-wing rate stabilisation I-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 200 | + +--- + +### fw_iterm_limit_stick_position + +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 | Min | Max | +| --- | --- | --- | +| 0.5 | 0 | 1 | + +--- + +### fw_iterm_throw_limit + +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 | Min | Max | +| --- | --- | --- | +| 165 | FW_ITERM_THROW_LIMIT_MIN | FW_ITERM_THROW_LIMIT_MAX | + +--- + +### fw_level_pitch_deadband + +Deadband for automatic leveling when AUTOLEVEL mode is used. + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 20 | + +--- + +### fw_level_pitch_gain + +I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 20 | + +--- + +### fw_level_pitch_trim + +Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -10 | 10 | + +--- + +### fw_loiter_direction + +Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. + +| Default | Min | Max | +| --- | --- | --- | +| RIGHT | | | + +--- + +### fw_min_throttle_down_pitch + +Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 450 | + +--- + +### fw_p_level + +Fixed-wing attitude stabilisation P-gain + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 200 | + +--- + +### fw_p_pitch + +Fixed-wing rate stabilisation P-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 200 | + +--- + +### fw_p_roll + +Fixed-wing rate stabilisation P-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 200 | + +--- + +### fw_p_yaw + +Fixed-wing rate stabilisation P-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 6 | 0 | 200 | + +--- + +### fw_reference_airspeed + +Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. + +| Default | Min | Max | +| --- | --- | --- | +| 1500 | 300 | 6000 | + +--- + +### fw_tpa_time_constant + +TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 5000 | + +--- + +### fw_turn_assist_pitch_gain + +Gain required to keep constant pitch angle during coordinated turns (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 2 | + +--- + +### fw_turn_assist_yaw_gain + +Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 2 | + +--- + +### fw_yaw_iterm_freeze_bank_angle + +Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 90 | + +--- + +### gps_auto_baud + +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 | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### gps_auto_config + +Enable automatic configuration of UBlox GPS receivers. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### gps_dyn_model + +GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. + +| Default | Min | Max | +| --- | --- | --- | +| AIR_1G | | | + +--- + +### gps_min_sats + +Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. + +| Default | Min | Max | +| --- | --- | --- | +| 6 | 5 | 10 | + +--- + +### gps_provider + +Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). + +| Default | Min | Max | +| --- | --- | --- | +| UBLOX | | | + +--- + +### gps_sbas_mode + +Which SBAS mode to be used + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### gps_ublox_use_galileo + +Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### gyro_abg_alpha + +Alpha factor for Gyro Alpha-Beta-Gamma filter + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1 | + +--- + +### gyro_abg_boost + +Boost factor for Gyro Alpha-Beta-Gamma filter + +| Default | Min | Max | +| --- | --- | --- | +| 0.35 | 0 | 2 | + +--- + +### gyro_abg_half_life + +Sample half-life for Gyro Alpha-Beta-Gamma filter + +| Default | Min | Max | +| --- | --- | --- | +| 0.5 | 0 | 10 | + +--- + +### gyro_anti_aliasing_lpf_hz + +Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz + +| Default | Min | Max | +| --- | --- | --- | +| 250 | | 1000 | + +--- + +### gyro_anti_aliasing_lpf_type + +Specifies the type of the software LPF of the gyro signals. + +| Default | Min | Max | +| --- | --- | --- | +| PT1 | | | + +--- + +### gyro_dyn_lpf_curve_expo + +Expo value for the throttle-to-frequency mapping for Dynamic LPF + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 1 | 10 | + +--- + +### gyro_dyn_lpf_max_hz + +Maximum frequency of the gyro Dynamic LPF + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 40 | 1000 | + +--- + +### gyro_dyn_lpf_min_hz + +Minimum frequency of the gyro Dynamic LPF + +| Default | Min | Max | +| --- | --- | --- | +| 200 | 40 | 400 | + +--- + +### gyro_hardware_lpf + +Hardware lowpass filter for gyro. This value should never be changed without a very strong reason! If you have to set gyro lpf below 256HZ, it means the frame is vibrating too much, and that should be fixed first. + +| Default | Min | Max | +| --- | --- | --- | +| 256HZ | | | + +--- + +### gyro_main_lpf_hz + +Software based gyro main lowpass filter. Value is cutoff frequency (Hz) + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 500 | + +--- + +### gyro_main_lpf_type + +Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. + +| Default | Min | Max | +| --- | --- | --- | +| BIQUAD | | | + +--- + +### gyro_notch_cutoff + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 500 | + +--- + +### gyro_notch_hz + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 500 | + +--- + +### gyro_to_use + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1 | + +--- + +### gyro_use_dyn_lpf + +Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### has_flaps + +Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### heading_hold_rate_limit + +This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. + +| Default | Min | Max | +| --- | --- | --- | +| 90 | HEADING_HOLD_RATE_LIMIT_MIN | HEADING_HOLD_RATE_LIMIT_MAX | + +--- + +### hott_alarm_sound_interval + +Battery alarm delay in seconds for Hott telemetry + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 120 | + +--- + +### i2c_speed + +This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) + +| Default | Min | Max | +| --- | --- | --- | +| 400KHZ | | | + +--- + +### ibus_telemetry_type + +Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 255 | + +--- + +### idle_power + +Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65535 | + +--- + +### imu2_align_pitch + +Pitch alignment for Secondary IMU. 1/10 of a degree + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### imu2_align_roll + +Roll alignment for Secondary IMU. 1/10 of a degree + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### imu2_align_yaw + +Yaw alignment for Secondary IMU. 1/10 of a degree + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1800 | 3600 | + +--- + +### imu2_gain_acc_x + +Secondary IMU ACC calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_gain_acc_y + +Secondary IMU ACC calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_gain_acc_z + +Secondary IMU ACC calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_gain_mag_x + +Secondary IMU MAG calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_gain_mag_y + +Secondary IMU MAG calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_gain_mag_z + +Secondary IMU MAG calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_hardware + +Selection of a Secondary IMU hardware type. NONE disables this functionality + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### imu2_radius_acc + +Secondary IMU MAG calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_radius_mag + +Secondary IMU MAG calibration data + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### imu2_use_for_osd_ahi + +If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### imu2_use_for_osd_heading + +If set to ON, Secondary IMU data will be used for Analog OSD heading + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### imu2_use_for_stabilized + +If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH) + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### imu_acc_ignore_rate + +Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 20 | + +--- + +### imu_acc_ignore_slope + +Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 5 | + +--- + +### imu_dcm_ki + +Inertial Measurement Unit KI Gain for accelerometer measurements + +| Default | Min | Max | +| --- | --- | --- | +| 50 | | 65535 | + +--- + +### imu_dcm_ki_mag + +Inertial Measurement Unit KI Gain for compass measurements + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 65535 | + +--- + +### imu_dcm_kp + +Inertial Measurement Unit KP Gain for accelerometer measurements + +| Default | Min | Max | +| --- | --- | --- | +| 2500 | | 65535 | + +--- + +### imu_dcm_kp_mag + +Inertial Measurement Unit KP Gain for compass measurements + +| Default | Min | Max | +| --- | --- | --- | +| 10000 | | 65535 | + +--- + +### inav_allow_dead_reckoning + +Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### inav_auto_mag_decl + +Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### inav_baro_epv + +Uncertainty value for barometric sensor [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 9999 | + +--- + +### inav_gravity_cal_tolerance + +Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 255 | + +--- + +### inav_max_eph_epv + +Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | 0 | 9999 | + +--- + +### inav_max_surface_altitude + +Max allowed altitude for surface following mode. [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 200 | 0 | 1000 | + +--- + +### inav_reset_altitude + +Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) + +| Default | Min | Max | +| --- | --- | --- | +| FIRST_ARM | | | + +--- + +### inav_reset_home + +Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM + +| Default | Min | Max | +| --- | --- | --- | +| FIRST_ARM | | | + +--- + +### inav_use_gps_no_baro + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### inav_use_gps_velned + +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 | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### inav_w_acc_bias + +Weight for accelerometer drift estimation + +| Default | Min | Max | +| --- | --- | --- | +| 0.01 | 0 | 1 | + +--- + +### inav_w_xy_flow_p + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1.0 | 0 | 100 | + +--- + +### inav_w_xy_flow_v + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 2.0 | 0 | 100 | + +--- + +### inav_w_xy_gps_p + +Weight of GPS coordinates in estimated UAV position and speed. + +| Default | Min | Max | +| --- | --- | --- | +| 1.0 | 0 | 10 | + +--- + +### inav_w_xy_gps_v + +Weight of GPS velocity data in estimated UAV speed + +| Default | Min | Max | +| --- | --- | --- | +| 2.0 | 0 | 10 | + +--- + +### inav_w_xy_res_v + +Decay coefficient for estimated velocity when GPS reference for position is lost + +| Default | Min | Max | +| --- | --- | --- | +| 0.5 | 0 | 10 | + +--- + +### inav_w_xyz_acc_p + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1.0 | 0 | 1 | + +--- + +### inav_w_z_baro_p + +Weight of barometer measurements in estimated altitude and climb rate + +| Default | Min | Max | +| --- | --- | --- | +| 0.35 | 0 | 10 | + +--- + +### inav_w_z_gps_p + +Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes + +| Default | Min | Max | +| --- | --- | --- | +| 0.2 | 0 | 10 | + +--- + +### inav_w_z_gps_v + +Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero + +| Default | Min | Max | +| --- | --- | --- | +| 0.1 | 0 | 10 | + +--- + +### inav_w_z_res_v + +Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost + +| Default | Min | Max | +| --- | --- | --- | +| 0.5 | 0 | 10 | + +--- + +### inav_w_z_surface_p + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 3.5 | 0 | 100 | + +--- + +### inav_w_z_surface_v + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 6.1 | 0 | 100 | + +--- + +### iterm_windup + +Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 90 | + +--- + +### ledstrip_visual_beeper + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### limit_attn_filter_cutoff + +Throttle attenuation PI control output filter cutoff frequency + +| Default | Min | Max | +| --- | --- | --- | +| 1.2 | | 100 | + +--- + +### limit_burst_current + +Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 4000 | + +--- + +### limit_burst_current_falldown_time + +Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current` + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 3000 | + +--- + +### limit_burst_current_time + +Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 3000 | + +--- + +### limit_burst_power + +Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 40000 | + +--- + +### limit_burst_power_falldown_time + +Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power` + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 3000 | + +--- + +### limit_burst_power_time + +Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 3000 | + +--- + +### limit_cont_current + +Continous current limit (dA), set to 0 to disable + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 4000 | + +--- + +### limit_cont_power + +Continous power limit (dW), set to 0 to disable + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 40000 | + +--- + +### limit_pi_i + +Throttle attenuation PI control I term + +| Default | Min | Max | +| --- | --- | --- | +| 100 | | 10000 | + +--- + +### limit_pi_p + +Throttle attenuation PI control P term + +| Default | Min | Max | +| --- | --- | --- | +| 100 | | 10000 | + +--- + +### log_level + +Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. + +| Default | Min | Max | +| --- | --- | --- | +| ERROR | | | + +--- + +### log_topics + +Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4294967295 | + +--- + +### looptime + +This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | | 9000 | + +--- + +### ltm_update_rate + +Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. + +| Default | Min | Max | +| --- | --- | --- | +| NORMAL | | | + +--- + +### mag_calibration_time + +Adjust how long time the Calibration of mag will last. + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 20 | 120 | + +--- + +### mag_declination + +Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -18000 | 18000 | + +--- + +### mag_hardware + +Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### mag_to_use + +Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1 | + +--- + +### maggain_x + +Magnetometer calibration X gain. If 1024, no calibration or calibration failed + +| Default | Min | Max | +| --- | --- | --- | +| 1024 | -32768 | 32767 | + +--- + +### maggain_y + +Magnetometer calibration Y gain. If 1024, no calibration or calibration failed + +| Default | Min | Max | +| --- | --- | --- | +| 1024 | -32768 | 32767 | + +--- + +### maggain_z + +Magnetometer calibration Z gain. If 1024, no calibration or calibration failed + +| Default | Min | Max | +| --- | --- | --- | +| 1024 | -32768 | 32767 | + +--- + +### magzero_x + +Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### magzero_y + +Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### magzero_z + +Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -32768 | 32767 | + +--- + +### manual_pitch_rate + +Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 100 | + +--- + +### manual_rc_expo + +Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] + +| Default | Min | Max | +| --- | --- | --- | +| 70 | 0 | 100 | + +--- + +### manual_rc_yaw_expo + +Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 100 | + +--- + +### manual_roll_rate + +Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 100 | + +--- + +### manual_yaw_rate + +Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 100 | + +--- + +### mavlink_ext_status_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 0 | 255 | + +--- + +### mavlink_extra1_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 255 | + +--- + +### mavlink_extra2_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 0 | 255 | + +--- + +### mavlink_extra3_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 255 | + +--- + +### mavlink_pos_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 0 | 255 | + +--- + +### mavlink_rc_chan_rate + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 255 | + +--- + +### mavlink_version + +Version of MAVLink to use + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 1 | 2 | + +--- + +### max_angle_inclination_pit + +Maximum inclination in level (angle) mode (PITCH axis). 100=10° + +| Default | Min | Max | +| --- | --- | --- | +| 300 | 100 | 900 | + +--- + +### max_angle_inclination_rll + +Maximum inclination in level (angle) mode (ROLL axis). 100=10° + +| Default | Min | Max | +| --- | --- | --- | +| 300 | 100 | 900 | + +--- + +### max_check + +These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. + +| Default | Min | Max | +| --- | --- | --- | +| 1900 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### max_throttle + +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 | Min | Max | +| --- | --- | --- | +| 1850 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### mc_cd_lpf_hz + +Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 0 | 200 | + +--- + +### mc_cd_pitch + +Multicopter Control Derivative gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 200 | + +--- + +### mc_cd_roll + +Multicopter Control Derivative gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 200 | + +--- + +### mc_cd_yaw + +Multicopter Control Derivative gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 200 | + +--- + +### mc_d_level + +Multicopter attitude stabilisation HORIZON transition point + +| Default | Min | Max | +| --- | --- | --- | +| 75 | 0 | 200 | + +--- + +### mc_d_pitch + +Multicopter rate stabilisation D-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 23 | 0 | 200 | + +--- + +### mc_d_roll + +Multicopter rate stabilisation D-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 23 | 0 | 200 | + +--- + +### mc_d_yaw + +Multicopter rate stabilisation D-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### mc_i_level + +Multicopter attitude stabilisation low-pass filter cutoff + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 0 | 200 | + +--- + +### mc_i_pitch + +Multicopter rate stabilisation I-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 0 | 200 | + +--- + +### mc_i_roll + +Multicopter rate stabilisation I-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 0 | 200 | + +--- + +### mc_i_yaw + +Multicopter rate stabilisation I-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 45 | 0 | 200 | + +--- + +### mc_iterm_relax + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| RP | | | + +--- + +### mc_iterm_relax_cutoff + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 1 | 100 | + +--- + +### mc_p_level + +Multicopter attitude stabilisation P-gain + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 200 | + +--- + +### mc_p_pitch + +Multicopter rate stabilisation P-gain for PITCH + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 200 | + +--- + +### mc_p_roll + +Multicopter rate stabilisation P-gain for ROLL + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 200 | + +--- + +### mc_p_yaw + +Multicopter rate stabilisation P-gain for YAW + +| Default | Min | Max | +| --- | --- | --- | +| 85 | 0 | 200 | + +--- + +### min_check + +These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. + +| Default | Min | Max | +| --- | --- | --- | +| 1100 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### min_command + +This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | 0 | PWM_RANGE_MAX | + +--- + +### mode_range_logic_operator + +Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. + +| Default | Min | Max | +| --- | --- | --- | +| OR | | | + +--- + +### model_preview_type + +ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. + +| Default | Min | Max | +| --- | --- | --- | +| -1 | -1 | 32767 | + +--- + +### moron_threshold + +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 | Min | Max | +| --- | --- | --- | +| 32 | | 128 | + +--- + +### motor_accel_time + +Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1000 | + +--- + +### motor_decel_time + +Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1000 | + +--- + +### motor_direction_inverted + +Use if you need to inverse yaw motor direction. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### motor_poles + +The number of motor poles. Required to compute motor RPM + +| Default | Min | Max | +| --- | --- | --- | +| 14 | 4 | 255 | + +--- + +### motor_pwm_protocol + +Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED + +| Default | Min | Max | +| --- | --- | --- | +| ONESHOT125 | | | + +--- + +### motor_pwm_rate + +Output frequency (in Hz) for motor pins. 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 | Min | Max | +| --- | --- | --- | +| 400 | 50 | 32000 | + +--- + +### msp_override_channels + +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 | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65535 | + +--- + +### name + +Craft name + +| Default | Min | Max | +| --- | --- | --- | +| _empty_ | | | + +--- + +### nav_auto_climb_rate + +Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 10 | 2000 | + +--- + +### nav_auto_speed + +Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] + +| Default | Min | Max | +| --- | --- | --- | +| 300 | 10 | 2000 | + +--- + +### nav_disarm_on_landing + +If set to ON, iNav disarms the FC after landing + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_emerg_landing_speed + +Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 100 | 2000 | + +--- + +### nav_extra_arming_safety + +If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### nav_fw_allow_manual_thr_increase + +Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_fw_bank_angle + +Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll + +| Default | Min | Max | +| --- | --- | --- | +| 35 | 5 | 80 | + +--- + +### nav_fw_climb_angle + +Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 5 | 80 | + +--- + +### nav_fw_control_smoothness + +How smoothly the autopilot controls the airplane to correct the navigation error + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 9 | + +--- + +### nav_fw_cruise_speed + +Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65535 | + +--- + +### nav_fw_cruise_thr + +Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) + +| Default | Min | Max | +| --- | --- | --- | +| 1400 | 1000 | 2000 | + +--- + +### nav_fw_cruise_yaw_rate + +Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 60 | + +--- + +### nav_fw_dive_angle + +Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 5 | 80 | + +--- + +### nav_fw_heading_p + +P gain of Heading Hold controller (Fixedwing) + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 255 | + +--- + +### nav_fw_land_dive_angle + +Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees + +| Default | Min | Max | +| --- | --- | --- | +| 2 | -20 | 20 | + +--- + +### nav_fw_launch_accel + +Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s + +| Default | Min | Max | +| --- | --- | --- | +| 1863 | 1000 | 20000 | + +--- + +### nav_fw_launch_climb_angle + +Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit + +| Default | Min | Max | +| --- | --- | --- | +| 18 | 5 | 45 | + +--- + +### nav_fw_launch_detect_time + +Time for which thresholds have to breached to consider launch happened [ms] + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 10 | 1000 | + +--- + +### nav_fw_launch_end_time + +Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] + +| Default | Min | Max | +| --- | --- | --- | +| 3000 | 0 | 5000 | + +--- + +### nav_fw_launch_idle_motor_delay + +Delay between raising throttle and motor starting at idle throttle (ms) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 60000 | + +--- + +### nav_fw_launch_idle_thr + +Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | 1000 | 2000 | + +--- + +### nav_fw_launch_max_altitude + +Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 60000 | + +--- + +### nav_fw_launch_max_angle + +Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] + +| Default | Min | Max | +| --- | --- | --- | +| 45 | 5 | 180 | + +--- + +### nav_fw_launch_min_time + +Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 60000 | + +--- + +### nav_fw_launch_motor_delay + +Delay between detected launch and launch sequence start and throttling up (ms) + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 0 | 5000 | + +--- + +### nav_fw_launch_spinup_time + +Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 1000 | + +--- + +### nav_fw_launch_thr + +Launch throttle - throttle to be set during launch sequence (pwm units) + +| Default | Min | Max | +| --- | --- | --- | +| 1700 | 1000 | 2000 | + +--- + +### nav_fw_launch_timeout + +Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) + +| Default | Min | Max | +| --- | --- | --- | +| 5000 | | 60000 | + +--- + +### nav_fw_launch_velocity + +Forward velocity threshold for swing-launch detection [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 300 | 100 | 10000 | + +--- + +### nav_fw_loiter_radius + +PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 7500 | 0 | 30000 | + +--- + +### nav_fw_max_thr + +Maximum throttle for flying wing in GPS assisted modes + +| Default | Min | Max | +| --- | --- | --- | +| 1700 | 1000 | 2000 | + +--- + +### nav_fw_min_thr + +Minimum throttle for flying wing in GPS assisted modes + +| Default | Min | Max | +| --- | --- | --- | +| 1200 | 1000 | 2000 | + +--- + +### nav_fw_pitch2thr + +Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 100 | + +--- + +### nav_fw_pitch2thr_smoothing + +How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh. + +| Default | Min | Max | +| --- | --- | --- | +| 6 | 0 | 9 | + +--- + +### nav_fw_pitch2thr_threshold + +Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees] + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 900 | + +--- + +### nav_fw_pos_hdg_d + +D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 255 | + +--- + +### nav_fw_pos_hdg_i + +I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 0 | 255 | + +--- + +### nav_fw_pos_hdg_p + +P gain of heading PID controller. (Fixedwing, rovers, boats) + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 0 | 255 | + +--- + +### nav_fw_pos_hdg_pidsum_limit + +Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) + +| Default | Min | Max | +| --- | --- | --- | +| 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | + +--- + +### nav_fw_pos_xy_d + +D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero + +| Default | Min | Max | +| --- | --- | --- | +| 8 | 0 | 255 | + +--- + +### nav_fw_pos_xy_i + +I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 255 | + +--- + +### nav_fw_pos_xy_p + +P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH + +| Default | Min | Max | +| --- | --- | --- | +| 75 | 0 | 255 | + +--- + +### nav_fw_pos_z_d + +D gain of altitude PID controller (Fixedwing) + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 255 | + +--- + +### nav_fw_pos_z_i + +I gain of altitude PID controller (Fixedwing) + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 255 | + +--- + +### nav_fw_pos_z_p + +P gain of altitude PID controller (Fixedwing) + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 255 | + +--- + +### nav_fw_yaw_deadband + +Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 90 | + +--- + +### nav_land_maxalt_vspd + +Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 200 | 100 | 2000 | + +--- + +### nav_land_minalt_vspd + +Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 50 | 500 | + +--- + +### nav_land_slowdown_maxalt + +Defines at what altitude the descent velocity should start to ramp down from `nav_land_maxalt_vspd` to `nav_land_minalt_vspd` during the RTH landing phase [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 2000 | 500 | 4000 | + +--- + +### nav_land_slowdown_minalt + +Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 50 | 1000 | + +--- + +### nav_manual_climb_rate + +Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] + +| Default | Min | Max | +| --- | --- | --- | +| 200 | 10 | 2000 | + +--- + +### nav_manual_speed + +Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 10 | 2000 | + +--- + +### nav_max_altitude + +Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 65000 | + +--- + +### nav_max_terrain_follow_alt + +Max allowed above the ground altitude for terrain following mode + +| Default | Min | Max | +| --- | --- | --- | +| 100 | | 1000 | + +--- + +### nav_mc_auto_disarm_delay + +Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s) + +| Default | Min | Max | +| --- | --- | --- | +| 2000 | 100 | 10000 | + +--- + +### nav_mc_bank_angle + +Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude + +| Default | Min | Max | +| --- | --- | --- | +| 30 | 15 | 45 | + +--- + +### nav_mc_braking_bank_angle + +max angle that MR is allowed to bank in BOOST mode + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 15 | 60 | + +--- + +### nav_mc_braking_boost_disengage_speed + +BOOST will be disabled when speed goes below this value + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 1000 | + +--- + +### nav_mc_braking_boost_factor + +acceleration factor for BOOST phase + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 200 | + +--- + +### nav_mc_braking_boost_speed_threshold + +BOOST can be enabled when speed is above this value + +| Default | Min | Max | +| --- | --- | --- | +| 150 | 100 | 1000 | + +--- + +### nav_mc_braking_boost_timeout + +how long in ms BOOST phase can happen + +| Default | Min | Max | +| --- | --- | --- | +| 750 | 0 | 5000 | + +--- + +### nav_mc_braking_disengage_speed + +braking is disabled when speed goes below this value + +| Default | Min | Max | +| --- | --- | --- | +| 75 | 0 | 1000 | + +--- + +### nav_mc_braking_speed_threshold + +min speed in cm/s above which braking can happen + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 1000 | + +--- + +### nav_mc_braking_timeout + +timeout in ms for braking + +| Default | Min | Max | +| --- | --- | --- | +| 2000 | 100 | 5000 | + +--- + +### nav_mc_heading_p + +P gain of Heading Hold controller (Multirotor) + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 255 | + +--- + +### nav_mc_hover_thr + +Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. + +| Default | Min | Max | +| --- | --- | --- | +| 1500 | 1000 | 2000 | + +--- + +### nav_mc_pos_deceleration_time + +Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting + +| Default | Min | Max | +| --- | --- | --- | +| 120 | 0 | 255 | + +--- + +### nav_mc_pos_expo + +Expo for PosHold control + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 255 | + +--- + +### nav_mc_pos_xy_p + +Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity + +| Default | Min | Max | +| --- | --- | --- | +| 65 | 0 | 255 | + +--- + +### nav_mc_pos_z_p + +P gain of altitude PID controller (Multirotor) + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 255 | + +--- + +### nav_mc_vel_xy_d + +D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 255 | + +--- + +### nav_mc_vel_xy_dterm_attenuation + +Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating. + +| Default | Min | Max | +| --- | --- | --- | +| 90 | 0 | 100 | + +--- + +### nav_mc_vel_xy_dterm_attenuation_end + +A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum + +| Default | Min | Max | +| --- | --- | --- | +| 60 | 0 | 100 | + +--- + +### nav_mc_vel_xy_dterm_attenuation_start + +A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 100 | + +--- + +### nav_mc_vel_xy_dterm_lpf_hz + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 2 | 0 | 100 | + +--- + +### nav_mc_vel_xy_ff + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 255 | + +--- + +### nav_mc_vel_xy_i + +I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 0 | 255 | + +--- + +### nav_mc_vel_xy_p + +P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations + +| Default | Min | Max | +| --- | --- | --- | +| 40 | 0 | 255 | + +--- + +### nav_mc_vel_z_d + +D gain of velocity PID controller + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 255 | + +--- + +### nav_mc_vel_z_i + +I gain of velocity PID controller + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 255 | + +--- + +### nav_mc_vel_z_p + +P gain of velocity PID controller + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 255 | + +--- + +### nav_mc_wp_slowdown + +When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### nav_min_rth_distance + +Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 0 | 5000 | + +--- + +### nav_overrides_motor_stop + +When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV + +| Default | Min | Max | +| --- | --- | --- | +| ALL_NAV | | | + +--- + +### nav_position_timeout + +If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 10 | + +--- + +### nav_rth_abort_threshold + +RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 50000 | | 65000 | + +--- + +### nav_rth_allow_landing + +If set to ON drone will land as a last phase of RTH. + +| Default | Min | Max | +| --- | --- | --- | +| ALWAYS | | | + +--- + +### nav_rth_alt_control_override + +If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the RTH climb phase using full pitch or roll stick held for > 1 second. RTH altitude is reset to the current altitude using pitch down stick. RTH CLIMB FIRST is overridden using right roll stick so craft turns and heads directly to home (CLIMB FIRST override only works for fixed wing) + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_rth_alt_mode + +Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details + +| Default | Min | Max | +| --- | --- | --- | +| AT_LEAST | | | + +--- + +### nav_rth_altitude + +Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | | 65000 | + +--- + +### nav_rth_climb_first + +If set to ON or ON_FW_SPIRAL aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF aircraft will turn and head home immediately climbing on the way. For a fixed wing ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate, turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor) + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### nav_rth_climb_ignore_emerg + +If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_rth_home_altitude + +Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 65000 | + +--- + +### nav_rth_tail_first + +If set to ON drone will return tail-first. Obviously meaningless for airplanes. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_use_fw_yaw_control + +Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_use_midthr_for_althold + +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 | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_user_control_mode + +Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. + +| Default | Min | Max | +| --- | --- | --- | +| ATTI | | | + +--- + +### nav_wp_load_on_boot + +If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### nav_wp_radius + +Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 10 | 10000 | + +--- + +### nav_wp_safe_distance + +First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. + +| Default | Min | Max | +| --- | --- | --- | +| 10000 | | 65000 | + +--- + +### opflow_hardware + +Selection of OPFLOW hardware. + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### opflow_scale + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 10.5 | 0 | 10000 | + +--- + +### osd_ahi_bordered + +Shows a border/corners around the AHI region (pixel OSD only) + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_ahi_height + +AHI height in pixels (pixel OSD only) + +| Default | Min | Max | +| --- | --- | --- | +| 162 | | 255 | + +--- + +### osd_ahi_max_pitch + +Max pitch, in degrees, for OSD artificial horizon + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 10 | 90 | + +--- + +### osd_ahi_reverse_roll + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_ahi_style + +Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. + +| Default | Min | Max | +| --- | --- | --- | +| DEFAULT | | | + +--- + +### osd_ahi_vertical_offset + +AHI vertical offset from center (pixel OSD only) + +| Default | Min | Max | +| --- | --- | --- | +| -18 | -128 | 127 | + +--- + +### osd_ahi_width + +AHI width in pixels (pixel OSD only) + +| Default | Min | Max | +| --- | --- | --- | +| 132 | | 255 | + +--- + +### osd_alt_alarm + +Value above which to make the OSD relative altitude indicator blink (meters) + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 0 | 10000 | + +--- + +### osd_baro_temp_alarm_max + +Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| 600 | -550 | 1250 | + +--- + +### osd_baro_temp_alarm_min + +Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| -200 | -550 | 1250 | + +--- + +### osd_camera_fov_h + +Horizontal field of view for the camera in degres + +| Default | Min | Max | +| --- | --- | --- | +| 135 | 60 | 150 | + +--- + +### osd_camera_fov_v + +Vertical field of view for the camera in degres + +| Default | Min | Max | +| --- | --- | --- | +| 85 | 30 | 120 | + +--- + +### osd_camera_uptilt + +Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -40 | 80 | + +--- + +### osd_coordinate_digits + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 9 | 8 | 11 | + +--- + +### osd_crosshairs_style + +To set the visual type for the crosshair + +| Default | Min | Max | +| --- | --- | --- | +| DEFAULT | | | + +--- + +### osd_crsf_lq_format + +To select LQ format + +| Default | Min | Max | +| --- | --- | --- | +| TYPE1 | | | + +--- + +### osd_current_alarm + +Value above which the OSD current consumption element will start blinking. Measured in full Amperes. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 255 | + +--- + +### osd_dist_alarm + +Value above which to make the OSD distance from home indicator blink (meters) + +| Default | Min | Max | +| --- | --- | --- | +| 1000 | 0 | 50000 | + +--- + +### osd_esc_temp_alarm_max + +Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| 900 | -550 | 1500 | + +--- + +### osd_esc_temp_alarm_min + +Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| -200 | -550 | 1500 | + +--- + +### osd_estimations_wind_compensation + +Use wind estimation for remaining flight time/distance estimation + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### osd_failsafe_switch_layout + +If enabled the OSD automatically switches to the first layout during failsafe + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_force_grid + +Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_gforce_alarm + +Value above which the OSD g force indicator will blink (g) + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 20 | + +--- + +### osd_gforce_axis_alarm_max + +Value above which the OSD axis g force indicators will blink (g) + +| Default | Min | Max | +| --- | --- | --- | +| 5 | -20 | 20 | + +--- + +### osd_gforce_axis_alarm_min + +Value under which the OSD axis g force indicators will blink (g) + +| Default | Min | Max | +| --- | --- | --- | +| -5 | -20 | 20 | + +--- + +### osd_home_position_arm_screen + +Should home position coordinates be displayed on the arming screen. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### osd_horizon_offset + +To vertically adjust the whole OSD and AHI and scrolling bars + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -2 | 2 | + +--- + +### osd_hud_homepoint + +To 3D-display the home point location in the hud + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_hud_homing + +To display little arrows around the crossair showing where the home point is in the hud + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_hud_margin_h + +Left and right margins for the hud area + +| Default | Min | Max | +| --- | --- | --- | +| 3 | 0 | 4 | + +--- + +### osd_hud_margin_v + +Top and bottom margins for the hud area + +| Default | Min | Max | +| --- | --- | --- | +| 3 | 1 | 3 | + +--- + +### osd_hud_radar_disp + +Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4 | + +--- + +### osd_hud_radar_nearest + +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 | Min | Max | +| --- | --- | --- | +| 0 | 0 | 4000 | + +--- + +### osd_hud_radar_range_max + +In meters, radar aircrafts further away than this will not be displayed in the hud + +| Default | Min | Max | +| --- | --- | --- | +| 4000 | 100 | 9990 | + +--- + +### osd_hud_radar_range_min + +In meters, radar aircrafts closer than this will not be displayed in the hud + +| Default | Min | Max | +| --- | --- | --- | +| 3 | 1 | 30 | + +--- + +### osd_hud_wp_disp + +How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 3 | + +--- + +### osd_imu_temp_alarm_max + +Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| 600 | -550 | 1250 | + +--- + +### osd_imu_temp_alarm_min + +Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) + +| Default | Min | Max | +| --- | --- | --- | +| -200 | -550 | 1250 | + +--- + +### osd_left_sidebar_scroll + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### osd_left_sidebar_scroll_step + +How many units each sidebar step represents. 0 means the default value for the scroll type. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 255 | + +--- + +### osd_link_quality_alarm + +LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50% + +| Default | Min | Max | +| --- | --- | --- | +| 70 | 0 | 100 | + +--- + +### osd_main_voltage_decimals + +Number of decimals for the battery voltages displayed in the OSD [1-2]. + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 2 | + +--- + +### osd_neg_alt_alarm + +Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters) + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 10000 | + +--- + +### osd_pan_servo_index + +Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 10 | + +--- + +### osd_pan_servo_pwm2centideg + +Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -36 | 36 | + +--- + +### osd_plus_code_digits + +Numer of plus code digits before shortening with `osd_plus_code_short`. Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm. + +| Default | Min | Max | +| --- | --- | --- | +| 11 | 10 | 13 | + +--- + +### osd_plus_code_short + +Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | | + +--- + +### osd_right_sidebar_scroll + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### osd_right_sidebar_scroll_step + +Same as left_sidebar_scroll_step, but for the right sidebar + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 255 | + +--- + +### osd_row_shiftdown + +Number of rows to shift the OSD display (increase if top rows are cut off) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 1 | + +--- + +### osd_rssi_alarm + +Value below which to make the OSD RSSI indicator blink + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 100 | + +--- + +### osd_rssi_dbm_alarm + +RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -130 | 0 | + +--- + +### osd_sidebar_height + +Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD) + +| Default | Min | Max | +| --- | --- | --- | +| 3 | 0 | 5 | + +--- + +### osd_sidebar_horizontal_offset + +Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -128 | 127 | + +--- + +### osd_sidebar_scroll_arrows + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_snr_alarm + +Value below which Crossfire SNR Alarm pops-up. (dB) + +| Default | Min | Max | +| --- | --- | --- | +| 4 | -20 | 10 | + +--- + +### osd_speed_source + +Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR + +| Default | Min | Max | +| --- | --- | --- | +| GROUND | | | + +--- + +### osd_stats_energy_unit + +Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) + +| Default | Min | Max | +| --- | --- | --- | +| MAH | | | + +--- + +### osd_stats_min_voltage_unit + +Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats. + +| Default | Min | Max | +| --- | --- | --- | +| BATTERY | | | + +--- + +### osd_telemetry + +To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST` + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### osd_temp_label_align + +Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` + +| Default | Min | Max | +| --- | --- | --- | +| LEFT | | | + +--- + +### osd_time_alarm + +Value above which to make the OSD flight time indicator blink (minutes) + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 0 | 600 | + +--- + +### osd_units + +IMPERIAL, METRIC, UK + +| Default | Min | Max | +| --- | --- | --- | +| METRIC | | | + +--- + +### osd_video_system + +Video system used. Possible values are `AUTO`, `PAL` and `NTSC` + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### pid_type + +Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### pidsum_limit + +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 | Min | Max | +| --- | --- | --- | +| 500 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | + +--- + +### pidsum_limit_yaw + +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 | Min | Max | +| --- | --- | --- | +| 350 | PID_SUM_LIMIT_MIN | PID_SUM_LIMIT_MAX | + +--- + +### pinio_box1 + +Mode assignment for PINIO#1 + +| Default | Min | Max | +| --- | --- | --- | +| `BOX_PERMANENT_ID_NONE` | 0 | 255 | + +--- + +### pinio_box2 + +Mode assignment for PINIO#1 + +| Default | Min | Max | +| --- | --- | --- | +| `BOX_PERMANENT_ID_NONE` | 0 | 255 | + +--- + +### pinio_box3 + +Mode assignment for PINIO#1 + +| Default | Min | Max | +| --- | --- | --- | +| `BOX_PERMANENT_ID_NONE` | 0 | 255 | + +--- + +### pinio_box4 + +Mode assignment for PINIO#1 + +| Default | Min | Max | +| --- | --- | --- | +| `BOX_PERMANENT_ID_NONE` | 0 | 255 | + +--- + +### pitch_rate + +Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 6 | 180 | + +--- + +### pitot_hardware + +Selection of pitot hardware. + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### pitot_lpf_milli_hz + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 350 | 0 | 10000 | + +--- + +### pitot_scale + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1.0 | 0 | 100 | + +--- + +### platform_type + +Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented + +| Default | Min | Max | +| --- | --- | --- | +| MULTIROTOR | | | + +--- + +### pos_hold_deadband + +Stick deadband in [r/c points], applied after r/c deadband and expo + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 2 | 250 | + +--- + +### prearm_timeout + +Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout. + +| Default | Min | Max | +| --- | --- | --- | +| 10000 | 0 | 10000 | + +--- + +### rangefinder_hardware + +Selection of rangefinder hardware. + +| Default | Min | Max | +| --- | --- | --- | +| NONE | | | + +--- + +### rangefinder_median_filter + +3-point median filtering for rangefinder readouts + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### rate_accel_limit_roll_pitch + +Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 500000 | + +--- + +### rate_accel_limit_yaw + +Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. + +| Default | Min | Max | +| --- | --- | --- | +| 10000 | | 500000 | + +--- + +### rc_expo + +Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) + +| Default | Min | Max | +| --- | --- | --- | +| 70 | 0 | 100 | + +--- + +### rc_filter_frequency + +RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 100 | + +--- + +### rc_yaw_expo + +Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 100 | + +--- + +### reboot_character + +Special character used to trigger reboot + +| Default | Min | Max | +| --- | --- | --- | +| 82 | 48 | 126 | + +--- + +### receiver_type + +Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL` + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | | | + +--- + +### report_cell_voltage + +S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### roll_rate + +Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 6 | 180 | + +--- + +### rpm_gyro_filter_enabled + +Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### rpm_gyro_harmonics + +Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 1 | 3 | + +--- + +### rpm_gyro_min_hz + +The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 30 | 200 | + +--- + +### rpm_gyro_q + +Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting + +| Default | Min | Max | +| --- | --- | --- | +| 500 | 1 | 3000 | + +--- + +### rssi_adc_channel + +ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | + +--- + +### rssi_channel + +RX channel containing the RSSI signal + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | MAX_SUPPORTED_RC_CHANNEL_COUNT | + +--- + +### rssi_max + +The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. + +| Default | Min | Max | +| --- | --- | --- | +| 100 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX | + +--- + +### rssi_min + +The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). + +| Default | Min | Max | +| --- | --- | --- | +| 0 | RSSI_VISIBLE_VALUE_MIN | RSSI_VISIBLE_VALUE_MAX | + +--- + +### rssi_source + +Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### rth_energy_margin + +Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 100 | + +--- + +### rx_max_usec + +Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. + +| Default | Min | Max | +| --- | --- | --- | +| 2115 | PWM_PULSE_MIN | PWM_PULSE_MAX | + +--- + +### rx_min_usec + +Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. + +| Default | Min | Max | +| --- | --- | --- | +| 885 | PWM_PULSE_MIN | PWM_PULSE_MAX | + +--- + +### rx_spi_id + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 0 | + +--- + +### rx_spi_protocol + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | | | + +--- + +### rx_spi_rf_channel_count + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 8 | + +--- + +### safehome_max_distance + +In order for a safehome to be used, it must be less than this distance (in cm) from the arming point. + +| Default | Min | Max | +| --- | --- | --- | +| 20000 | 0 | 65000 | + +--- + +### safehome_usage_mode + +Used to control when safehomes will be used. Possible values are `OFF`, `RTH` and `RTH_FS`. See [Safehome documentation](Safehomes.md#Safehome) for more information. + +| Default | Min | Max | +| --- | --- | --- | +| RTH | | | + +--- + +### sbus_sync_interval + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 3000 | 500 | 10000 | + +--- + +### sdcard_detect_inverted + +This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | | | + +--- + +### serialrx_halfduplex + +Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire. + +| Default | Min | Max | +| --- | --- | --- | +| AUTO | | | + +--- + +### serialrx_inverted + +Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### serialrx_provider + +When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | | | + +--- + +### servo_autotrim_rotation_limit + +Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`. + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 1 | 60 | + +--- + +### servo_center_pulse + +Servo midpoint + +| Default | Min | Max | +| --- | --- | --- | +| 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### servo_lpf_hz + +Selects the servo PWM output cutoff frequency. Value is in [Hz] + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 0 | 400 | + +--- + +### servo_protocol + +An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) + +| Default | Min | Max | +| --- | --- | --- | +| PWM | | | + +--- + +### servo_pwm_rate + +Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 50 | 498 | + +--- + +### setpoint_kalman_enabled + +Enable Kalman filter on the PID controller setpoint + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### setpoint_kalman_q + +Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 1 | 16000 | + +--- + +### setpoint_kalman_sharpness + +Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets + +| Default | Min | Max | +| --- | --- | --- | +| 100 | 1 | 16000 | + +--- + +### setpoint_kalman_w + +Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response + +| Default | Min | Max | +| --- | --- | --- | +| 4 | 1 | 40 | + +--- + +### sim_ground_station_number + +Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. + +| Default | Min | Max | +| --- | --- | --- | +| _empty_ | | | + +--- + +### sim_low_altitude + +Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. + +| Default | Min | Max | +| --- | --- | --- | +| -32767 | -32768 | 32767 | + +--- + +### sim_pin + +PIN code for the SIM module + +| Default | Min | Max | +| --- | --- | --- | +| 0000 | | | + +--- + +### sim_transmit_flags + +Bitmask specifying text message transmit condition flags for the SIM module. 1: continuous transmission, 2: continuous transmission in failsafe mode, 4: continuous transmission when GPS signal quality is low, 8: acceleration events, 16: continuous transmission when altitude is below `sim_low_altitude` + +| Default | Min | Max | +| --- | --- | --- | +| `SIM_TX_FLAG_FAILSAFE` | | 63 | + +--- + +### sim_transmit_interval + +Text message transmission interval in seconds for SIM module. Minimum value: 10 + +| Default | Min | Max | +| --- | --- | --- | +| 60 | SIM_MIN_TRANSMIT_INTERVAL | 65535 | + +--- + +### small_angle + +If the aircraft tilt angle exceed this value the copter will refuse to arm. + +| Default | Min | Max | +| --- | --- | --- | +| 25 | 0 | 180 | + +--- + +### smartport_fuel_unit + +S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] + +| Default | Min | Max | +| --- | --- | --- | +| MAH | | | + +--- + +### smartport_master_halfduplex + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### smartport_master_inverted + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### smith_predictor_delay + +Expected delay of the gyro signal. In milliseconds + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 8 | + +--- + +### smith_predictor_lpf_hz + +Cutoff frequency for the Smith Predictor Low Pass Filter + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 1 | 500 | + +--- + +### smith_predictor_strength + +The strength factor of a Smith Predictor of PID measurement. In percents + +| Default | Min | Max | +| --- | --- | --- | +| 0.5 | 0 | 1 | + +--- + +### spektrum_sat_bind + +0 = disabled. Used to bind the spektrum satellite to RX + +| Default | Min | Max | +| --- | --- | --- | +| `SPEKTRUM_SAT_BIND_DISABLED` | SPEKTRUM_SAT_BIND_DISABLED | SPEKTRUM_SAT_BIND_MAX | + +--- + +### srxl2_baud_fast + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### srxl2_unit_id + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 15 | + +--- + +### stats + +General switch of the statistics recording feature (a.k.a. odometer) + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### stats_total_dist + +Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 2147483647 | + +--- + +### stats_total_energy + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 2147483647 | + +--- + +### stats_total_time + +Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | | 2147483647 | + +--- + +### switch_disarm_delay + +Delay before disarming when requested by switch (ms) [0-1000] + +| Default | Min | Max | +| --- | --- | --- | +| 250 | 0 | 1000 | + +--- + +### telemetry_halfduplex + +S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### telemetry_inverted + +Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### telemetry_switch + +Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### thr_comp_weight + +Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) + +| Default | Min | Max | +| --- | --- | --- | +| 1 | 0 | 2 | + +--- + +### thr_expo + +Throttle exposition value + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + +### thr_mid + +Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. + +| Default | Min | Max | +| --- | --- | --- | +| 50 | 0 | 100 | + +--- + +### throttle_idle + +The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. + +| Default | Min | Max | +| --- | --- | --- | +| 15 | 0 | 30 | + +--- + +### throttle_scale + +Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% + +| Default | Min | Max | +| --- | --- | --- | +| 1.0 | 0 | 1 | + +--- + +### throttle_tilt_comp_str + +Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + +### tpa_breakpoint + +See tpa_rate. + +| Default | Min | Max | +| --- | --- | --- | +| 1500 | PWM_RANGE_MIN | PWM_RANGE_MAX | + +--- + +### tpa_rate + +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 | Min | Max | +| --- | --- | --- | +| 0 | 0 | 100 | + +--- + +### tri_unarmed_servo + +On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### turtle_mode_power_factor + +Turtle mode power factor + +| Default | Min | Max | +| --- | --- | --- | +| 55 | 0 | 100 | + +--- + +### tz_automatic_dst + +Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### tz_offset + +Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs + +| Default | Min | Max | +| --- | --- | --- | +| 0 | -1440 | 1440 | + +--- + +### vbat_adc_channel + +ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | ADC_CHN_NONE | ADC_CHN_MAX | + +--- + +### vbat_cell_detect_voltage + +Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units. + +| Default | Min | Max | +| --- | --- | --- | +| 425 | 100 | 500 | + +--- + +### vbat_max_cell_voltage + +Maximum voltage per cell in 0.01V units, default is 4.20V + +| Default | Min | Max | +| --- | --- | --- | +| 420 | 100 | 500 | + +--- + +### vbat_meter_type + +Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running + +| Default | Min | Max | +| --- | --- | --- | +| ADC | | | + +--- + +### vbat_min_cell_voltage + +Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) + +| Default | Min | Max | +| --- | --- | --- | +| 330 | 100 | 500 | + +--- + +### vbat_scale + +Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. + +| Default | Min | Max | +| --- | --- | --- | +| _target default_ | VBAT_SCALE_MIN | VBAT_SCALE_MAX | + +--- + +### vbat_warning_cell_voltage + +Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) + +| Default | Min | Max | +| --- | --- | --- | +| 350 | 100 | 500 | + +--- + +### vtx_band + +Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. + +| Default | Min | Max | +| --- | --- | --- | +| 4 | VTX_SETTINGS_NO_BAND | VTX_SETTINGS_MAX_BAND | + +--- + +### vtx_channel + +Channel to use within the configured `vtx_band`. Valid values are [1, 8]. + +| Default | Min | Max | +| --- | --- | --- | +| 1 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL | + +--- + +### vtx_halfduplex + +Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### vtx_low_power_disarm + +When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. + +| Default | Min | Max | +| --- | --- | --- | +| OFF | | | + +--- + +### vtx_max_power_override + +Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 10000 | + +--- + +### vtx_pit_mode_chan + +_// TODO_ + +| Default | Min | Max | +| --- | --- | --- | +| 1 | VTX_SETTINGS_MIN_CHANNEL | VTX_SETTINGS_MAX_CHANNEL | + +--- + +### vtx_power + +VTX RF power level to use. The exact number of mw depends on the VTX hardware. + +| Default | Min | Max | +| --- | --- | --- | +| 1 | VTX_SETTINGS_MIN_POWER | VTX_SETTINGS_MAX_POWER | + +--- + +### vtx_smartaudio_early_akk_workaround + +Enable workaround for early AKK SAudio-enabled VTX bug. + +| Default | Min | Max | +| --- | --- | --- | +| ON | | | + +--- + +### yaw_deadband + +These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. + +| Default | Min | Max | +| --- | --- | --- | +| 5 | 0 | 100 | + +--- + +### yaw_lpf_hz + +Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) + +| Default | Min | Max | +| --- | --- | --- | +| 0 | 0 | 200 | + +--- + +### yaw_rate + +Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. + +| Default | Min | Max | +| --- | --- | --- | +| 20 | 2 | 180 | + +--- -> Note: this table is autogenerated. Do not edit it manually. \ No newline at end of file diff --git a/src/utils/update_cli_docs.py b/src/utils/update_cli_docs.py index f685d908a8..0c72c6a759 100755 --- a/src/utils/update_cli_docs.py +++ b/src/utils/update_cli_docs.py @@ -38,7 +38,7 @@ 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): +def generate_md_from_yaml(settings_yaml): """Generate a sorted markdown table with description & default value for each setting""" params = {} @@ -84,20 +84,19 @@ def generate_md_table_from_yaml(settings_yaml): "max": member["max"] if "max" in member else "" } - # MD table header - md_table_lines = [ - "| Variable Name | Default Value | Min | Max | Description |\n", - "| ------------- | ------------- | --- | --- | ----------- |\n", - ] - - # Sort the settings by name and build the rows of the table + # Sort the settings by name and build the doc + output_lines = [] for param in sorted(params.items()): - md_table_lines.append("| {} | {} | {} | {} | {} |\n".format( - param[0], param[1]['default'], param[1]['min'], param[1]['max'], param[1]['description'] - )) + output_lines.extend([ + f"### {param[0]}\n\n", + f"{param[1]['description'] if param[1]['description'] else '_// TODO_'}\n\n", + "| Default | Min | Max |\n| --- | --- | --- |\n", + f"| {param[1]['default']} | {param[1]['min']} | {param[1]['max']} |\n\n", + "---\n\n" + ]) - # Return the assembled table - return md_table_lines + # Return the assembled doc body + return output_lines def write_settings_md(lines): """Write the contents of the CLI settings docs""" @@ -185,9 +184,9 @@ if __name__ == "__main__": defaults_match = check_defaults(settings_yaml) quit(0 if defaults_match else 1) - md_table_lines = generate_md_table_from_yaml(settings_yaml) - 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) + output_lines = generate_md_from_yaml(settings_yaml) + output_lines = [ + "# CLI Variable Reference\n\n", + "> Note: this document is autogenerated. Do not edit it manually.\n\n" + ] + output_lines + write_settings_md(output_lines) From e1303e3b40b1885c0bb0593acc13fe36e9883eae Mon Sep 17 00:00:00 2001 From: Roman Lut <11955117+RomanLut@users.noreply.github.com> Date: Tue, 25 May 2021 01:32:29 +0300 Subject: [PATCH 22/67] fixed mavlink rssi range --- src/main/telemetry/mavlink.c | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index b5725a19b2..1405bbcd47 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -497,8 +497,9 @@ void mavlinkSendRCChannelsAndRSSI(void) GET_CHANNEL_VALUE(6), // chan8_raw RC channel 8 value, in microseconds GET_CHANNEL_VALUE(7), - // rssi Receive signal strength indicator, 0: 0%, 255: 100% - scaleRange(getRSSI(), 0, 1023, 0, 255)); + // rssi Receive signal strength indicator, 0: 0%, 254: 100% + //https://github.com/mavlink/mavlink/issues/1027 + scaleRange(getRSSI(), 0, 1023, 0, 254)); #undef GET_CHANNEL_VALUE mavlinkSendMessage(); From 966c73d4f82c46bde1a05957d2e2d1f822ea37d4 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 26 May 2021 13:37:40 +0200 Subject: [PATCH 23/67] disable level trim when any stick is deflected --- src/main/flight/pid.c | 11 ++++++++--- 1 file changed, 8 insertions(+), 3 deletions(-) diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 1d682623ec..104776acf3 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1327,11 +1327,16 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs) */ pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR; - //Iterm should freeze when pitch stick is deflected + //Iterm should freeze when sticks are deflected + bool areSticksDeflected = false; + for (int stick = ROLL; stick <= YAW; stick++) { + areSticksDeflected = areSticksDeflected || + rxGetChannelValue(stick) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) || + rxGetChannelValue(stick) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband); + } if ( !IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) || - rxGetChannelValue(PITCH) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) || - rxGetChannelValue(PITCH) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband) || + areSticksDeflected || (!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE)) || navigationIsControllingAltitude() ) { From b7b32d8937a031aeea1243bf64be5d764c1bfc62 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 26 May 2021 22:48:16 +0200 Subject: [PATCH 24/67] docs --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 050ee8d4bc..cc17716fac 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -3894,7 +3894,7 @@ Shows a border/corners around the AHI region (pixel OSD only) ### osd_ahi_camera_uptilt_comp -When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. +When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD). | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 16d5f9dcdb..16e8923511 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -3183,7 +3183,7 @@ groups: min: -40 max: 80 - name: osd_ahi_camera_uptilt_comp - description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees and this setting set to `ON`, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees." + description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD)." default_value: OFF field: ahi_camera_uptilt_comp type: bool From 585e7da4b5d81efedf11461d83158380aae188c8 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Thu, 27 May 2021 08:29:46 +0200 Subject: [PATCH 25/67] rename operand --- docs/Programming Framework.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/docs/Programming Framework.md b/docs/Programming Framework.md index ca5cc65f7f..b6f2780870 100644 --- a/docs/Programming Framework.md +++ b/docs/Programming Framework.md @@ -81,7 +81,7 @@ IPF can be edited using INAV Configurator user interface, of via CLI | Operand Type | Name | Notes | |---- |---- |---- | | 0 | VALUE | Value derived from `value` field | -| 1 | RC_CHANNEL | `value` points to RC channel number, indexed from 1 | +| 1 | GET_RC_CHANNEL | `value` points to RC channel number, indexed from 1 | | 2 | FLIGHT | `value` points to flight parameter table | | 3 | FLIGHT_MODE | `value` points to flight modes table | | 4 | LC | `value` points to other logic condition ID | From c6fd5a79281b10f2d6abc258f2f50e2e6294db5c Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 7 Apr 2021 11:35:20 +0200 Subject: [PATCH 26/67] ignore roll --- src/main/flight/imu.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index 3401e3b00c..7373dc26b4 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -504,7 +504,7 @@ static float imuCalculateAccelerometerWeight(const float dT) float accWeight_RateIgnore = 1.0f; if (ARMING_FLAG(ARMED) && STATE(FIXED_WING_LEGACY) && imuConfig()->acc_ignore_rate) { - const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF)); + const float rotRateMagnitude = sqrtf(sq(imuMeasuredRotationBF.y) + sq(imuMeasuredRotationBF.z)); const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, IMU_CENTRIFUGAL_LPF, dT); if (imuConfig()->acc_ignore_slope) { From 78225f5b71198d8e684e22b0cf8c3b27f062a8dc Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 10 Apr 2021 22:37:41 +0200 Subject: [PATCH 27/67] =?UTF-8?q?=EF=BB=BFglide=20slope?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/main/io/osd.c | 16 ++++++++++++++++ src/main/io/osd.h | 1 + 2 files changed, 17 insertions(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0e6f9738b3..ada7c1619b 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1495,6 +1495,22 @@ static bool osdDrawSingleElement(uint8_t item) break; } + case OSD_GLIDE_SLOPE: + { + float sinkRate = -getEstimatedActualVelocity(Z); + float horizontalSpeed = gpsSol.groundSpeed; + float glideSlope = horizontalSpeed / sinkRate; + buff[0] = 'G'; + buff[1] = 'S'; + if (sinkRate > 0 && horizontalSpeed > 100) { + osdFormatCentiNumber(buff + 2, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); + } else { + buff[2] = buff[3] = buff[4] = '-'; + } + buff[5] = '\0'; + break; + } + case OSD_GPS_LAT: osdFormatCoordinate(buff, SYM_LAT, gpsSol.llh.lat); break; diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 38557f0cb5..751fca0eb0 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -231,6 +231,7 @@ typedef enum { OSD_PLIMIT_REMAINING_BURST_TIME, OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, OSD_PLIMIT_ACTIVE_POWER_LIMIT, + OSD_GLIDE_SLOPE, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 22ef795578f08976545dff1466b14fc26599223e Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 10 Apr 2021 23:00:17 +0200 Subject: [PATCH 28/67] filter glideslope, use airspeed if available --- src/main/io/osd.c | 19 ++++++++++++++++--- 1 file changed, 16 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ada7c1619b..15f981fc63 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1497,12 +1497,25 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_GLIDE_SLOPE: { + + #if defined(USE_PITOT) + float horizontalSpeed = sensors(SENSOR_PITOT) ? pitot.airSpeed : gpsSol.groundSpeed; + #else + float horizontalSpeed = gpsSol.groundSpeed; + #endif float sinkRate = -getEstimatedActualVelocity(Z); - float horizontalSpeed = gpsSol.groundSpeed; - float glideSlope = horizontalSpeed / sinkRate; + + float glideSlope; + static pt1Filter_t gsFilterState; + static timeUs_t gsUpdated = 0; + timeUs_t currentTimeUs = micros(); + timeDelta_t gsTimeDelta = cmpTimeUs(currentTimeUs, gsUpdated); + glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 1, gsTimeDelta * 1e-6f); + gsUpdated = currentTimeUs; + buff[0] = 'G'; buff[1] = 'S'; - if (sinkRate > 0 && horizontalSpeed > 100) { + if (glideSlope > 0 && horizontalSpeed > 100) { osdFormatCentiNumber(buff + 2, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); } else { buff[2] = buff[3] = buff[4] = '-'; From c7d0fee82141b796c732a2850049de5d781ad189 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 10 Apr 2021 23:02:31 +0200 Subject: [PATCH 29/67] position --- src/main/io/osd.c | 1 + 1 file changed, 1 insertion(+) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 15f981fc63..75cc6884e2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -2990,6 +2990,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); + osdLayoutsConfig->item_pos[0][OSD_GLIDE_SLOPE] = OSD_POS(23, 2); osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2); From 117f53a94abd48c4d00bfe82de691e7ab3e0425c Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Tue, 27 Apr 2021 14:31:20 +0200 Subject: [PATCH 30/67] =?UTF-8?q?=EF=BB=BFchange=20symbol?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- src/main/io/osd.c | 22 +++++++++------------- 1 file changed, 9 insertions(+), 13 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 75cc6884e2..977f86e6ee 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1495,7 +1495,7 @@ static bool osdDrawSingleElement(uint8_t item) break; } - case OSD_GLIDE_SLOPE: + case OSD_GLIDESLOPE: { #if defined(USE_PITOT) @@ -1505,22 +1505,18 @@ static bool osdDrawSingleElement(uint8_t item) #endif float sinkRate = -getEstimatedActualVelocity(Z); - float glideSlope; static pt1Filter_t gsFilterState; - static timeUs_t gsUpdated = 0; - timeUs_t currentTimeUs = micros(); - timeDelta_t gsTimeDelta = cmpTimeUs(currentTimeUs, gsUpdated); - glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 1, gsTimeDelta * 1e-6f); + static timeUs_t gsUpdatedTime; + float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, US2S(micros() - gsUpdatedTime)); gsUpdated = currentTimeUs; - buff[0] = 'G'; - buff[1] = 'S'; - if (glideSlope > 0 && horizontalSpeed > 100) { - osdFormatCentiNumber(buff + 2, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); + buff[0] = 0x77; // Use direction arrow as glideslope symbol + if (glideSlope > 0 && horizontalSpeed > 100 && glideSlope < 100) { + osdFormatCentiNumber(buff + 1, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); } else { - buff[2] = buff[3] = buff[4] = '-'; + buff[1] = buff[2] = buff[3] = '-'; } - buff[5] = '\0'; + buff[4] = '\0'; break; } @@ -2990,7 +2986,7 @@ void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig) osdLayoutsConfig->item_pos[0][OSD_MAIN_BATT_SAG_COMPENSATED_CELL_VOLTAGE] = OSD_POS(12, 1); osdLayoutsConfig->item_pos[0][OSD_GPS_SPEED] = OSD_POS(23, 1); osdLayoutsConfig->item_pos[0][OSD_3D_SPEED] = OSD_POS(23, 1); - osdLayoutsConfig->item_pos[0][OSD_GLIDE_SLOPE] = OSD_POS(23, 2); + osdLayoutsConfig->item_pos[0][OSD_GLIDESLOPE] = OSD_POS(23, 2); osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS] = OSD_POS(1, 2) | OSD_VISIBLE_FLAG; osdLayoutsConfig->item_pos[0][OSD_THROTTLE_POS_AUTO_THR] = OSD_POS(6, 2); From 7f78d5fd3d452ce1d10ae1144e3957f137491963 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 28 Apr 2021 10:51:52 +0200 Subject: [PATCH 31/67] add symbol --- src/main/drivers/osd_symbols.h | 2 +- src/main/io/osd.c | 11 +++++------ 2 files changed, 6 insertions(+), 7 deletions(-) diff --git a/src/main/drivers/osd_symbols.h b/src/main/drivers/osd_symbols.h index 62c6db4313..750ac0d8ec 100644 --- a/src/main/drivers/osd_symbols.h +++ b/src/main/drivers/osd_symbols.h @@ -109,7 +109,7 @@ #define SYM_AH_CH_CENTER 0x7E // 126 Crossair center -// 0x7F // 127 - +#define SYM_GLIDESLOPE 0x7F // 127 Glideslope #define SYM_AH_H_START 0x80 // 128 to 136 Horizontal AHI diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 977f86e6ee..f1a5940fa5 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1497,20 +1497,19 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_GLIDESLOPE: { - #if defined(USE_PITOT) float horizontalSpeed = sensors(SENSOR_PITOT) ? pitot.airSpeed : gpsSol.groundSpeed; #else float horizontalSpeed = gpsSol.groundSpeed; #endif float sinkRate = -getEstimatedActualVelocity(Z); - static pt1Filter_t gsFilterState; - static timeUs_t gsUpdatedTime; - float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, US2S(micros() - gsUpdatedTime)); - gsUpdated = currentTimeUs; + const timeUs_t currentTimeUs = millis(); + static timeUs_t gsUpdatedTimeUs; + float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, US2S(currentTimeUs - gsUpdatedTimeUs)); + gsUpdatedTimeUs = currentTimeUs; - buff[0] = 0x77; // Use direction arrow as glideslope symbol + buff[0] = SYM_GLIDESLOPE; // Use direction arrow as glideslope symbol if (glideSlope > 0 && horizontalSpeed > 100 && glideSlope < 100) { osdFormatCentiNumber(buff + 1, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); } else { From afff7223706e1cbc927b473f4c1b536898871a28 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Tue, 4 May 2021 21:16:36 +0200 Subject: [PATCH 32/67] small change --- src/main/io/osd.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f1a5940fa5..606526b7c2 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1511,7 +1511,7 @@ static bool osdDrawSingleElement(uint8_t item) buff[0] = SYM_GLIDESLOPE; // Use direction arrow as glideslope symbol if (glideSlope > 0 && horizontalSpeed > 100 && glideSlope < 100) { - osdFormatCentiNumber(buff + 1, (int16_t)(glideSlope * 100.0f), 0, 2, 0, 3); + osdFormatCentiNumber(buff + 1, glideSlope * 100, 0, 2, 0, 3); } else { buff[1] = buff[2] = buff[3] = '-'; } From 00500a138fa085af0cff295d4e1ae9defd8213bc Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 8 May 2021 23:38:19 +0200 Subject: [PATCH 33/67] build error --- src/main/io/osd.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/io/osd.h b/src/main/io/osd.h index 751fca0eb0..e1d22e1a7d 100644 --- a/src/main/io/osd.h +++ b/src/main/io/osd.h @@ -231,7 +231,7 @@ typedef enum { OSD_PLIMIT_REMAINING_BURST_TIME, OSD_PLIMIT_ACTIVE_CURRENT_LIMIT, OSD_PLIMIT_ACTIVE_POWER_LIMIT, - OSD_GLIDE_SLOPE, + OSD_GLIDESLOPE, OSD_ITEM_COUNT // MUST BE LAST } osd_items_e; From 933473ca29f221c8c516229d45348ec207d2150f Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 8 May 2021 23:42:06 +0200 Subject: [PATCH 34/67] don't use airspeed --- src/main/io/osd.c | 6 +----- 1 file changed, 1 insertion(+), 5 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 606526b7c2..b0d1abd574 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1497,11 +1497,7 @@ static bool osdDrawSingleElement(uint8_t item) case OSD_GLIDESLOPE: { - #if defined(USE_PITOT) - float horizontalSpeed = sensors(SENSOR_PITOT) ? pitot.airSpeed : gpsSol.groundSpeed; - #else - float horizontalSpeed = gpsSol.groundSpeed; - #endif + float horizontalSpeed = gpsSol.groundSpeed; float sinkRate = -getEstimatedActualVelocity(Z); static pt1Filter_t gsFilterState; const timeUs_t currentTimeUs = millis(); From 92a653a1f61b416007000e5d91ae472eab116ef4 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Mon, 10 May 2021 21:20:42 +0200 Subject: [PATCH 35/67] float comparison --- src/main/io/osd.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index b0d1abd574..400d8744f7 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1505,8 +1505,8 @@ static bool osdDrawSingleElement(uint8_t item) float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, US2S(currentTimeUs - gsUpdatedTimeUs)); gsUpdatedTimeUs = currentTimeUs; - buff[0] = SYM_GLIDESLOPE; // Use direction arrow as glideslope symbol - if (glideSlope > 0 && horizontalSpeed > 100 && glideSlope < 100) { + buff[0] = SYM_GLIDESLOPE; + if (glideSlope > 0.0f && glideSlope < 100.0f) { osdFormatCentiNumber(buff + 1, glideSlope * 100, 0, 2, 0, 3); } else { buff[1] = buff[2] = buff[3] = '-'; From d64e83e5fa1538586b2269b496463dc3e4169566 Mon Sep 17 00:00:00 2001 From: flywoo Date: Tue, 18 May 2021 17:11:59 +0800 Subject: [PATCH 36/67] Add new target FLYWOOF745 --- src/main/target/FLYWOOF745/CMakeLists.txt | 2 + src/main/target/FLYWOOF745/target.c | 45 ++++++ src/main/target/FLYWOOF745/target.h | 176 ++++++++++++++++++++++ 3 files changed, 223 insertions(+) create mode 100644 src/main/target/FLYWOOF745/CMakeLists.txt create mode 100644 src/main/target/FLYWOOF745/target.c create mode 100644 src/main/target/FLYWOOF745/target.h diff --git a/src/main/target/FLYWOOF745/CMakeLists.txt b/src/main/target/FLYWOOF745/CMakeLists.txt new file mode 100644 index 0000000000..7839c348b3 --- /dev/null +++ b/src/main/target/FLYWOOF745/CMakeLists.txt @@ -0,0 +1,2 @@ +target_stm32f745xg(FLYWOOF745) +target_stm32f745xg(FLYWOOF745NANO) diff --git a/src/main/target/FLYWOOF745/target.c b/src/main/target/FLYWOOF745/target.c new file mode 100644 index 0000000000..7512bff47b --- /dev/null +++ b/src/main/target/FLYWOOF745/target.c @@ -0,0 +1,45 @@ +/* + * This file is part of INAV. + * + * 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 +#include "drivers/io.h" +#include "drivers/pwm_mapping.h" +#include "drivers/timer.h" +#include "drivers/bus.h" + +const timerHardware_t timerHardware[] = { + DEF_TIM(TIM1, CH3, PE13, TIM_USE_PPM, 0, 1), // PPM, DMA2_ST6 + + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M1 , DMA1_ST7 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // M2 , DMA1_ST2 + DEF_TIM(TIM1, CH1, PE9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 2), // M3 , DMA2_ST2 + DEF_TIM(TIM1, CH2, PE11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // M4 , DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M5 , DMA2_ST7 + DEF_TIM(TIM5, CH4, PA3, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M6 , DMA1_ST1 + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M7 , DMA1_ST4 + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO | TIM_USE_MC_SERVO, 0, 0), // M8 , DMA1_ST5 + DEF_TIM(TIM4, CH1, PD12, TIM_USE_LED, 0, 0), // LED_STRIP, DMA1_ST0 +}; + +const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]); diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h new file mode 100644 index 0000000000..ddf5690b2d --- /dev/null +++ b/src/main/target/FLYWOOF745/target.h @@ -0,0 +1,176 @@ +/* + * This file is part of INAV. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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. + * + * Cleanflight and Betaflight are distributed in the hope that they + * 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 software. + * + * If not, see . + */ + +#pragma once + +#ifdef FLYWOOF745 +#define TARGET_BOARD_IDENTIFIER "FWF7" +#define USBD_PRODUCT_STRING "FLYWOOF745" +#else +#define TARGET_BOARD_IDENTIFIER "FW7N" +#define USBD_PRODUCT_STRING "FLYWOOF745NANO" +#endif + +#define LED0 PA2// + +#define BEEPER PD15// +#define BEEPER_INVERTED + +#define USE_DSHOT +#define USE_ESC_SENSOR + +#define USE_MPU_DATA_READY_SIGNAL +#define USE_EXTI + +#define USE_IMU_MPU6000 +#define IMU_MPU6000_ALIGN CW270_DEG// +#define GYRO_INT_EXTI PE1// +#define MPU6000_CS_PIN SPI4_NSS_PIN// +#define MPU6000_SPI_BUS BUS_SPI4// + + +#define USB_IO +#define USE_VCP +#define VBUS_SENSING_ENABLED +#define VBUS_SENSING_PIN PA8// + +#define USE_UART1 +#define UART1_TX_PIN PA9// +#define UART1_RX_PIN PA10// + +#define USE_UART2 +#define UART2_TX_PIN PD5// +#define UART2_RX_PIN PD6// + +#define USE_UART3 + +#ifdef FLYWOOF745 +#define UART3_TX_PIN PB10// +#define UART3_RX_PIN PB11// +#else +#define UART3_TX_PIN PD8// +#define UART3_RX_PIN PD9// +#endif + +#define USE_UART4 +#define UART4_TX_PIN PA0// +#define UART4_RX_PIN PA1// + +#define USE_UART5 +#define UART5_TX_PIN PC12// +#define UART5_RX_PIN PD2// + +#define USE_UART6 +#define UART6_TX_PIN PC6// +#define UART6_RX_PIN PC7// + +#define USE_UART7 +#define UART7_TX_PIN PE8// +#define UART7_RX_PIN PE7// + +#define SERIAL_PORT_COUNT 8 //VCP,UART1,UART2,UART3,UART4,UART5,UART6,UART7 + +#define USE_SPI +#define USE_SPI_DEVICE_1 //FLASH +#define USE_SPI_DEVICE_2 //OSD +#define USE_SPI_DEVICE_4 //ICM20689 + +#define SPI1_NSS_PIN PA4// +#define SPI1_SCK_PIN PA5// +#define SPI1_MISO_PIN PA6// +#define SPI1_MOSI_PIN PA7// + +#define SPI2_NSS_PIN PB12// +#define SPI2_SCK_PIN PB13/// +#define SPI2_MISO_PIN PB14// +#define SPI2_MOSI_PIN PB15// + +#define SPI4_NSS_PIN PE4// +#define SPI4_SCK_PIN PE2// +#define SPI4_MISO_PIN PE5// +#define SPI4_MOSI_PIN PE6// + +#define USE_OSD + +#define USE_MAX7456 +#define MAX7456_SPI_BUS BUS_SPI2 +#define MAX7456_CS_PIN SPI2_NSS_PIN + +#define M25P16_CS_PIN SPI1_NSS_PIN +#define M25P16_SPI_BUS BUS_SPI1 +#define USE_FLASHFS +#define USE_FLASH_M25P16 +#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 + +#ifdef FLYWOOF745NANO +#define USE_I2C_DEVICE_2 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 +#endif +#define USE_BARO +#define USE_BARO_BMP280 +#define BARO_I2C_BUS BUS_I2C1 + +#define USE_MAG +#define MAG_I2C_BUS BUS_I2C1 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_MAG_MAG3110 +#define USE_MAG_IST8310 +#define USE_MAG_IST8308 +#define USE_MAG_LIS3MDL + +#define TEMPERATURE_I2C_BUS BUS_I2C1 + +#define RANGEFINDER_I2C_BUS BUS_I2C1 + +#define USE_ADC +#define ADC_CHANNEL_1_PIN PC2// +#define ADC_CHANNEL_2_PIN PC3// +#define ADC_CHANNEL_3_PIN PC5// + +#define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 +#define VBAT_ADC_CHANNEL ADC_CHN_2 +#define RSSI_ADC_CHANNEL ADC_CHN_3 + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_VBAT | FEATURE_BLACKBOX) +#define DEFAULT_RX_TYPE RX_TYPE_SERIAL +#define SERIALRX_UART SERIAL_PORT_USART1 +#define SERIALRX_PROVIDER SERIALRX_SBUS + +#define USE_LED_STRIP +#define WS2811_PIN PD12 // //TIM4_CH1 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff + +#define MAX_PWM_OUTPUT_PORTS 8 From 80c9c9c58b5ab32f8e4444153dd54b2996cb80e0 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 29 May 2021 23:46:14 +0200 Subject: [PATCH 37/67] change max gains to 300 and min rate to 40dps (10 dps on yaw) --- src/main/fc/settings.yaml | 6 +++--- src/main/flight/pid_autotune.c | 2 +- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 16e8923511..5c102ff736 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -182,12 +182,12 @@ tables: constants: RPYL_PID_MIN: 0 - RPYL_PID_MAX: 200 + RPYL_PID_MAX: 300 MANUAL_RATE_MIN: 0 MANUAL_RATE_MAX: 100 - ROLL_PITCH_RATE_MIN: 6 + ROLL_PITCH_RATE_MIN: 4 ROLL_PITCH_RATE_MAX: 180 groups: @@ -1289,7 +1289,7 @@ groups: 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: 2 + min: 1 max: 180 - name: manual_rc_expo description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]" diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index 9679e736e2..91e8682634 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -47,7 +47,7 @@ #include "flight/pid.h" #define AUTOTUNE_FIXED_WING_MIN_FF 10 -#define AUTOTUNE_FIXED_WING_MAX_FF 200 +#define AUTOTUNE_FIXED_WING_MAX_FF 300 #define AUTOTUNE_FIXED_WING_MIN_ROLL_PITCH_RATE 40 #define AUTOTUNE_FIXED_WING_MIN_YAW_RATE 10 #define AUTOTUNE_FIXED_WING_MAX_RATE 720 From 82639070d8233e4dc4c8130dafb7ce23eacb7dbc Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sun, 30 May 2021 10:23:53 +0200 Subject: [PATCH 38/67] fix time scale --- src/main/io/osd.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 400d8744f7..5030365368 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1500,14 +1500,14 @@ static bool osdDrawSingleElement(uint8_t item) float horizontalSpeed = gpsSol.groundSpeed; float sinkRate = -getEstimatedActualVelocity(Z); static pt1Filter_t gsFilterState; - const timeUs_t currentTimeUs = millis(); - static timeUs_t gsUpdatedTimeUs; - float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, US2S(currentTimeUs - gsUpdatedTimeUs)); - gsUpdatedTimeUs = currentTimeUs; + const timeMs_t currentTimeMs = millis(); + static timeMs_t gsUpdatedTimeMs; + float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); + gsUpdatedTimeMs = currentTimeMs; buff[0] = SYM_GLIDESLOPE; if (glideSlope > 0.0f && glideSlope < 100.0f) { - osdFormatCentiNumber(buff + 1, glideSlope * 100, 0, 2, 0, 3); + osdFormatCentiNumber(buff + 1, glideSlope * 100.0f, 0, 2, 0, 3); } else { buff[1] = buff[2] = buff[3] = '-'; } From 7e070f3a11659f76fc41a9d32e270f857a5a4e2c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Niccol=C3=B2=20Maggioni?= Date: Mon, 31 May 2021 01:25:44 +0200 Subject: [PATCH 39/67] Fix Cruise mode MSP box active check --- src/main/fc/fc_msp_box.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 5ec8491e52..058aa6b4cf 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -356,7 +356,7 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE)), BOXNAVALTHOLD); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_POSHOLD_MODE)), BOXNAVPOSHOLD); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)), BOXNAVCOURSEHOLD); - CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) && IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE)), BOXNAVCRUISE); + CHECK_ACTIVE_BOX((IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) && IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE))), BOXNAVCRUISE); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_RTH_MODE)), BOXNAVRTH); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_WP_MODE)), BOXNAVWP); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)), BOXAIRMODE); From 900261c75184c98dc01dcdd1b871bce888f3df95 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Mon, 31 May 2021 08:43:25 +0200 Subject: [PATCH 40/67] Correct assign sensors to exposed bus --- src/main/target/FLYWOOF745/target.h | 52 ++++++++++++++++++----------- 1 file changed, 32 insertions(+), 20 deletions(-) diff --git a/src/main/target/FLYWOOF745/target.h b/src/main/target/FLYWOOF745/target.h index ddf5690b2d..be57e83f96 100644 --- a/src/main/target/FLYWOOF745/target.h +++ b/src/main/target/FLYWOOF745/target.h @@ -92,20 +92,20 @@ #define USE_SPI_DEVICE_2 //OSD #define USE_SPI_DEVICE_4 //ICM20689 -#define SPI1_NSS_PIN PA4// -#define SPI1_SCK_PIN PA5// -#define SPI1_MISO_PIN PA6// -#define SPI1_MOSI_PIN PA7// +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 -#define SPI2_NSS_PIN PB12// -#define SPI2_SCK_PIN PB13/// -#define SPI2_MISO_PIN PB14// -#define SPI2_MOSI_PIN PB15// +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 -#define SPI4_NSS_PIN PE4// -#define SPI4_SCK_PIN PE2// -#define SPI4_MISO_PIN PE5// -#define SPI4_MOSI_PIN PE6// +#define SPI4_NSS_PIN PE4 +#define SPI4_SCK_PIN PE2 +#define SPI4_MISO_PIN PE5 +#define SPI4_MOSI_PIN PE6 #define USE_OSD @@ -120,6 +120,7 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT #define USE_I2C + #define USE_I2C_DEVICE_1 #define I2C1_SCL PB6 #define I2C1_SDA PB7 @@ -128,13 +129,28 @@ #define USE_I2C_DEVICE_2 #define I2C2_SCL PB10 #define I2C2_SDA PB11 + +//External I2C bus is different than internal one +#define MAG_I2C_BUS BUS_I2C2 +#define TEMPERATURE_I2C_BUS BUS_I2C2 +#define RANGEFINDER_I2C_BUS BUS_I2C2 +#define DEFAULT_I2C_BUS BUS_I2C2 + +#else + +//External I2C bus is the same as interal one +#define MAG_I2C_BUS BUS_I2C1 +#define TEMPERATURE_I2C_BUS BUS_I2C1 +#define RANGEFINDER_I2C_BUS BUS_I2C1 +#define DEFAULT_I2C_BUS BUS_I2C1 + #endif + #define USE_BARO #define USE_BARO_BMP280 #define BARO_I2C_BUS BUS_I2C1 #define USE_MAG -#define MAG_I2C_BUS BUS_I2C1 #define USE_MAG_HMC5883 #define USE_MAG_QMC5883 #define USE_MAG_MAG3110 @@ -142,14 +158,10 @@ #define USE_MAG_IST8308 #define USE_MAG_LIS3MDL -#define TEMPERATURE_I2C_BUS BUS_I2C1 - -#define RANGEFINDER_I2C_BUS BUS_I2C1 - #define USE_ADC -#define ADC_CHANNEL_1_PIN PC2// -#define ADC_CHANNEL_2_PIN PC3// -#define ADC_CHANNEL_3_PIN PC5// +#define ADC_CHANNEL_1_PIN PC2 +#define ADC_CHANNEL_2_PIN PC3 +#define ADC_CHANNEL_3_PIN PC5 #define CURRENT_METER_ADC_CHANNEL ADC_CHN_1 #define VBAT_ADC_CHANNEL ADC_CHN_2 From 802f8e1ab72b1b59c9550a27f181db5ca4988563 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 31 May 2021 16:29:05 +0200 Subject: [PATCH 41/67] Fix CHECK_ACTIVE_BOX/IS_ENABLED --- src/main/fc/fc_msp_box.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/fc/fc_msp_box.c b/src/main/fc/fc_msp_box.c index 058aa6b4cf..9b0a90e54b 100644 --- a/src/main/fc/fc_msp_box.c +++ b/src/main/fc/fc_msp_box.c @@ -326,7 +326,7 @@ void initActiveBoxIds(void) #endif } -#define IS_ENABLED(mask) (mask == 0 ? 0 : 1) +#define IS_ENABLED(mask) ((mask) == 0 ? 0 : 1) #define CHECK_ACTIVE_BOX(condition, index) do { if (IS_ENABLED(condition)) { activeBoxes[index] = 1; } } while(0) void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) @@ -356,7 +356,7 @@ void packBoxModeFlags(boxBitmask_t * mspBoxModeFlags) CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE)), BOXNAVALTHOLD); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_POSHOLD_MODE)), BOXNAVPOSHOLD); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)), BOXNAVCOURSEHOLD); - CHECK_ACTIVE_BOX((IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) && IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE))), BOXNAVCRUISE); + CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_COURSE_HOLD_MODE)) && IS_ENABLED(FLIGHT_MODE(NAV_ALTHOLD_MODE)), BOXNAVCRUISE); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_RTH_MODE)), BOXNAVRTH); CHECK_ACTIVE_BOX(IS_ENABLED(FLIGHT_MODE(NAV_WP_MODE)), BOXNAVWP); CHECK_ACTIVE_BOX(IS_ENABLED(IS_RC_MODE_ACTIVE(BOXAIRMODE)), BOXAIRMODE); From 83bf9965e4d1c702334772a25c0c5564721444f7 Mon Sep 17 00:00:00 2001 From: Harry Phillips Date: Mon, 31 May 2021 15:38:55 +0100 Subject: [PATCH 42/67] Set MAVLink v1 flag correctly (#7047) * Set MAVLink v1 flag correctly * Only create 1 MAVLink COMM buffer as we only ever use 1 --- src/main/rx/mavlink.h | 1 + src/main/telemetry/mavlink.c | 10 +++++++++- 2 files changed, 10 insertions(+), 1 deletion(-) diff --git a/src/main/rx/mavlink.h b/src/main/rx/mavlink.h index a54e16d76d..951b0eba10 100644 --- a/src/main/rx/mavlink.h +++ b/src/main/rx/mavlink.h @@ -19,6 +19,7 @@ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-function" +#define MAVLINK_COMM_NUM_BUFFERS 1 #include "common/mavlink.h" #pragma GCC diagnostic pop diff --git a/src/main/telemetry/mavlink.c b/src/main/telemetry/mavlink.c index 2b1c85e8eb..8b924e53eb 100644 --- a/src/main/telemetry/mavlink.c +++ b/src/main/telemetry/mavlink.c @@ -89,6 +89,7 @@ #pragma GCC diagnostic push #pragma GCC diagnostic ignored "-Wunused-function" +#define MAVLINK_COMM_NUM_BUFFERS 1 #include "common/mavlink.h" #pragma GCC diagnostic pop @@ -326,7 +327,14 @@ void checkMAVLinkTelemetryState(void) static void mavlinkSendMessage(void) { uint8_t mavBuffer[MAVLINK_MAX_PACKET_LEN]; - if (telemetryConfig()->mavlink.version == 1) mavSendMsg.magic = MAVLINK_STX_MAVLINK1; + + mavlink_status_t* chan_state = mavlink_get_channel_status(MAVLINK_COMM_0); + if (telemetryConfig()->mavlink.version == 1) { + chan_state->flags |= MAVLINK_STATUS_FLAG_OUT_MAVLINK1; + } else { + chan_state->flags &= ~MAVLINK_STATUS_FLAG_OUT_MAVLINK1; + } + int msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavSendMsg); for (int i = 0; i < msgLength; i++) { From d2f0b7813fc03c19014070d4c6b02b5efd12954c Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Tue, 1 Jun 2021 13:55:15 +0200 Subject: [PATCH 43/67] cleanup --- src/main/flight/pid_autotune.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index 91e8682634..5dcc40a12f 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -53,8 +53,8 @@ #define AUTOTUNE_FIXED_WING_MAX_RATE 720 #define AUTOTUNE_FIXED_WING_CONVERGENCE_RATE 10 #define AUTOTUNE_FIXED_WING_SAMPLE_INTERVAL 20 // ms -#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use averagea over the last 20 seconds -#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds +#define AUTOTUNE_FIXED_WING_SAMPLES 1000 // Use average over the last 20 seconds of hard maneuvers +#define AUTOTUNE_FIXED_WING_MIN_SAMPLES 250 // Start updating tune after 5 seconds of hard maneuvers PG_REGISTER_WITH_RESET_TEMPLATE(pidAutotuneConfig_t, pidAutotuneConfig, PG_PID_AUTOTUNE_CONFIG, 2); From 7abd6e1eda35421672c15c38f492b0cffad93cd9 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Tue, 1 Jun 2021 14:06:23 +0200 Subject: [PATCH 44/67] docs --- docs/Settings.md | 66 ++++++++++++++++++++++++------------------------ 1 file changed, 33 insertions(+), 33 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index cc17716fac..407f59bab6 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1138,7 +1138,7 @@ Fixed-wing attitude stabilisation HORIZON transition point | Default | Min | Max | | --- | --- | --- | -| 75 | 0 | 200 | +| 75 | 0 | 300 | --- @@ -1148,7 +1148,7 @@ Fixed wing rate stabilisation D-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 200 | +| 0 | 0 | 300 | --- @@ -1158,7 +1158,7 @@ Fixed wing rate stabilisation D-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 200 | +| 0 | 0 | 300 | --- @@ -1168,7 +1168,7 @@ Fixed wing rate stabilisation D-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 200 | +| 0 | 0 | 300 | --- @@ -1178,7 +1178,7 @@ Fixed-wing rate stabilisation FF-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 50 | 0 | 200 | +| 50 | 0 | 300 | --- @@ -1188,7 +1188,7 @@ Fixed-wing rate stabilisation FF-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 50 | 0 | 200 | +| 50 | 0 | 300 | --- @@ -1198,7 +1198,7 @@ Fixed-wing rate stabilisation FF-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 200 | +| 60 | 0 | 300 | --- @@ -1208,7 +1208,7 @@ Fixed-wing attitude stabilisation low-pass filter cutoff | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 200 | +| 5 | 0 | 300 | --- @@ -1218,7 +1218,7 @@ Fixed-wing rate stabilisation I-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 7 | 0 | 200 | +| 7 | 0 | 300 | --- @@ -1228,7 +1228,7 @@ Fixed-wing rate stabilisation I-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 7 | 0 | 200 | +| 7 | 0 | 300 | --- @@ -1238,7 +1238,7 @@ Fixed-wing rate stabilisation I-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 10 | 0 | 200 | +| 10 | 0 | 300 | --- @@ -1318,7 +1318,7 @@ Fixed-wing attitude stabilisation P-gain | Default | Min | Max | | --- | --- | --- | -| 20 | 0 | 200 | +| 20 | 0 | 300 | --- @@ -1328,7 +1328,7 @@ Fixed-wing rate stabilisation P-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 200 | +| 5 | 0 | 300 | --- @@ -1338,7 +1338,7 @@ Fixed-wing rate stabilisation P-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 200 | +| 5 | 0 | 300 | --- @@ -1348,7 +1348,7 @@ Fixed-wing rate stabilisation P-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 6 | 0 | 200 | +| 6 | 0 | 300 | --- @@ -2568,7 +2568,7 @@ Multicopter Control Derivative gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 200 | +| 60 | 0 | 300 | --- @@ -2578,7 +2578,7 @@ Multicopter Control Derivative gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 200 | +| 60 | 0 | 300 | --- @@ -2588,7 +2588,7 @@ Multicopter Control Derivative gain for YAW | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 200 | +| 60 | 0 | 300 | --- @@ -2598,7 +2598,7 @@ Multicopter attitude stabilisation HORIZON transition point | Default | Min | Max | | --- | --- | --- | -| 75 | 0 | 200 | +| 75 | 0 | 300 | --- @@ -2608,7 +2608,7 @@ Multicopter rate stabilisation D-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 23 | 0 | 200 | +| 23 | 0 | 300 | --- @@ -2618,7 +2618,7 @@ Multicopter rate stabilisation D-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 23 | 0 | 200 | +| 23 | 0 | 300 | --- @@ -2628,7 +2628,7 @@ Multicopter rate stabilisation D-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 200 | +| 0 | 0 | 300 | --- @@ -2638,7 +2638,7 @@ Multicopter attitude stabilisation low-pass filter cutoff | Default | Min | Max | | --- | --- | --- | -| 15 | 0 | 200 | +| 15 | 0 | 300 | --- @@ -2648,7 +2648,7 @@ Multicopter rate stabilisation I-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 30 | 0 | 200 | +| 30 | 0 | 300 | --- @@ -2658,7 +2658,7 @@ Multicopter rate stabilisation I-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 30 | 0 | 200 | +| 30 | 0 | 300 | --- @@ -2668,7 +2668,7 @@ Multicopter rate stabilisation I-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 45 | 0 | 200 | +| 45 | 0 | 300 | --- @@ -2698,7 +2698,7 @@ Multicopter attitude stabilisation P-gain | Default | Min | Max | | --- | --- | --- | -| 20 | 0 | 200 | +| 20 | 0 | 300 | --- @@ -2708,7 +2708,7 @@ Multicopter rate stabilisation P-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 40 | 0 | 200 | +| 40 | 0 | 300 | --- @@ -2718,7 +2718,7 @@ Multicopter rate stabilisation P-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 40 | 0 | 200 | +| 40 | 0 | 300 | --- @@ -2728,7 +2728,7 @@ Multicopter rate stabilisation P-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 85 | 0 | 200 | +| 85 | 0 | 300 | --- @@ -4618,7 +4618,7 @@ Defines rotation rate on PITCH axis that UAV will try to archive on max. stick d | Default | Min | Max | | --- | --- | --- | -| 20 | 6 | 180 | +| 20 | 4 | 180 | --- @@ -4788,7 +4788,7 @@ Defines rotation rate on ROLL axis that UAV will try to archive on max. stick de | Default | Min | Max | | --- | --- | --- | -| 20 | 6 | 180 | +| 20 | 4 | 180 | --- @@ -5628,7 +5628,7 @@ Defines rotation rate on YAW axis that UAV will try to archive on max. stick def | Default | Min | Max | | --- | --- | --- | -| 20 | 2 | 180 | +| 20 | 1 | 180 | --- From 1deed7c7d20e6882b38137d78e864bbef01cfe01 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Tue, 1 Jun 2021 14:12:55 +0200 Subject: [PATCH 45/67] default 90% target deflection --- docs/Settings.md | 2 +- src/main/fc/settings.yaml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 407f59bab6..54abd73e1b 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1098,7 +1098,7 @@ The target percentage of maximum mixer output used for determining the rates in | Default | Min | Max | | --- | --- | --- | -| 80 | 50 | 100 | +| 90 | 50 | 100 | --- diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 5c102ff736..3ebfe2bfbc 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2161,7 +2161,7 @@ groups: type: uint8_t - name: fw_autotune_max_rate_deflection description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`." - default_value: 80 + default_value: 90 field: fw_max_rate_deflection min: 50 max: 100 From db8bad2f6aae377ba1b4a3d39ae122d7affc41ce Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 2 Jun 2021 20:30:33 +0200 Subject: [PATCH 46/67] 255 max gains --- 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 3ebfe2bfbc..4995b9ce34 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -182,7 +182,7 @@ tables: constants: RPYL_PID_MIN: 0 - RPYL_PID_MAX: 300 + RPYL_PID_MAX: 255 MANUAL_RATE_MIN: 0 MANUAL_RATE_MAX: 100 From 0aec5ca0f1bb25c776c9b73e46fc74e00931aee1 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 2 Jun 2021 20:32:10 +0200 Subject: [PATCH 47/67] docs update --- docs/Settings.md | 60 ++++++++++++++++++++++++------------------------ 1 file changed, 30 insertions(+), 30 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 54abd73e1b..4f5d6487f7 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1138,7 +1138,7 @@ Fixed-wing attitude stabilisation HORIZON transition point | Default | Min | Max | | --- | --- | --- | -| 75 | 0 | 300 | +| 75 | 0 | 255 | --- @@ -1148,7 +1148,7 @@ Fixed wing rate stabilisation D-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 300 | +| 0 | 0 | 255 | --- @@ -1158,7 +1158,7 @@ Fixed wing rate stabilisation D-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 300 | +| 0 | 0 | 255 | --- @@ -1168,7 +1168,7 @@ Fixed wing rate stabilisation D-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 300 | +| 0 | 0 | 255 | --- @@ -1178,7 +1178,7 @@ Fixed-wing rate stabilisation FF-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 50 | 0 | 300 | +| 50 | 0 | 255 | --- @@ -1188,7 +1188,7 @@ Fixed-wing rate stabilisation FF-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 50 | 0 | 300 | +| 50 | 0 | 255 | --- @@ -1198,7 +1198,7 @@ Fixed-wing rate stabilisation FF-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 300 | +| 60 | 0 | 255 | --- @@ -1208,7 +1208,7 @@ Fixed-wing attitude stabilisation low-pass filter cutoff | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 300 | +| 5 | 0 | 255 | --- @@ -1218,7 +1218,7 @@ Fixed-wing rate stabilisation I-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 7 | 0 | 300 | +| 7 | 0 | 255 | --- @@ -1228,7 +1228,7 @@ Fixed-wing rate stabilisation I-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 7 | 0 | 300 | +| 7 | 0 | 255 | --- @@ -1238,7 +1238,7 @@ Fixed-wing rate stabilisation I-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 10 | 0 | 300 | +| 10 | 0 | 255 | --- @@ -1318,7 +1318,7 @@ Fixed-wing attitude stabilisation P-gain | Default | Min | Max | | --- | --- | --- | -| 20 | 0 | 300 | +| 20 | 0 | 255 | --- @@ -1328,7 +1328,7 @@ Fixed-wing rate stabilisation P-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 300 | +| 5 | 0 | 255 | --- @@ -1338,7 +1338,7 @@ Fixed-wing rate stabilisation P-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 5 | 0 | 300 | +| 5 | 0 | 255 | --- @@ -1348,7 +1348,7 @@ Fixed-wing rate stabilisation P-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 6 | 0 | 300 | +| 6 | 0 | 255 | --- @@ -2568,7 +2568,7 @@ Multicopter Control Derivative gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 300 | +| 60 | 0 | 255 | --- @@ -2578,7 +2578,7 @@ Multicopter Control Derivative gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 300 | +| 60 | 0 | 255 | --- @@ -2588,7 +2588,7 @@ Multicopter Control Derivative gain for YAW | Default | Min | Max | | --- | --- | --- | -| 60 | 0 | 300 | +| 60 | 0 | 255 | --- @@ -2598,7 +2598,7 @@ Multicopter attitude stabilisation HORIZON transition point | Default | Min | Max | | --- | --- | --- | -| 75 | 0 | 300 | +| 75 | 0 | 255 | --- @@ -2608,7 +2608,7 @@ Multicopter rate stabilisation D-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 23 | 0 | 300 | +| 23 | 0 | 255 | --- @@ -2618,7 +2618,7 @@ Multicopter rate stabilisation D-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 23 | 0 | 300 | +| 23 | 0 | 255 | --- @@ -2628,7 +2628,7 @@ Multicopter rate stabilisation D-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 0 | 0 | 300 | +| 0 | 0 | 255 | --- @@ -2638,7 +2638,7 @@ Multicopter attitude stabilisation low-pass filter cutoff | Default | Min | Max | | --- | --- | --- | -| 15 | 0 | 300 | +| 15 | 0 | 255 | --- @@ -2648,7 +2648,7 @@ Multicopter rate stabilisation I-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 30 | 0 | 300 | +| 30 | 0 | 255 | --- @@ -2658,7 +2658,7 @@ Multicopter rate stabilisation I-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 30 | 0 | 300 | +| 30 | 0 | 255 | --- @@ -2668,7 +2668,7 @@ Multicopter rate stabilisation I-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 45 | 0 | 300 | +| 45 | 0 | 255 | --- @@ -2698,7 +2698,7 @@ Multicopter attitude stabilisation P-gain | Default | Min | Max | | --- | --- | --- | -| 20 | 0 | 300 | +| 20 | 0 | 255 | --- @@ -2708,7 +2708,7 @@ Multicopter rate stabilisation P-gain for PITCH | Default | Min | Max | | --- | --- | --- | -| 40 | 0 | 300 | +| 40 | 0 | 255 | --- @@ -2718,7 +2718,7 @@ Multicopter rate stabilisation P-gain for ROLL | Default | Min | Max | | --- | --- | --- | -| 40 | 0 | 300 | +| 40 | 0 | 255 | --- @@ -2728,7 +2728,7 @@ Multicopter rate stabilisation P-gain for YAW | Default | Min | Max | | --- | --- | --- | -| 85 | 0 | 300 | +| 85 | 0 | 255 | --- From 2702823d78f7060ce6ae8a6ada418f69bd939d61 Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Fri, 4 Jun 2021 22:21:56 +0200 Subject: [PATCH 48/67] fix --- src/main/io/osd.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 5030365368..b8c792304f 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1502,7 +1502,8 @@ static bool osdDrawSingleElement(uint8_t item) static pt1Filter_t gsFilterState; const timeMs_t currentTimeMs = millis(); static timeMs_t gsUpdatedTimeMs; - float glideSlope = pt1FilterApply4(&gsFilterState, horizontalSpeed / sinkRate, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); + float glideSlope = horizontalSpeed / sinkRate; + glideSlope = pt1FilterApply4(&gsFilterState, isnormal(glideSlope) ? glideSlope : 200, 0.5, MS2S(currentTimeMs - gsUpdatedTimeMs)); gsUpdatedTimeMs = currentTimeMs; buff[0] = SYM_GLIDESLOPE; From 81fdf6d5aec31c84f042a5c0ecbf168a0150bb06 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 5 Jun 2021 11:31:16 +0200 Subject: [PATCH 49/67] Add sticks restriction to continuous trim --- docs/Settings.md | 12 +++++++++++- src/main/fc/fc_core.c | 2 +- src/main/fc/rc_controls.c | 7 ++++--- src/main/fc/rc_controls.h | 5 +++-- src/main/fc/settings.yaml | 7 ++++++- src/main/flight/pid.c | 8 +------- src/main/flight/servos.c | 12 +++++++----- src/main/navigation/navigation.c | 2 +- src/main/navigation/navigation_fw_launch.c | 4 ++-- 9 files changed, 36 insertions(+), 23 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index 4f5d6487f7..e12b881df9 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -482,6 +482,16 @@ Blackbox logging rate numerator. Use num/denom settings to decide if a frame sho --- +### control_deadband + +Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered. + +| Default | Min | Max | +| --- | --- | --- | +| 10 | 2 | 250 | + +--- + ### cpu_underclock 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 @@ -4664,7 +4674,7 @@ Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER ### pos_hold_deadband -Stick deadband in [r/c points], applied after r/c deadband and expo +Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes. | Default | Min | Max | | --- | --- | --- | diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c index 57825a01cc..529de05f61 100755 --- a/src/main/fc/fc_core.c +++ b/src/main/fc/fc_core.c @@ -216,7 +216,7 @@ static void updateArmingStatus(void) /* CHECK: pitch / roll sticks centered when NAV_LAUNCH_MODE enabled */ if (isNavLaunchEnabled()) { - if (areSticksDeflectedMoreThanPosHoldDeadband()) { + if (areSticksDeflected()) { ENABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); } else { DISABLE_ARMING_FLAG(ARMING_DISABLED_ROLLPITCH_NOT_CENTERED); diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 563d181fb6..daa6975975 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -71,12 +71,13 @@ stickPositions_e rcStickPositions; FASTRAM int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW -PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 2); +PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 3); PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, .deadband = SETTING_DEADBAND_DEFAULT, .yaw_deadband = SETTING_YAW_DEADBAND_DEFAULT, .pos_hold_deadband = SETTING_POS_HOLD_DEADBAND_DEFAULT, + .control_deadband = SETTING_CONTROL_DEADBAND_DEFAULT, .alt_hold_deadband = SETTING_ALT_HOLD_DEADBAND_DEFAULT, .mid_throttle_deadband = SETTING_3D_DEADBAND_THROTTLE_DEFAULT, .airmodeHandlingType = SETTING_AIRMODE_TYPE_DEFAULT, @@ -97,9 +98,9 @@ bool areSticksInApModePosition(uint16_t ap_mode) return ABS(rcCommand[ROLL]) < ap_mode && ABS(rcCommand[PITCH]) < ap_mode; } -bool areSticksDeflectedMoreThanPosHoldDeadband(void) +bool areSticksDeflected(void) { - return (ABS(rcCommand[ROLL]) > rcControlsConfig()->pos_hold_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->pos_hold_deadband); + return ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband || ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband || ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband; } throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index f5258a9c9e..6063ca1942 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -84,7 +84,8 @@ extern int16_t rcCommand[4]; typedef struct rcControlsConfig_s { uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero. - uint8_t pos_hold_deadband; // Adds ability to adjust the Hold-position when moving the sticks (assisted mode) + uint8_t pos_hold_deadband; // Deadband for position hold + uint8_t control_deadband; // General deadband to check if sticks are deflected uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered @@ -106,7 +107,7 @@ stickPositions_e getRcStickPositions(void); bool checkStickPosition(stickPositions_e stickPos); bool areSticksInApModePosition(uint16_t ap_mode); -bool areSticksDeflectedMoreThanPosHoldDeadband(void); +bool areSticksDeflected(void); throttleStatus_e calculateThrottleStatus(throttleStatusType_e type); rollPitchStatus_e calculateRollPitchCenterStatus(void); void processRcStickPositions(throttleStatus_e throttleStatus); diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 4995b9ce34..88e1da1281 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -1505,7 +1505,12 @@ groups: min: 0 max: 100 - name: pos_hold_deadband - description: "Stick deadband in [r/c points], applied after r/c deadband and expo" + description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes." + default_value: 10 + min: 2 + max: 250 + - name: control_deadband + description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered." default_value: 10 min: 2 max: 250 diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 34a1298714..bf52ec24b1 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -1314,15 +1314,9 @@ void updateFixedWingLevelTrim(timeUs_t currentTimeUs) pidControllerFlags_e flags = PID_LIMIT_INTEGRATOR; //Iterm should freeze when sticks are deflected - bool areSticksDeflected = false; - for (int stick = ROLL; stick <= YAW; stick++) { - areSticksDeflected = areSticksDeflected || - rxGetChannelValue(stick) > (PWM_RANGE_MIDDLE + pidProfile()->fixedWingLevelTrimDeadband) || - rxGetChannelValue(stick) < (PWM_RANGE_MIDDLE - pidProfile()->fixedWingLevelTrimDeadband); - } if ( !IS_RC_MODE_ACTIVE(BOXAUTOLEVEL) || - areSticksDeflected || + areSticksDeflected() || (!FLIGHT_MODE(ANGLE_MODE) && !FLIGHT_MODE(HORIZON_MODE)) || navigationIsControllingAltitude() ) { diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index c3a242497c..c55e7d48fa 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -490,6 +490,7 @@ void processServoAutotrimMode(void) #define SERVO_AUTOTRIM_CENTER_MIN 1300 #define SERVO_AUTOTRIM_CENTER_MAX 1700 #define SERVO_AUTOTRIM_UPDATE_SIZE 5 +#define SERVO_AUTOTRIM_ATIITUDE_LIMIT 50 // 5 degrees void processContinuousServoAutotrim(const float dT) { @@ -497,21 +498,22 @@ void processContinuousServoAutotrim(const float dT) static servoAutotrimState_e trimState = AUTOTRIM_IDLE; static uint32_t servoMiddleUpdateCount; - const float rotRateMagnitude = sqrtf(vectorNormSquared(&imuMeasuredRotationBF)); - const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, rotRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT); - const float targetRateMagnitude = getTotalRateTarget(); - const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, targetRateMagnitude, SERVO_AUTOTRIM_FILTER_CUTOFF, dT); + const float rotRateMagnitudeFiltered = pt1FilterApply4(&rotRateFilter, sqrtf(vectorNormSquared(&imuMeasuredRotationBF)), SERVO_AUTOTRIM_FILTER_CUTOFF, dT); + const float targetRateMagnitudeFiltered = pt1FilterApply4(&targetRateFilter, getTotalRateTarget(), SERVO_AUTOTRIM_FILTER_CUTOFF, dT); if (ARMING_FLAG(ARMED)) { trimState = AUTOTRIM_COLLECTING; if ((millis() - lastUpdateTimeMs) > 500) { const bool planeIsFlyingStraight = rotRateMagnitudeFiltered <= DEGREES_TO_RADIANS(servoConfig()->servo_autotrim_rotation_limit); const bool noRotationCommanded = targetRateMagnitudeFiltered <= servoConfig()->servo_autotrim_rotation_limit; - const bool planeIsFlyingLevel = calculateCosTiltAngle() >= 0.878153032f; + const bool sticksAreCentered = !areSticksDeflected(); + const bool planeIsFlyingLevel = (ABS(attitude.values.pitch) + DEGREES_TO_DECIDEGREES(getFixedWingLevelTrim())) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT + && ABS(attitude.values.roll) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT; if ( planeIsFlyingStraight && noRotationCommanded && planeIsFlyingLevel && + sticksAreCentered && !FLIGHT_MODE(MANUAL_MODE) && isGPSHeadingValid() // TODO: proper flying detection ) { diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 5bf4b26783..ef1d9d41e5 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1728,7 +1728,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationF //allow to leave NAV_LAUNCH_MODE if it has being enabled as feature by moving sticks with low throttle. if (feature(FEATURE_FW_LAUNCH)) { throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); - if ((throttleStatus == THROTTLE_LOW) && (areSticksDeflectedMoreThanPosHoldDeadband())) { + if ((throttleStatus == THROTTLE_LOW) && (areSticksDeflected())) { abortFixedWingLaunch(); return NAV_FSM_EVENT_SWITCH_TO_IDLE; } diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index de86475f41..42a8efc526 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -251,7 +251,7 @@ static inline bool isLaunchMaxAltitudeReached(void) static inline bool areSticksMoved(timeMs_t initialTime, timeUs_t currentTimeUs) { - return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && areSticksDeflectedMoreThanPosHoldDeadband(); + return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && areSticksDeflected(); } static void resetPidsIfNeeded(void) { @@ -435,7 +435,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs); const timeMs_t endTimeMs = navConfig()->fw.launch_end_time; - if (areSticksDeflectedMoreThanPosHoldDeadband()) { + if (areSticksDeflected()) { return FW_LAUNCH_EVENT_ABORT; // cancel the launch and do the FW_LAUNCH_STATE_IDLE state } if (elapsedTimeMs > endTimeMs) { From 45b0591e4fa2f7c65bc9f0ab518bac066136bf99 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 6 Jun 2021 18:45:01 +0200 Subject: [PATCH 50/67] Restructre scheduler to run RT callbacks also after any RT task --- src/main/scheduler/scheduler.c | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index b03276aacb..75b532e515 100755 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -299,7 +299,9 @@ void FAST_CODE NOINLINE scheduler(void) #if defined(SCHEDULER_DEBUG) DEBUG_SET(DEBUG_SCHEDULER, 2, micros() - currentTimeUs - taskExecutionTime); // time spent in scheduler #endif - } else { + } + + if (!selectedTask || forcedRealTimeTask) { // Execute system real-time callbacks and account for them to SYSTEM account const timeUs_t currentTimeBeforeTaskCall = micros(); taskRunRealtimeCallbacks(currentTimeBeforeTaskCall); From 446204dee2bd517fd365fdb7b09ea37d2b8faa55 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 6 Jun 2021 19:01:12 +0200 Subject: [PATCH 51/67] Run only PID as RT task --- src/main/fc/fc_tasks.c | 2 +- src/main/scheduler/scheduler.h | 1 + 2 files changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index e4ef2a2132..a76adcb9e9 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -414,7 +414,7 @@ cfTask_t cfTasks[TASK_COUNT] = { .taskName = "GYRO", .taskFunc = taskGyro, .desiredPeriod = TASK_PERIOD_US(TASK_GYRO_LOOPTIME), - .staticPriority = TASK_PRIORITY_REALTIME, + .staticPriority = TASK_PRIORITY_HIGHER, }, [TASK_SERIAL] = { .taskName = "SERIAL", diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 4efa96e17d..37413010f0 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -27,6 +27,7 @@ typedef enum { TASK_PRIORITY_MEDIUM = 3, TASK_PRIORITY_MEDIUM_HIGH = 4, TASK_PRIORITY_HIGH = 5, + TASK_PRIORITY_HIGHER = 8, TASK_PRIORITY_REALTIME = 18, TASK_PRIORITY_MAX = 255 } cfTaskPriority_e; From 81a99ac346485c4ef32139d4b20435270103cf48 Mon Sep 17 00:00:00 2001 From: "Pawel Spychalski (DzikuVx)" Date: Sun, 6 Jun 2021 19:14:12 +0200 Subject: [PATCH 52/67] Rollback to previous way of RT --- src/main/fc/fc_tasks.c | 2 +- src/main/scheduler/scheduler.h | 1 - 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/fc/fc_tasks.c b/src/main/fc/fc_tasks.c index a76adcb9e9..e4ef2a2132 100755 --- a/src/main/fc/fc_tasks.c +++ b/src/main/fc/fc_tasks.c @@ -414,7 +414,7 @@ cfTask_t cfTasks[TASK_COUNT] = { .taskName = "GYRO", .taskFunc = taskGyro, .desiredPeriod = TASK_PERIOD_US(TASK_GYRO_LOOPTIME), - .staticPriority = TASK_PRIORITY_HIGHER, + .staticPriority = TASK_PRIORITY_REALTIME, }, [TASK_SERIAL] = { .taskName = "SERIAL", diff --git a/src/main/scheduler/scheduler.h b/src/main/scheduler/scheduler.h index 37413010f0..4efa96e17d 100755 --- a/src/main/scheduler/scheduler.h +++ b/src/main/scheduler/scheduler.h @@ -27,7 +27,6 @@ typedef enum { TASK_PRIORITY_MEDIUM = 3, TASK_PRIORITY_MEDIUM_HIGH = 4, TASK_PRIORITY_HIGH = 5, - TASK_PRIORITY_HIGHER = 8, TASK_PRIORITY_REALTIME = 18, TASK_PRIORITY_MAX = 255 } cfTaskPriority_e; From 99bfeeade7238a044d23a18f690aa026ecf42af0 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 6 Jun 2021 22:41:28 +0100 Subject: [PATCH 53/67] Update beeper.c --- src/main/io/beeper.c | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 02f88c87d8..cd7893f5e6 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -344,8 +344,7 @@ void beeperUpdate(timeUs_t currentTimeUs) if (!beeperIsOn) { #ifdef USE_DSHOT - if (!areMotorsRunning() - && beeperConfig()->dshot_beeper_enabled + if (isMotorProtocolDshot() && !areMotorsRunning() && beeperConfig()->dshot_beeper_enabled && currentTimeUs - lastDshotBeeperCommandTimeUs > getDShotBeaconGuardDelayUs()) { lastDshotBeeperCommandTimeUs = currentTimeUs; From 1a104a8f2aa412a50c01b9a6c20ebafa65c8c62b Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sat, 12 Dec 2020 23:51:38 +0000 Subject: [PATCH 54/67] Display only geospatial WPs on OSD Fix to ensure only geospatial WPs are displayed on OSD with sequential numbering maintained around nongeo WPs. --- src/main/io/osd.c | 15 ++++++++++++++- src/main/navigation/navigation.c | 15 ++++++++++++++- src/main/navigation/navigation_private.h | 3 ++- 3 files changed, 30 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0e6f9738b3..f5594c83e4 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1383,6 +1383,19 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, displayWriteWithAttr(osdDisplayPort, elemPosX + strlen(str) + 1 + valueOffset, elemPosY, buff, elemAttr); } +int8_t getGeoWaypointNumber(int8_t waypointIndex) +{ + if (posControl.waypointList[waypointIndex].flag == NAV_WP_FLAG_LAST) { + if ((posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_HEAD)) { + return posControl.waypointList[waypointIndex - 1].flag; + } else { + return posControl.waypointList[waypointIndex - 1].flag + 1; + } + } else { + return posControl.waypointList[waypointIndex].flag; + } +} + static bool osdDrawSingleElement(uint8_t item) { uint16_t pos = osdLayoutsConfig()->item_pos[currentLayout][item]; @@ -3833,7 +3846,7 @@ textAttributes_t osdGetSystemMessage(char *buff, size_t buff_size, bool isCenter // Countdown display for remaining Waypoints char buf[6]; osdFormatDistanceSymbol(buf, posControl.wpDistance, 0); - tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", posControl.activeWaypointIndex + 1, posControl.waypointCount, buf); + tfp_sprintf(messageBuf, "TO WP %u/%u (%s)", getGeoWaypointNumber(posControl.activeWaypointIndex), posControl.geoWaypointCount, buf); messages[messageCount++] = messageBuf; } else if (NAV_Status.state == MW_NAV_STATE_HOLD_TIMED) { // WP hold time countdown in seconds diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 5bf4b26783..6917b20f7f 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2833,13 +2833,25 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) else if ((wpNumber >= 1) && (wpNumber <= NAV_MAX_WAYPOINTS) && !ARMING_FLAG(ARMED)) { if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) + static int8_t nonGeoWaypointCount = 0; + if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) { posControl.waypointList[wpNumber - 1] = *wpData; - if(wpData->action == NAV_WP_ACTION_JUMP) { + if (wpData->action == NAV_WP_ACTION_JUMP) { posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) + nonGeoWaypointCount += 1; + } + if (wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD) { + nonGeoWaypointCount += 1; } posControl.waypointCount = wpNumber; posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST); + posControl.geoWaypointCount = posControl.waypointCount - nonGeoWaypointCount; + if (posControl.waypointListValid) { + nonGeoWaypointCount = 0; + } else { + posControl.waypointList[wpNumber - 1].flag = wpNumber - nonGeoWaypointCount; + } } } } @@ -2851,6 +2863,7 @@ void resetWaypointList(void) if (!ARMING_FLAG(ARMED)) { posControl.waypointCount = 0; posControl.waypointListValid = false; + posControl.geoWaypointCount = 0; } } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index b26299e707..308c55a9c7 100755 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -356,7 +356,8 @@ typedef struct { navWaypoint_t waypointList[NAV_MAX_WAYPOINTS]; bool waypointListValid; int8_t waypointCount; - + int8_t geoWaypointCount; // total geospatial WPs in mission + navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; float wpInitialAltitude; // Altitude at start of WP From ec693daeb642d9107d57a6b137ba8cb7d0b41aa0 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 14 Dec 2020 17:09:57 +0000 Subject: [PATCH 55/67] Update Method Change from using WP.flag to WP.p3 --- src/main/io/osd.c | 10 +++------- src/main/navigation/navigation.c | 19 ++++++++++--------- 2 files changed, 13 insertions(+), 16 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index f5594c83e4..41b0d1302e 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1385,14 +1385,10 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, int8_t getGeoWaypointNumber(int8_t waypointIndex) { - if (posControl.waypointList[waypointIndex].flag == NAV_WP_FLAG_LAST) { - if ((posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_HEAD)) { - return posControl.waypointList[waypointIndex - 1].flag; - } else { - return posControl.waypointList[waypointIndex - 1].flag + 1; - } + if ((posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_HEAD)) { + return posControl.waypointList[waypointIndex - 1].p3; } else { - return posControl.waypointList[waypointIndex].flag; + return posControl.waypointList[waypointIndex].p3; } } diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 6917b20f7f..381493d456 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2834,24 +2834,25 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) if (wpData->action == NAV_WP_ACTION_WAYPOINT || wpData->action == NAV_WP_ACTION_JUMP || wpData->action == NAV_WP_ACTION_RTH || wpData->action == NAV_WP_ACTION_HOLD_TIME || wpData->action == NAV_WP_ACTION_LAND || wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD ) { // Only allow upload next waypoint (continue upload mission) or first waypoint (new mission) static int8_t nonGeoWaypointCount = 0; - + if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) { posControl.waypointList[wpNumber - 1] = *wpData; - if (wpData->action == NAV_WP_ACTION_JUMP) { - posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) + + if(wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD || wpData->action == NAV_WP_ACTION_JUMP) { + if(wpData->action == NAV_WP_ACTION_JUMP) { + posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) + } nonGeoWaypointCount += 1; + } else { + posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; } - if (wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD) { - nonGeoWaypointCount += 1; - } + posControl.waypointCount = wpNumber; posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST); posControl.geoWaypointCount = posControl.waypointCount - nonGeoWaypointCount; if (posControl.waypointListValid) { nonGeoWaypointCount = 0; - } else { - posControl.waypointList[wpNumber - 1].flag = wpNumber - nonGeoWaypointCount; - } + } } } } From b0d75aa6cd57933c591f944f38e4f6d27e241d68 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Tue, 15 Dec 2020 09:14:47 +0000 Subject: [PATCH 56/67] Update navigation.c --- src/main/navigation/navigation.c | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 381493d456..2040da65f3 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2839,10 +2839,12 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) posControl.waypointList[wpNumber - 1] = *wpData; if(wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD || wpData->action == NAV_WP_ACTION_JUMP) { + nonGeoWaypointCount += 1; if(wpData->action == NAV_WP_ACTION_JUMP) { posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) - } - nonGeoWaypointCount += 1; + } else { + posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; + } } else { posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; } From 7cec1f2fdb6fb0be2a5970e19052205b1859ffc4 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 16 Dec 2020 22:41:55 +0000 Subject: [PATCH 57/67] Update osd.c --- src/main/io/osd.c | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 41b0d1302e..8113b07059 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1385,7 +1385,7 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, int8_t getGeoWaypointNumber(int8_t waypointIndex) { - if ((posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_SET_HEAD)) { + if (posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP) { return posControl.waypointList[waypointIndex - 1].p3; } else { return posControl.waypointList[waypointIndex].p3; @@ -1995,8 +1995,9 @@ static bool osdDrawSingleElement(uint8_t item) fpVector3_t poi; geoConvertGeodeticToLocal(&poi, &posControl.gpsOrigin, &wp2, waypointMissionAltConvMode(posControl.waypointList[j].p3)); int32_t altConvModeAltitude = waypointMissionAltConvMode(posControl.waypointList[j].p3) == GEO_ALT_ABSOLUTE ? osdGetAltitudeMsl() : osdGetAltitude(); - while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more - osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 49 + j, i); + j = getGeoWaypointNumber(j); + while (j > 9) j -= 10; // Only the last digit displayed if WP>=10, no room for more (48 = ascii 0) + osdHudDrawPoi(calculateDistanceToDestination(&poi) / 100, osdGetHeadingAngle(calculateBearingToDestination(&poi) / 100), (posControl.waypointList[j].alt - altConvModeAltitude)/ 100, 2, SYM_WAYPOINT, 48 + j, i); } } } From 94e199ecd94caaa966298214ccde78374dd30600 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Wed, 10 Feb 2021 22:38:30 +0000 Subject: [PATCH 58/67] Fix white space --- src/main/navigation/navigation.c | 2 +- src/main/navigation/navigation_private.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) mode change 100755 => 100644 src/main/navigation/navigation_private.h diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 2040da65f3..99696a76c0 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2844,7 +2844,7 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) } else { posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; - } + } } else { posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; } diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h old mode 100755 new mode 100644 index 308c55a9c7..9c77e8c094 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -357,7 +357,7 @@ typedef struct { bool waypointListValid; int8_t waypointCount; int8_t geoWaypointCount; // total geospatial WPs in mission - + navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; float wpInitialAltitude; // Altitude at start of WP From 36974174aa1cfac6fb3c9035f140f8b3950f1edf Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Sun, 28 Feb 2021 11:26:34 +0000 Subject: [PATCH 59/67] Change Index List Change from using WP .P3 to dedicated geospatial WP list list array --- src/main/io/osd.c | 6 +----- src/main/navigation/navigation.c | 6 +----- src/main/navigation/navigation_private.h | 3 ++- 3 files changed, 4 insertions(+), 11 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 8113b07059..0d23880f18 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1385,11 +1385,7 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, int8_t getGeoWaypointNumber(int8_t waypointIndex) { - if (posControl.waypointList[waypointIndex].action == NAV_WP_ACTION_JUMP) { - return posControl.waypointList[waypointIndex - 1].p3; - } else { - return posControl.waypointList[waypointIndex].p3; - } + return posControl.geoWaypointList[waypointIndex]; } static bool osdDrawSingleElement(uint8_t item) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index 99696a76c0..f42acff897 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2837,17 +2837,13 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) if (wpNumber == (posControl.waypointCount + 1) || wpNumber == 1) { posControl.waypointList[wpNumber - 1] = *wpData; - if(wpData->action == NAV_WP_ACTION_SET_POI || wpData->action == NAV_WP_ACTION_SET_HEAD || wpData->action == NAV_WP_ACTION_JUMP) { nonGeoWaypointCount += 1; if(wpData->action == NAV_WP_ACTION_JUMP) { posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) - } else { - posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; } - } else { - posControl.waypointList[wpNumber - 1].p3 = wpNumber - nonGeoWaypointCount; } + posControl.geoWaypointList[wpNumber - 1] = wpNumber - nonGeoWaypointCount; posControl.waypointCount = wpNumber; posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 9c77e8c094..3cd7e2b595 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -356,7 +356,8 @@ typedef struct { navWaypoint_t waypointList[NAV_MAX_WAYPOINTS]; bool waypointListValid; int8_t waypointCount; - int8_t geoWaypointCount; // total geospatial WPs in mission + int8_t geoWaypointCount; // total geospatial WPs in mission + int8_t geoWaypointList[NAV_MAX_WAYPOINTS]; // holds realigned geospacial WP numbering index navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; From 1a7ce2619725eeb6aae7d56af237294f1f860a00 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 19 Apr 2021 14:44:12 +0100 Subject: [PATCH 60/67] Change of method Change to remove array for storing geospatial WP indices. Uses iterative method to determine geospatial WP numbering instead. --- src/main/io/osd.c | 17 ++++++++++++++++- src/main/navigation/navigation.c | 1 - src/main/navigation/navigation_private.h | 1 - 3 files changed, 16 insertions(+), 3 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 0d23880f18..20dea5c151 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1385,7 +1385,22 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, int8_t getGeoWaypointNumber(int8_t waypointIndex) { - return posControl.geoWaypointList[waypointIndex]; + static int8_t lastWaypointIndex = 1; + static int8_t lastGeoWaypointIndex; + + if (waypointIndex != lastWaypointIndex) { + lastWaypointIndex = waypointIndex; + lastGeoWaypointIndex = waypointIndex; + for (uint8_t i = 0; i <= waypointIndex; i++) { + if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || + posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || + posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { + lastGeoWaypointIndex -= 1; + } + } + } + + return lastGeoWaypointIndex + 1; } static bool osdDrawSingleElement(uint8_t item) diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index f42acff897..9ae3111499 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -2843,7 +2843,6 @@ void setWaypoint(uint8_t wpNumber, const navWaypoint_t * wpData) posControl.waypointList[wpNumber - 1].p1 -= 1; // make index (vice WP #) } } - posControl.geoWaypointList[wpNumber - 1] = wpNumber - nonGeoWaypointCount; posControl.waypointCount = wpNumber; posControl.waypointListValid = (wpData->flag == NAV_WP_FLAG_LAST); diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index 3cd7e2b595..c778b5e540 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -357,7 +357,6 @@ typedef struct { bool waypointListValid; int8_t waypointCount; int8_t geoWaypointCount; // total geospatial WPs in mission - int8_t geoWaypointList[NAV_MAX_WAYPOINTS]; // holds realigned geospacial WP numbering index navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; From b4b11c40bd076c195e5079e5e349c8b373081d62 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 19 Apr 2021 15:11:27 +0100 Subject: [PATCH 61/67] Update navigation_private.h --- src/main/navigation/navigation_private.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/main/navigation/navigation_private.h b/src/main/navigation/navigation_private.h index c778b5e540..e87547567d 100644 --- a/src/main/navigation/navigation_private.h +++ b/src/main/navigation/navigation_private.h @@ -356,9 +356,9 @@ typedef struct { navWaypoint_t waypointList[NAV_MAX_WAYPOINTS]; bool waypointListValid; int8_t waypointCount; - int8_t geoWaypointCount; // total geospatial WPs in mission + int8_t geoWaypointCount; // total geospatial WPs in mission - navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation + navWaypointPosition_t activeWaypoint; // Local position and initial bearing, filled on waypoint activation int8_t activeWaypointIndex; float wpInitialAltitude; // Altitude at start of WP float wpInitialDistance; // Distance when starting flight to WP From 012c7fbe9ca0318a3dae47e632913c91e23278c0 Mon Sep 17 00:00:00 2001 From: breadoven <56191411+breadoven@users.noreply.github.com> Date: Mon, 7 Jun 2021 09:36:10 +0100 Subject: [PATCH 62/67] Update osd.c --- src/main/io/osd.c | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index 20dea5c151..08f1575b77 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -1386,21 +1386,20 @@ static void osdDisplayAdjustableDecimalValue(uint8_t elemPosX, uint8_t elemPosY, int8_t getGeoWaypointNumber(int8_t waypointIndex) { static int8_t lastWaypointIndex = 1; - static int8_t lastGeoWaypointIndex; + static int8_t geoWaypointIndex; if (waypointIndex != lastWaypointIndex) { - lastWaypointIndex = waypointIndex; - lastGeoWaypointIndex = waypointIndex; + lastWaypointIndex = geoWaypointIndex = waypointIndex; for (uint8_t i = 0; i <= waypointIndex; i++) { if (posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP) { - lastGeoWaypointIndex -= 1; + geoWaypointIndex -= 1; } } } - return lastGeoWaypointIndex + 1; + return geoWaypointIndex + 1; } static bool osdDrawSingleElement(uint8_t item) From 58f67260ee6e97754fabd459ad6513366caa783f Mon Sep 17 00:00:00 2001 From: Michel Pastor Date: Mon, 7 Jun 2021 23:16:43 +0200 Subject: [PATCH 63/67] Fix power limits (#7075) --- src/main/flight/power_limits.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/src/main/flight/power_limits.c b/src/main/flight/power_limits.c index 1ce770aca4..ee5c0c3c77 100644 --- a/src/main/flight/power_limits.c +++ b/src/main/flight/power_limits.c @@ -192,7 +192,6 @@ void powerLimiterApply(int16_t *throttleCommand) { currentThrottleCommand = currentThrAttned; } else { wasLimitingCurrent = false; - currentThrAttnIntegrator = 0; pt1FilterReset(¤tThrAttnFilter, 0); currentThrottleCommand = *throttleCommand; @@ -222,7 +221,6 @@ void powerLimiterApply(int16_t *throttleCommand) { powerThrottleCommand = powerThrAttned; } else { wasLimitingPower = false; - powerThrAttnIntegrator = 0; pt1FilterReset(&powerThrAttnFilter, 0); powerThrottleCommand = *throttleCommand; From 78a839e23336c7454757847f741f4ec98f57f47e Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 9 Jun 2021 11:13:19 +0200 Subject: [PATCH 64/67] remove level trim deadband setting --- docs/Settings.md | 10 ---------- src/main/fc/rc_controls.c | 2 +- src/main/fc/rc_controls.h | 2 +- src/main/fc/settings.yaml | 6 ------ src/main/flight/pid.c | 1 - src/main/flight/pid.h | 1 - 6 files changed, 2 insertions(+), 20 deletions(-) diff --git a/docs/Settings.md b/docs/Settings.md index e12b881df9..de9cc0ea45 100644 --- a/docs/Settings.md +++ b/docs/Settings.md @@ -1272,16 +1272,6 @@ Limits max/min I-term value in stabilization PID controller in case of Fixed Win --- -### fw_level_pitch_deadband - -Deadband for automatic leveling when AUTOLEVEL mode is used. - -| Default | Min | Max | -| --- | --- | --- | -| 5 | 0 | 20 | - ---- - ### fw_level_pitch_gain I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index daa6975975..9ee7774a14 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -100,7 +100,7 @@ bool areSticksInApModePosition(uint16_t ap_mode) bool areSticksDeflected(void) { - return ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband || ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband || ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband; + return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband); } throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type) diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index 6063ca1942..e683c987fe 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -85,7 +85,7 @@ typedef struct rcControlsConfig_s { uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. uint8_t yaw_deadband; // introduce a deadband around the stick center for yaw axis. Must be greater than zero. uint8_t pos_hold_deadband; // Deadband for position hold - uint8_t control_deadband; // General deadband to check if sticks are deflected + uint8_t control_deadband; // General deadband to check if sticks are deflected, us PWM. uint8_t alt_hold_deadband; // Defines the neutral zone of throttle stick during altitude hold uint16_t mid_throttle_deadband; // default throttle deadband from MIDRC uint8_t airmodeHandlingType; // Defaults to ANTI_WINDUP triggered at sticks centered diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml index 88e1da1281..8bf61790e3 100644 --- a/src/main/fc/settings.yaml +++ b/src/main/fc/settings.yaml @@ -2123,12 +2123,6 @@ groups: field: fixedWingLevelTrimGain min: 0 max: 20 - - name: fw_level_pitch_deadband - description: "Deadband for automatic leveling when AUTOLEVEL mode is used." - default_value: 5 - field: fixedWingLevelTrimDeadband - min: 0 - max: 20 - name: PG_PID_AUTOTUNE_CONFIG type: pidAutotuneConfig_t diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index bf52ec24b1..9af3aadb13 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -308,7 +308,6 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile, .fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT, .fixedWingLevelTrimGain = SETTING_FW_LEVEL_PITCH_GAIN_DEFAULT, - .fixedWingLevelTrimDeadband = SETTING_FW_LEVEL_PITCH_DEADBAND_DEFAULT, #ifdef USE_SMITH_PREDICTOR .smithPredictorStrength = SETTING_SMITH_PREDICTOR_STRENGTH_DEFAULT, diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 734007b481..37486a4cac 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -165,7 +165,6 @@ typedef struct pidProfile_s { float fixedWingLevelTrim; float fixedWingLevelTrimGain; - float fixedWingLevelTrimDeadband; #ifdef USE_SMITH_PREDICTOR float smithPredictorStrength; float smithPredictorDelay; From dac60f7a730abec99c6d960c4756accd257b8c16 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 9 Jun 2021 11:26:28 +0200 Subject: [PATCH 65/67] fix pitch angle --- src/main/flight/servos.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index c55e7d48fa..72ec959115 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -507,7 +507,7 @@ void processContinuousServoAutotrim(const float dT) const bool planeIsFlyingStraight = rotRateMagnitudeFiltered <= DEGREES_TO_RADIANS(servoConfig()->servo_autotrim_rotation_limit); const bool noRotationCommanded = targetRateMagnitudeFiltered <= servoConfig()->servo_autotrim_rotation_limit; const bool sticksAreCentered = !areSticksDeflected(); - const bool planeIsFlyingLevel = (ABS(attitude.values.pitch) + DEGREES_TO_DECIDEGREES(getFixedWingLevelTrim())) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT + const bool planeIsFlyingLevel = ABS(attitude.values.pitch + DEGREES_TO_DECIDEGREES(getFixedWingLevelTrim())) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT && ABS(attitude.values.roll) <= SERVO_AUTOTRIM_ATIITUDE_LIMIT; if ( planeIsFlyingStraight && From 156c947d3c2c74edd50672a8044df9e769a34b07 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Wed, 9 Jun 2021 14:33:34 +0200 Subject: [PATCH 66/67] separate function for only roll/pitch stick deflection --- src/main/fc/rc_controls.c | 5 +++++ src/main/fc/rc_controls.h | 1 + src/main/navigation/navigation.c | 2 +- src/main/navigation/navigation_fw_launch.c | 4 ++-- 4 files changed, 9 insertions(+), 3 deletions(-) diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 9ee7774a14..74952a5329 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -103,6 +103,11 @@ bool areSticksDeflected(void) return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[YAW]) > rcControlsConfig()->control_deadband); } +bool isRollPitchStickDeflected(void) +{ + return (ABS(rcCommand[ROLL]) > rcControlsConfig()->control_deadband) || (ABS(rcCommand[PITCH]) > rcControlsConfig()->control_deadband); +} + throttleStatus_e FAST_CODE NOINLINE calculateThrottleStatus(throttleStatusType_e type) { int value; diff --git a/src/main/fc/rc_controls.h b/src/main/fc/rc_controls.h index e683c987fe..dd617f29e7 100644 --- a/src/main/fc/rc_controls.h +++ b/src/main/fc/rc_controls.h @@ -108,6 +108,7 @@ bool checkStickPosition(stickPositions_e stickPos); bool areSticksInApModePosition(uint16_t ap_mode); bool areSticksDeflected(void); +bool isRollPitchStickDeflected(void); throttleStatus_e calculateThrottleStatus(throttleStatusType_e type); rollPitchStatus_e calculateRollPitchCenterStatus(void); void processRcStickPositions(throttleStatus_e throttleStatus); diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c index ef1d9d41e5..f4de112384 100644 --- a/src/main/navigation/navigation.c +++ b/src/main/navigation/navigation.c @@ -1728,7 +1728,7 @@ static navigationFSMEvent_t navOnEnteringState_NAV_STATE_LAUNCH_WAIT(navigationF //allow to leave NAV_LAUNCH_MODE if it has being enabled as feature by moving sticks with low throttle. if (feature(FEATURE_FW_LAUNCH)) { throttleStatus_e throttleStatus = calculateThrottleStatus(THROTTLE_STATUS_TYPE_RC); - if ((throttleStatus == THROTTLE_LOW) && (areSticksDeflected())) { + if ((throttleStatus == THROTTLE_LOW) && (isRollPitchStickDeflected())) { abortFixedWingLaunch(); return NAV_FSM_EVENT_SWITCH_TO_IDLE; } diff --git a/src/main/navigation/navigation_fw_launch.c b/src/main/navigation/navigation_fw_launch.c index 42a8efc526..ea71f2a7b9 100755 --- a/src/main/navigation/navigation_fw_launch.c +++ b/src/main/navigation/navigation_fw_launch.c @@ -251,7 +251,7 @@ static inline bool isLaunchMaxAltitudeReached(void) static inline bool areSticksMoved(timeMs_t initialTime, timeUs_t currentTimeUs) { - return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && areSticksDeflected(); + return (initialTime + currentStateElapsedMs(currentTimeUs)) > navConfig()->fw.launch_min_time && isRollPitchStickDeflected(); } static void resetPidsIfNeeded(void) { @@ -435,7 +435,7 @@ static fixedWingLaunchEvent_t fwLaunchState_FW_LAUNCH_STATE_FINISH(timeUs_t curr const timeMs_t elapsedTimeMs = currentStateElapsedMs(currentTimeUs); const timeMs_t endTimeMs = navConfig()->fw.launch_end_time; - if (areSticksDeflected()) { + if (isRollPitchStickDeflected()) { return FW_LAUNCH_EVENT_ABORT; // cancel the launch and do the FW_LAUNCH_STATE_IDLE state } if (elapsedTimeMs > endTimeMs) { From b8189a3d3d952cc262e3e4e6c6450d3cd9dd46b5 Mon Sep 17 00:00:00 2001 From: Alexander van Saase Date: Sat, 12 Jun 2021 00:37:02 +0200 Subject: [PATCH 67/67] fix autotune max ff value bug --- src/main/flight/pid_autotune.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c index 5dcc40a12f..a3cc96e811 100755 --- a/src/main/flight/pid_autotune.c +++ b/src/main/flight/pid_autotune.c @@ -47,7 +47,7 @@ #include "flight/pid.h" #define AUTOTUNE_FIXED_WING_MIN_FF 10 -#define AUTOTUNE_FIXED_WING_MAX_FF 300 +#define AUTOTUNE_FIXED_WING_MAX_FF 255 #define AUTOTUNE_FIXED_WING_MIN_ROLL_PITCH_RATE 40 #define AUTOTUNE_FIXED_WING_MIN_YAW_RATE 10 #define AUTOTUNE_FIXED_WING_MAX_RATE 720