diff --git a/CMakeLists.txt b/CMakeLists.txt
index b73616735b..400e890b7f 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -22,6 +22,14 @@ endif()
option(COMPILER_VERSION_CHECK "Ensure the compiler matches the expected version" ON)
+include(GetGitRevisionDescription)
+get_git_head_revision(GIT_REFSPEC GIT_SHA1)
+string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV)
+
+# Load settings related functions, so the tests can use them
+include(main)
+include(settings)
+
if(TOOLCHAIN STREQUAL none)
add_subdirectory(src/test)
else()
@@ -49,10 +57,6 @@ if(CMAKE_BUILD_TYPE STREQUAL "Release" OR CMAKE_BUILD_TYPE STREQUAL "RelWithDebI
set(IS_RELEASE_BUILD ON)
endif()
-include(GetGitRevisionDescription)
-get_git_head_revision(GIT_REFSPEC GIT_SHA1)
-string(SUBSTRING ${GIT_SHA1} 0 8 GIT_REV)
-
set(FIRMWARE_VERSION ${PROJECT_VERSION})
option(WARNINGS_AS_ERRORS "Make all warnings into errors")
@@ -64,10 +68,8 @@ set(COMMON_COMPILE_DEFINITIONS
FC_VERSION_PATCH_LEVEL=${CMAKE_PROJECT_VERSION_PATCH}
)
-include(settings)
include(openocd)
include(svd)
-include(main)
include(stm32)
add_subdirectory(src)
diff --git a/cmake/settings.cmake b/cmake/settings.cmake
index 17d48168b4..5d4e4e3862 100644
--- a/cmake/settings.cmake
+++ b/cmake/settings.cmake
@@ -4,6 +4,7 @@ set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h")
set(SETTINGS_FILE "${MAIN_SRC_DIR}/fc/settings.yaml")
set(SETTINGS_GENERATOR "${MAIN_UTILS_DIR}/settings.rb")
+include(CMakeParseArguments)
function(enable_settings exe name)
get_generated_files_dir(dir ${name})
@@ -15,11 +16,26 @@ function(enable_settings exe name)
list(APPEND cflags ${options})
list(APPEND cflags ${includes})
list(APPEND cflags ${defs})
+
+ cmake_parse_arguments(
+ args
+ # Boolean arguments
+ ""
+ # Single value arguments
+ "OUTPUTS;SETTINGS_CXX"
+ # Multi-value arguments
+ ""
+ # Start parsing after the known arguments
+ ${ARGN}
+ )
+
+ set(output ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C})
add_custom_command(
- OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C}
+ OUTPUT ${output}
COMMAND
- ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH=$ENV{PATH}
+ ${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${name} PATH=$ENV{PATH} SETTINGS_CXX=${args_SETTINGS_CXX}
${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${MAIN_DIR} ${SETTINGS_FILE} -o "${dir}"
DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE}
)
+ set(${args_OUTPUTS} ${output} PARENT_SCOPE)
endfunction()
diff --git a/docs/Settings.md b/docs/Settings.md
index e5d99e738b..a2987a8270 100644
--- a/docs/Settings.md
+++ b/docs/Settings.md
@@ -12,8 +12,8 @@
| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
-| acc_notch_cutoff | | |
-| acc_notch_hz | | |
+| acc_notch_cutoff | 1 | |
+| acc_notch_hz | 0 | |
| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
@@ -22,17 +22,17 @@
| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
| airmode_throttle_threshold | 1300 | 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 | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
+| airspeed_adc_channel | :target | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
-| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
-| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
-| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
+| align_board_pitch | :zero | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
+| align_board_roll | :zero | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
+| align_board_yaw | :zero | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. |
| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. |
| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. |
-| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) |
+| align_opflow | CW0FLIP | Optical flow module alignment (default CW0_DEG_FLIP) |
| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] |
| antigravity_accelerator | 1 | |
| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain |
@@ -40,73 +40,73 @@
| applied_defaults | 0 | Internal (configurator) hint. Should not be changed manually |
| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. |
| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
-| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting |
+| baro_median_filter | True | 3-point median filtering for barometer readouts. No reason to change this setting |
| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation. 7S, 9S and 11S batteries cannot be autodetected. |
| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` |
| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. |
| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. |
| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). |
| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. |
-| blackbox_device | SPIFLASH | Selection of where to write blackbox data |
+| blackbox_device | :target | Selection of where to write blackbox data |
| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. |
| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations |
-| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
+| cpu_underclock | False | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit |
-| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
-| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. |
-| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. |
+| current_adc_channel | :target | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
+| current_meter_offset | :target | This sets the output offset voltage of the current sensor in millivolts. |
+| current_meter_scale | :target | 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 | | |
-| d_boost_gyro_delta_lpf_hz | | |
-| d_boost_max_at_acceleration | | |
+| d_boost_factor | 1.25 | |
+| d_boost_gyro_delta_lpf_hz | 80 | |
+| d_boost_max_at_acceleration | 7500 | |
| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
| 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 |
+| disarm_kill_switch | True | 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 | False | 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_speed_source | GROUND | Sets the speed type displayed by the DJI OSD: GROUND, 3D, AIR |
-| 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 | | Enables workarounds for different versions of MSP protocol used |
+| dji_use_name_for_messages | True | Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance |
+| dji_workarounds | 1 | Enables workarounds for different versions of MSP protocol used |
| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter |
-| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
+| dterm_lpf2_type | BIQUAD | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value |
-| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
-| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter |
+| 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 | False | Enable/disable dynamic gyro notch also known as Matrix Filter |
| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` |
| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches |
-| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers |
-| eleres_freq | | |
-| eleres_loc_delay | | |
-| eleres_loc_en | | |
-| eleres_loc_power | | |
-| eleres_signature | | |
-| eleres_telemetry_en | | |
-| eleres_telemetry_power | | |
-| esc_sensor_listen_only | OFF | Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case |
+| 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 | |
+| eleres_loc_delay | 240 | |
+| eleres_loc_en | False | |
+| eleres_loc_power | 7 | |
+| eleres_signature | :zero | |
+| eleres_telemetry_en | False | |
+| eleres_telemetry_power | 7 | |
+| esc_sensor_listen_only | False | Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case |
| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). |
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn |
-| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. |
+| failsafe_lights | True | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. |
| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. |
| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. |
| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. |
| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
-| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode |
+| failsafe_mission | True | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode |
| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). |
| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). |
| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. |
| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
-| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
-| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
+| failsafe_throttle_low_delay | 0 | 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 | False | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
| flip_over_after_crash_power_factor | 65 | flip over after crash power factor |
-| fpv_mix_degrees | | |
+| fpv_mix_degrees | 0 | |
| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
-| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
-| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
-| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data |
+| frsky_default_latitude | 0 | 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 | 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 | False | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data |
| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] |
| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] |
@@ -139,27 +139,27 @@
| fw_turn_assist_pitch_gain | 1 | 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 | 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 | 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_auto_baud | True | 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 | True | Enable automatic configuration of UBlox GPS receivers. |
| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. |
| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. |
| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). |
| gps_sbas_mode | NONE | Which SBAS mode to be used |
-| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. |
+| gps_ublox_use_galileo | False | 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_dyn_lpf_curve_expo | 5 | Expo value for the throttle-to-frequency mapping for Dynamic LPF |
| gyro_dyn_lpf_max_hz | 500 | Maximum frequency of the gyro Dynamic LPF |
| gyro_dyn_lpf_min_hz | 200 | 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_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
-| gyro_notch_cutoff | | |
-| gyro_notch_hz | | |
+| gyro_notch_cutoff | 1 | |
+| gyro_notch_hz | 0 | |
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) |
-| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
-| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
-| gyro_to_use | | |
-| 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 |
+| gyro_stage2_lowpass_type | BIQUAD | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
+| gyro_sync | True | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
+| gyro_to_use | 0 | |
+| gyro_use_dyn_lpf | False | Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position. |
+| has_flaps | False | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. |
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) |
@@ -177,65 +177,65 @@
| imu2_hardware | NONE | Selection of a Secondary IMU hardware type. NONE disables this functionality |
| imu2_radius_acc | 0 | Secondary IMU MAG calibration data |
| imu2_radius_mag | 0 | 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) |
+| imu2_use_for_osd_ahi | False | If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon |
+| imu2_use_for_osd_heading | False | If set to ON, Secondary IMU data will be used for Analog OSD heading |
+| imu2_use_for_stabilized | False | 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 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes |
| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) |
| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements |
| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements |
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements |
-| inav_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.000 | Uncertainty value for barometric sensor [cm] |
+| inav_allow_dead_reckoning | False | Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation |
+| inav_auto_mag_decl | True | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. |
+| inav_baro_epv | 100 | Uncertainty value for barometric sensor [cm] |
| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. |
-| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] |
+| inav_max_eph_epv | 1000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] |
| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] |
| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) |
| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
-| inav_use_gps_no_baro | | |
-| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. |
-| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation |
-| inav_w_xy_flow_p | | |
-| inav_w_xy_flow_v | | |
-| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. |
-| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed |
-| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost |
-| inav_w_xyz_acc_p | | |
-| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate |
-| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
-| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero |
-| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost |
-| inav_w_z_surface_p | | |
-| inav_w_z_surface_v | | |
+| inav_use_gps_no_baro | False | |
+| inav_use_gps_velned | True | 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 | Weight for accelerometer drift estimation |
+| inav_w_xy_flow_p | 1.0 | |
+| inav_w_xy_flow_v | 2.0 | |
+| inav_w_xy_gps_p | 1.0 | Weight of GPS coordinates in estimated UAV position and speed. |
+| inav_w_xy_gps_v | 2.0 | Weight of GPS velocity data in estimated UAV speed |
+| inav_w_xy_res_v | 0.5 | Decay coefficient for estimated velocity when GPS reference for position is lost |
+| inav_w_xyz_acc_p | 1.0 | |
+| inav_w_z_baro_p | 0.35 | Weight of barometer measurements in estimated altitude and climb rate |
+| inav_w_z_gps_p | 0.2 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
+| inav_w_z_gps_v | 0.1 | 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 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost |
+| inav_w_z_surface_p | 3.5 | |
+| inav_w_z_surface_v | 6.1 | |
| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) |
-| ledstrip_visual_beeper | OFF | |
-| log_level | `ERROR` | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. |
+| ledstrip_visual_beeper | False | |
+| log_level | ERROR | Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage. |
| log_topics | 0 | Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage. |
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. |
| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. |
| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
-| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target |
+| mag_to_use | 0 | 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 | Magnetometer calibration X gain. If 1024, no calibration or calibration failed |
| maggain_y | 1024 | Magnetometer calibration Y gain. If 1024, no calibration or calibration failed |
| maggain_z | 1024 | Magnetometer calibration Z gain. If 1024, no calibration or calibration failed |
-| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
-| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
-| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
+| magzero_x | :zero | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
+| magzero_y | :zero | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
+| magzero_z | :zero | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% |
| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] |
| manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] |
| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% |
| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% |
-| mavlink_ext_status_rate | | |
-| mavlink_extra1_rate | | |
-| mavlink_extra2_rate | | |
-| mavlink_extra3_rate | | |
-| mavlink_pos_rate | | |
-| mavlink_rc_chan_rate | | |
+| mavlink_ext_status_rate | 2 | |
+| mavlink_extra1_rate | 10 | |
+| mavlink_extra2_rate | 2 | |
+| mavlink_extra3_rate | 1 | |
+| mavlink_pos_rate | 2 | |
+| mavlink_rc_chan_rate | 5 | |
| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° |
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
@@ -252,8 +252,8 @@
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL |
| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW |
-| mc_iterm_relax | | |
-| mc_iterm_relax_cutoff | | |
+| mc_iterm_relax | RP | |
+| mc_iterm_relax_cutoff | 15 | |
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
@@ -265,19 +265,19 @@
| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. |
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
-| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. |
+| motor_direction_inverted | False | Use if you need to inverse yaw motor direction. |
| motor_poles | 14 | 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 | 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 | 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 string | Craft name |
+| name | | Craft name |
| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] |
| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] |
-| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing |
+| nav_disarm_on_landing | False | If set to ON, iNav disarms the FC after landing |
| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] |
| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used |
-| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing |
-| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll |
+| nav_fw_allow_manual_thr_increase | False | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing |
+| nav_fw_bank_angle | 35 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll |
| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error |
| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s |
@@ -289,7 +289,7 @@
| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s |
| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit |
| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] |
-| nav_fw_launch_end_time | 2000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] |
+| nav_fw_launch_end_time | 3000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] |
| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) |
| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. |
| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] |
@@ -306,15 +306,15 @@
| nav_fw_pitch2thr_smoothing | 6 | How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh. |
| nav_fw_pitch2thr_threshold | 50 | Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees] |
| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
-| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
-| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) |
+| nav_fw_pos_hdg_i | 2 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
+| nav_fw_pos_hdg_p | 30 | P gain of heading PID controller. (Fixedwing, rovers, boats) |
| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) |
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
-| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) |
-| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) |
-| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) |
+| nav_fw_pos_z_d | 10 | D gain of altitude PID controller (Fixedwing) |
+| nav_fw_pos_z_i | 5 | I gain of altitude PID controller (Fixedwing) |
+| nav_fw_pos_z_p | 40 | P gain of altitude PID controller (Fixedwing) |
| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course |
| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] |
| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] |
@@ -341,15 +341,15 @@
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
| nav_mc_vel_xy_dterm_attenuation | 90 | 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 | 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" | 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 | | |
-| nav_mc_vel_xy_ff | | |
+| nav_mc_vel_xy_dterm_attenuation_start | 10 | 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 | |
+| nav_mc_vel_xy_ff | 40 | |
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
| nav_mc_vel_z_i | 50 | I gain of velocity PID controller |
| nav_mc_vel_z_p | 100 | P gain of velocity PID controller |
-| nav_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_mc_wp_slowdown | True | 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 | 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 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) |
@@ -357,23 +357,23 @@
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details |
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
-| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
-| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
+| nav_rth_climb_first | True | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
+| nav_rth_climb_ignore_emerg | False | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
-| nav_rth_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_rth_tail_first | False | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
+| nav_use_fw_yaw_control | False | 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 | False | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude |
| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. |
| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius |
| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. |
-| opflow_hardware | | Selection of OPFLOW hardware. |
-| opflow_scale | | |
-| osd_ahi_bordered | OFF | Shows a border/corners around the AHI region (pixel OSD only) |
+| opflow_hardware | NONE | Selection of OPFLOW hardware. |
+| opflow_scale | 10.5 | |
+| osd_ahi_bordered | False | Shows a border/corners around the AHI region (pixel OSD only) |
| osd_ahi_height | 162 | AHI height in pixels (pixel OSD only) |
| osd_ahi_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon |
-| osd_ahi_reverse_roll | | |
+| osd_ahi_reverse_roll | False | |
| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. |
-| osd_ahi_vertical_offset | 0 | AHI vertical offset from center (pixel OSD only) |
+| osd_ahi_vertical_offset | -18 | AHI vertical offset from center (pixel OSD only) |
| osd_ahi_width | 132 | AHI width in pixels (pixel OSD only) |
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) |
@@ -381,155 +381,155 @@
| osd_camera_fov_h | 135 | Horizontal field of view for the camera in degres |
| osd_camera_fov_v | 85 | Vertical field of view for the camera in degres |
| osd_camera_uptilt | 0 | Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal |
-| osd_coordinate_digits | | |
+| osd_coordinate_digits | 9 | |
| 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 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. |
| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) |
| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
-| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
-| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe |
-| osd_force_grid | OFF | Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) |
+| osd_estimations_wind_compensation | True | Use wind estimation for remaining flight time/distance estimation |
+| osd_failsafe_switch_layout | False | If enabled the OSD automatically switches to the first layout during failsafe |
+| osd_force_grid | False | Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development) |
| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) |
| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) |
| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) |
-| osd_home_position_arm_screen | ON | Should home position coordinates be displayed on the arming screen. |
+| osd_home_position_arm_screen | True | Should home position coordinates be displayed on the arming screen. |
| osd_horizon_offset | 0 | To vertically adjust the whole OSD and AHI and scrolling bars |
-| osd_hud_homepoint | 0 | To 3D-display the home point location in the hud |
-| osd_hud_homing | 0 | To display little arrows around the crossair showing where the home point is in the hud |
+| osd_hud_homepoint | False | To 3D-display the home point location in the hud |
+| osd_hud_homing | False | To display little arrows around the crossair showing where the home point is in the hud |
| osd_hud_margin_h | 3 | Left and right margins for the hud area |
| osd_hud_margin_v | 3 | Top and bottom margins for the hud area |
| osd_hud_radar_disp | 0 | 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 | 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" | In meters, radar aircrafts further away than this will not be displayed in the hud |
+| osd_hud_radar_range_max | 4000 | In meters, radar aircrafts further away than this will not be displayed in the hud |
| osd_hud_radar_range_min | 3 | In meters, radar aircrafts closer than this will not be displayed in the hud |
| osd_hud_wp_disp | 0 | 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 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
-| osd_left_sidebar_scroll | | |
+| osd_left_sidebar_scroll | NONE | |
| osd_left_sidebar_scroll_step | 0 | How many units each sidebar step represents. 0 means the default value for the scroll type. |
| osd_link_quality_alarm | 70 | LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50% |
| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. |
| osd_neg_alt_alarm | 5 | Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
-| 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. |
+| osd_pan_servo_index | 0 | 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 | 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 | 10 | 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_digits | 11 | 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 | | |
+| osd_right_sidebar_scroll | NONE | |
| osd_right_sidebar_scroll_step | 0 | Same as left_sidebar_scroll_step, but for the right sidebar |
| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) |
| osd_rssi_alarm | 20 | Value below which to make the OSD RSSI indicator blink |
| osd_sidebar_horizontal_offset | 0 | Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges. |
-| osd_sidebar_scroll_arrows | | |
+| osd_sidebar_scroll_arrows | False | |
| osd_snr_alarm | 4 | Value below which Crossfire SNR Alarm pops-up. (dB) |
| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) |
| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` |
| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) |
| osd_units | METRIC | IMPERIAL, METRIC, UK |
| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` |
-| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` |
+| 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 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
-| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
-| pinio_box1 | target specific | Mode assignment for PINIO#1 |
-| pinio_box2 | target specific | Mode assignment for PINIO#1 |
-| pinio_box3 | target specific | Mode assignment for PINIO#1 |
-| pinio_box4 | target specific | Mode assignment for PINIO#1 |
+| pidsum_limit_yaw | 350 | 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 | Mode assignment for PINIO#1 |
+| pinio_box2 | :BOX_PERMANENT_ID_NONE | Mode assignment for PINIO#1 |
+| pinio_box3 | :BOX_PERMANENT_ID_NONE | Mode assignment for PINIO#1 |
+| pinio_box4 | :BOX_PERMANENT_ID_NONE | Mode assignment for PINIO#1 |
| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
| pitot_hardware | NONE | Selection of pitot hardware. |
-| pitot_lpf_milli_hz | | |
-| pitot_scale | | |
-| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
-| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo |
+| pitot_lpf_milli_hz | 350 | |
+| pitot_scale | 1.0 | |
+| platform_type | MULTIROTOR | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
+| pos_hold_deadband | 10 | Stick deadband in [r/c points], applied after r/c deadband and expo |
| prearm_timeout | 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 |
+| rangefinder_median_filter | False | 3-point median filtering for rangefinder readouts |
| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. |
| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. |
| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) |
| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values |
| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) |
| reboot_character | 82 | Special character used to trigger reboot |
-| receiver_type | `TARGET dependent` | 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 |
+| receiver_type | :target | Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL` |
+| report_cell_voltage | False | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON |
| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
-| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV |
+| rpm_gyro_filter_enabled | False | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV |
| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine |
-| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` |
+| rpm_gyro_min_hz | 100 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` |
| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting |
-| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
+| rssi_adc_channel | :target | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
| rssi_channel | 0 | RX channel containing the RSSI signal |
| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. |
| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). |
-| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` |
+| rssi_source | AUTO | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` |
| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation |
| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. |
| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. |
-| rx_spi_id | | |
-| rx_spi_protocol | | |
-| rx_spi_rf_channel_count | | |
+| rx_spi_id | :zero | |
+| rx_spi_protocol | :target | |
+| rx_spi_rf_channel_count | :zero | |
| safehome_max_distance | 20000 | In order for a safehome to be used, it must be less than this distance (in cm) from the arming point. |
-| sbus_sync_interval | | |
-| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. |
+| sbus_sync_interval | 3000 | |
+| sdcard_detect_inverted | :target | 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 | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
+| serialrx_inverted | False | 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 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
| servo_center_pulse | 1500 | Servo midpoint |
| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] |
| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) |
| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. |
-| setpoint_kalman_enabled | OFF | Enable Kalman filter on the PID controller setpoint |
+| setpoint_kalman_enabled | False | Enable Kalman filter on the PID controller setpoint |
| setpoint_kalman_q | 100 | 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 | Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets |
| setpoint_kalman_w | 4 | 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 string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. |
-| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. |
-| sim_pin | Empty string | PIN code for the SIM module |
-| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low |
+| sim_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. |
+| sim_low_altitude | -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 | 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 | Text message transmission interval in seconds for SIM module. Minimum value: 10 |
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] |
-| smartport_master_halfduplex | | |
-| smartport_master_inverted | | |
-| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX |
-| srxl2_baud_fast | | |
-| srxl2_unit_id | | |
-| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) |
+| smartport_master_halfduplex | True | |
+| smartport_master_inverted | False | |
+| spektrum_sat_bind | :SPEKTRUM_SAT_BIND_DISABLED | 0 = disabled. Used to bind the spektrum satellite to RX |
+| srxl2_baud_fast | True | |
+| srxl2_unit_id | 1 | |
+| stats | False | General switch of the statistics recording feature (a.k.a. odometer) |
| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. |
-| stats_total_energy | | |
+| stats_total_energy | 0 | |
| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. |
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
-| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
-| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. |
-| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. |
-| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
+| telemetry_halfduplex | True | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
+| telemetry_inverted | False | 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 | False | 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 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
| thr_expo | 0 | Throttle exposition value |
| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. |
| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. |
-| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% |
+| throttle_scale | 1.0 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% |
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
| tpa_breakpoint | 1500 | See tpa_rate. |
| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. |
-| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. |
+| tri_unarmed_servo | True | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. |
| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. |
| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs |
-| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled |
+| vbat_adc_channel | :target | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled |
| vbat_cell_detect_voltage | 425 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V. |
| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V |
-| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running |
+| vbat_meter_type | ADC | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running |
| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) |
-| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. |
+| vbat_scale | :target | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. |
| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) |
| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. |
| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. |
-| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. |
+| vtx_halfduplex | True | 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 | 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 | | |
+| vtx_pit_mode_chan | 1 | |
| vtx_power | 1 | 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. |
+| vtx_smartaudio_early_akk_workaround | True | Enable workaround for early AKK SAudio-enabled VTX bug. |
| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
-| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |
+| yaw_lpf_hz | 0 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |
| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
> Note: this table is autogenerated. Do not edit it manually.
\ No newline at end of file
diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c
index 2a98978442..a39aaed510 100644
--- a/src/main/blackbox/blackbox.c
+++ b/src/main/blackbox/blackbox.c
@@ -52,6 +52,7 @@
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
@@ -91,18 +92,18 @@
#endif
#ifdef SDCARD_DETECT_INVERTED
-#define BLACKBOX_INTERVED_CARD_DETECTION 1
+#define BLACKBOX_INVERTED_CARD_DETECTION 1
#else
-#define BLACKBOX_INTERVED_CARD_DETECTION 0
+#define BLACKBOX_INVERTED_CARD_DETECTION 0
#endif
PG_REGISTER_WITH_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 1);
PG_RESET_TEMPLATE(blackboxConfig_t, blackboxConfig,
.device = DEFAULT_BLACKBOX_DEVICE,
- .rate_num = 1,
- .rate_denom = 1,
- .invertedCardDetection = BLACKBOX_INTERVED_CARD_DETECTION,
+ .rate_num = SETTING_BLACKBOX_RATE_NUM_DEFAULT,
+ .rate_denom = SETTING_BLACKBOX_RATE_DENOM_DEFAULT,
+ .invertedCardDetection = BLACKBOX_INVERTED_CARD_DETECTION,
);
#define BLACKBOX_SHUTDOWN_TIMEOUT_MILLIS 200
@@ -1656,6 +1657,7 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("motorOutput", "%d,%d", getThrottleIdleValue(),motorConfig()->maxthrottle);
BLACKBOX_PRINT_HEADER_LINE("acc_1G", "%u", acc.dev.acc_1G);
+#ifdef USE_ADC
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
if (testBlackboxCondition(FLIGHT_LOG_FIELD_CONDITION_VBAT)) {
blackboxPrintfHeaderLine("vbat_scale", "%u", batteryMetersConfig()->voltage.scale / 10);
@@ -1667,6 +1669,7 @@ static bool blackboxWriteSysinfo(void)
currentBatteryProfile->voltage.cellWarning / 10,
currentBatteryProfile->voltage.cellMax / 10);
BLACKBOX_PRINT_HEADER_LINE("vbatref", "%u", vbatReference);
+#endif
BLACKBOX_PRINT_HEADER_LINE_CUSTOM(
//Note: Log even if this is a virtual current meter, since the virtual meter uses these parameters too:
@@ -1723,17 +1726,25 @@ static bool blackboxWriteSysinfo(void)
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_hz", "%d", gyroConfig()->gyro_soft_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf_type", "%d", gyroConfig()->gyro_soft_lpf_type);
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf2_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz);
+#ifdef USE_DYNAMIC_FILTERS
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ);
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz);
+#endif
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_notch_hz,
0);
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_notch_cutoff,
1);
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", accelerometerConfig()->acc_lpf_hz);
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
+#ifdef USE_BARO
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
+#endif
+#ifdef USE_MAG
BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", compassConfig()->mag_hardware);
+#else
+ BLACKBOX_PRINT_HEADER_LINE("mag_hardware", "%d", MAG_NONE);
+#endif
BLACKBOX_PRINT_HEADER_LINE("serialrx_provider", "%d", rxConfig()->serialrx_provider);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_protocol", "%d", motorConfig()->motorPwmProtocol);
BLACKBOX_PRINT_HEADER_LINE("motor_pwm_rate", "%d", motorConfig()->motorPwmRate);
diff --git a/src/main/common/log.c b/src/main/common/log.c
index 284589ca6d..24093c6595 100644
--- a/src/main/common/log.c
+++ b/src/main/common/log.c
@@ -39,6 +39,7 @@
#include "io/serial.h"
#include "fc/config.h"
+#include "fc/settings.h"
#include "msp/msp.h"
#include "msp/msp_serial.h"
@@ -54,6 +55,11 @@ static mspPort_t * mspLogPort = NULL;
PG_REGISTER(logConfig_t, logConfig, PG_LOG_CONFIG, 0);
+PG_RESET_TEMPLATE(logConfig_t, logConfig,
+ .level = SETTING_LOG_LEVEL_DEFAULT,
+ .topics = SETTING_LOG_TOPICS_DEFAULT
+);
+
void logInit(void)
{
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LOG);
diff --git a/src/main/common/time.c b/src/main/common/time.c
index 27faeeadfb..f1204c57f4 100644
--- a/src/main/common/time.c
+++ b/src/main/common/time.c
@@ -33,6 +33,8 @@
#include "drivers/time.h"
+#include "fc/settings.h"
+
// For the "modulo 4" arithmetic to work, we need a leap base year
#define REFERENCE_YEAR 2000
// Offset (seconds) from the UNIX epoch (1970-01-01) to 2000-01-01
@@ -55,8 +57,8 @@ static const uint16_t days[4][12] =
PG_REGISTER_WITH_RESET_TEMPLATE(timeConfig_t, timeConfig, PG_TIME_CONFIG, 1);
PG_RESET_TEMPLATE(timeConfig_t, timeConfig,
- .tz_offset = 0,
- .tz_automatic_dst = TZ_AUTO_DST_OFF,
+ .tz_offset = SETTING_TZ_OFFSET_DEFAULT,
+ .tz_automatic_dst = SETTING_TZ_AUTOMATIC_DST_DEFAULT,
);
static rtcTime_t dateTimeToRtcTime(const dateTime_t *dt)
diff --git a/src/main/config/general_settings.c b/src/main/config/general_settings.c
index 38b8ecf3e3..47015f8ee6 100644
--- a/src/main/config/general_settings.c
+++ b/src/main/config/general_settings.c
@@ -28,8 +28,10 @@
#include "config/general_settings.h"
+#include "fc/settings.h"
+
PG_REGISTER_WITH_RESET_TEMPLATE(generalSettings_t, generalSettings, PG_GENERAL_SETTINGS, 0);
PG_RESET_TEMPLATE(generalSettings_t, generalSettings,
- .appliedDefaults = APPLIED_DEFAULTS_NONE,
-);
\ No newline at end of file
+ .appliedDefaults = SETTING_APPLIED_DEFAULTS_DEFAULT,
+);
diff --git a/src/main/drivers/display.c b/src/main/drivers/display.c
index 5afe475184..2bb96175a1 100644
--- a/src/main/drivers/display.c
+++ b/src/main/drivers/display.c
@@ -30,6 +30,7 @@
#include "drivers/display_font_metadata.h"
#include "drivers/time.h"
+#include "fc/settings.h"
#define SW_BLINK_CYCLE_MS 200 // 200ms on / 200ms off
@@ -43,7 +44,7 @@
PG_REGISTER_WITH_RESET_TEMPLATE(displayConfig_t, displayConfig, PG_DISPLAY_CONFIG, 0);
PG_RESET_TEMPLATE(displayConfig_t, displayConfig,
- .force_sw_blink = false,
+ .force_sw_blink = SETTING_DISPLAY_FORCE_SW_BLINK_DEFAULT
);
static bool displayAttributesRequireEmulation(displayPort_t *instance, textAttributes_t attr)
diff --git a/src/main/fc/config.c b/src/main/fc/config.c
index 5fcf8a6d11..d38554bd21 100755
--- a/src/main/fc/config.c
+++ b/src/main/fc/config.c
@@ -112,11 +112,15 @@ PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG,
PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
.current_profile_index = 0,
.current_battery_profile_index = 0,
- .debug_mode = DEBUG_NONE,
- .i2c_speed = I2C_SPEED_400KHZ,
- .cpuUnderclock = 0,
- .throttle_tilt_compensation_strength = 0, // 0-100, 0 - disabled
- .name = { 0 }
+ .debug_mode = SETTING_DEBUG_MODE_DEFAULT,
+#ifdef USE_I2C
+ .i2c_speed = SETTING_I2C_SPEED_DEFAULT,
+#endif
+#ifdef USE_UNDERCLOCK
+ .cpuUnderclock = SETTING_CPU_UNDERCLOCK_DEFAULT,
+#endif
+ .throttle_tilt_compensation_strength = SETTING_THROTTLE_TILT_COMP_STR_DEFAULT, // 0-100, 0 - disabled
+ .name = SETTING_NAME_DEFAULT
);
PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0);
diff --git a/src/main/fc/config.h b/src/main/fc/config.h
index bab2d96eef..48dc455e71 100644
--- a/src/main/fc/config.h
+++ b/src/main/fc/config.h
@@ -73,8 +73,12 @@ typedef struct systemConfig_s {
uint8_t current_profile_index;
uint8_t current_battery_profile_index;
uint8_t debug_mode;
+#ifdef USE_I2C
uint8_t i2c_speed;
+#endif
+#ifdef USE_UNDERCLOCK
uint8_t cpuUnderclock;
+#endif
uint8_t throttle_tilt_compensation_strength; // the correction that will be applied at throttle_correction_angle.
char name[MAX_NAME_LENGTH + 1];
} systemConfig_t;
diff --git a/src/main/fc/controlrate_profile.c b/src/main/fc/controlrate_profile.c
index 1c633ec1bf..ba464a1fe6 100644
--- a/src/main/fc/controlrate_profile.c
+++ b/src/main/fc/controlrate_profile.c
@@ -29,6 +29,7 @@
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/rc_curves.h"
+#include "fc/settings.h"
const controlRateConfig_t *currentControlRateProfile;
@@ -40,31 +41,31 @@ void pgResetFn_controlRateProfiles(controlRateConfig_t *instance)
for (int i = 0; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
RESET_CONFIG(controlRateConfig_t, &instance[i],
.throttle = {
- .rcMid8 = 50,
- .rcExpo8 = 0,
- .dynPID = 0,
- .pa_breakpoint = 1500,
- .fixedWingTauMs = 0
+ .rcMid8 = SETTING_THR_MID_DEFAULT,
+ .rcExpo8 = SETTING_THR_EXPO_DEFAULT,
+ .dynPID = SETTING_TPA_RATE_DEFAULT,
+ .pa_breakpoint = SETTING_TPA_BREAKPOINT_DEFAULT,
+ .fixedWingTauMs = SETTING_FW_TPA_TIME_CONSTANT_DEFAULT
},
.stabilized = {
- .rcExpo8 = 70,
- .rcYawExpo8 = 20,
- .rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
- .rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT,
- .rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT,
+ .rcExpo8 = SETTING_RC_EXPO_DEFAULT,
+ .rcYawExpo8 = SETTING_RC_YAW_EXPO_DEFAULT,
+ .rates[FD_ROLL] = SETTING_ROLL_RATE_DEFAULT,
+ .rates[FD_PITCH] = SETTING_PITCH_RATE_DEFAULT,
+ .rates[FD_YAW] = SETTING_YAW_RATE_DEFAULT,
},
.manual = {
- .rcExpo8 = 70,
- .rcYawExpo8 = 20,
- .rates[FD_ROLL] = 100,
- .rates[FD_PITCH] = 100,
- .rates[FD_YAW] = 100
+ .rcExpo8 = SETTING_MANUAL_RC_EXPO_DEFAULT,
+ .rcYawExpo8 = SETTING_MANUAL_RC_YAW_EXPO_DEFAULT,
+ .rates[FD_ROLL] = SETTING_MANUAL_ROLL_RATE_DEFAULT,
+ .rates[FD_PITCH] = SETTING_MANUAL_PITCH_RATE_DEFAULT,
+ .rates[FD_YAW] = SETTING_MANUAL_YAW_RATE_DEFAULT
},
.misc = {
- .fpvCamAngleDegrees = 0,
+ .fpvCamAngleDegrees = SETTING_FPV_MIX_DEGREES_DEFAULT
}
);
}
diff --git a/src/main/fc/controlrate_profile.h b/src/main/fc/controlrate_profile.h
index b8428347aa..b425148581 100644
--- a/src/main/fc/controlrate_profile.h
+++ b/src/main/fc/controlrate_profile.h
@@ -33,10 +33,8 @@ and so on.
*/
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX 180
#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN 6
-#define CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_YAW_RATE_MAX 180
#define CONTROL_RATE_CONFIG_YAW_RATE_MIN 2
-#define CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT 20
#define CONTROL_RATE_CONFIG_TPA_MAX 100
diff --git a/src/main/fc/fc_core.c b/src/main/fc/fc_core.c
index d4de465bac..40c18fd31f 100755
--- a/src/main/fc/fc_core.c
+++ b/src/main/fc/fc_core.c
@@ -417,9 +417,11 @@ void disarm(disarmReason_t disarmReason)
#endif
statsOnDisarm();
logicConditionReset();
-#ifdef USE_PROGRAMMING_FRAMEWORK
+
+#ifdef USE_PROGRAMMING_FRAMEWORK
programmingPidReset();
-#endif
+#endif
+
beeper(BEEPER_DISARMING); // emit disarm tone
prearmWasReset = false;
@@ -527,10 +529,11 @@ void tryArm(void)
//It is required to inform the mixer that arming was executed and it has to switch to the FORWARD direction
ENABLE_STATE(SET_REVERSIBLE_MOTORS_FORWARD);
logicConditionReset();
-
-#ifdef USE_PROGRAMMING_FRAMEWORK
+
+#ifdef USE_PROGRAMMING_FRAMEWORK
programmingPidReset();
-#endif
+#endif
+
headFreeModeHold = DECIDEGREES_TO_DEGREES(attitude.values.yaw);
resetHeadingHoldTarget(DECIDEGREES_TO_DEGREES(attitude.values.yaw));
diff --git a/src/main/fc/fc_init.c b/src/main/fc/fc_init.c
index 38f69891fb..ce6fecb053 100644
--- a/src/main/fc/fc_init.c
+++ b/src/main/fc/fc_init.c
@@ -220,8 +220,12 @@ void init(void)
ensureEEPROMContainsValidData();
readEEPROM();
+#ifdef USE_UNDERCLOCK
// Re-initialize system clock to their final values (if necessary)
systemClockSetup(systemConfig()->cpuUnderclock);
+#else
+ systemClockSetup(false);
+#endif
#ifdef USE_I2C
i2cSetSpeed(systemConfig()->i2c_speed);
diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c
index 0e47385044..5fdcebc9e1 100644
--- a/src/main/fc/fc_msp.c
+++ b/src/main/fc/fc_msp.c
@@ -487,7 +487,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, gyroRateDps(i));
}
for (int i = 0; i < 3; i++) {
+#ifdef USE_MAG
sbufWriteU16(dst, mag.magADC[i]);
+#else
+ sbufWriteU16(dst, 0);
+#endif
}
}
break;
@@ -785,12 +789,23 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU8(dst, rxConfig()->rssi_channel);
sbufWriteU8(dst, 0);
+#ifdef USE_MAG
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
+#else
+ sbufWriteU16(dst, 0);
+#endif
+#ifdef USE_ADC
sbufWriteU8(dst, batteryMetersConfig()->voltage.scale / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
+#else
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+#endif
break;
case MSP2_INAV_MISC:
@@ -813,8 +828,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
#endif
sbufWriteU8(dst, rxConfig()->rssi_channel);
+#ifdef USE_MAG
sbufWriteU16(dst, compassConfig()->mag_declination / 10);
+#else
+ sbufWriteU16(dst, 0);
+#endif
+#ifdef USE_ADC
sbufWriteU16(dst, batteryMetersConfig()->voltage.scale);
sbufWriteU8(dst, batteryMetersConfig()->voltageSource);
sbufWriteU8(dst, currentBatteryProfile->cells);
@@ -822,6 +842,15 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
+#else
+ sbufWriteU16(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+#endif
sbufWriteU32(dst, currentBatteryProfile->capacity.value);
sbufWriteU32(dst, currentBatteryProfile->capacity.warning);
@@ -841,6 +870,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP2_INAV_BATTERY_CONFIG:
+#ifdef USE_ADC
sbufWriteU16(dst, batteryMetersConfig()->voltage.scale);
sbufWriteU8(dst, batteryMetersConfig()->voltageSource);
sbufWriteU8(dst, currentBatteryProfile->cells);
@@ -848,6 +878,15 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMin);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellMax);
sbufWriteU16(dst, currentBatteryProfile->voltage.cellWarning);
+#else
+ sbufWriteU16(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+ sbufWriteU16(dst, 0);
+#endif
sbufWriteU16(dst, batteryMetersConfig()->current.offset);
sbufWriteU16(dst, batteryMetersConfig()->current.scale);
@@ -947,10 +986,17 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
break;
case MSP_VOLTAGE_METER_CONFIG:
+#ifdef USE_ADC
sbufWriteU8(dst, batteryMetersConfig()->voltage.scale / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMin / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellMax / 10);
sbufWriteU8(dst, currentBatteryProfile->voltage.cellWarning / 10);
+#else
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+ sbufWriteU8(dst, 0);
+#endif
break;
case MSP_CURRENT_METER_CONFIG:
@@ -969,15 +1015,25 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
sbufWriteU16(dst, rxConfig()->maxcheck);
sbufWriteU16(dst, PWM_RANGE_MIDDLE);
sbufWriteU16(dst, rxConfig()->mincheck);
+#ifdef USE_SPEKTRUM_BIND
sbufWriteU8(dst, rxConfig()->spektrum_sat_bind);
+#else
+ sbufWriteU8(dst, 0);
+#endif
sbufWriteU16(dst, rxConfig()->rx_min_usec);
sbufWriteU16(dst, rxConfig()->rx_max_usec);
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolation)
sbufWriteU8(dst, 0); // for compatibility with betaflight (rcInterpolationInterval)
sbufWriteU16(dst, 0); // for compatibility with betaflight (airModeActivateThreshold)
+#ifdef USE_RX_SPI
sbufWriteU8(dst, rxConfig()->rx_spi_protocol);
sbufWriteU32(dst, rxConfig()->rx_spi_id);
sbufWriteU8(dst, rxConfig()->rx_spi_rf_channel_count);
+#else
+ sbufWriteU8(dst, 0);
+ sbufWriteU32(dst, 0);
+ sbufWriteU8(dst, 0);
+#endif
sbufWriteU8(dst, 0); // for compatibility with betaflight (fpvCamAngleDegrees)
sbufWriteU8(dst, rxConfig()->receiverType);
break;
@@ -1154,7 +1210,11 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
case MSP_SENSOR_ALIGNMENT:
sbufWriteU8(dst, gyroConfig()->gyro_align);
sbufWriteU8(dst, accelerometerConfig()->acc_align);
+#ifdef USE_MAG
sbufWriteU8(dst, compassConfig()->mag_align);
+#else
+ sbufWriteU8(dst, 0);
+#endif
#ifdef USE_OPFLOW
sbufWriteU8(dst, opticalFlowConfig()->opflow_align);
#else
@@ -1831,10 +1891,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif
+#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10; // vbatlevel_warn1 in MWC2.3 GUI
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10; // vbatlevel_warn2 in MWC2.3 GUI
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10; // vbatlevel when buzzer starts to alert
+#else
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+#endif
} else
return MSP_RESULT_ERROR;
break;
@@ -1869,6 +1936,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
sbufReadU16(src);
#endif
+#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU16(src);
batteryMetersConfigMutable()->voltageSource = sbufReadU8(src);
currentBatteryProfileMutable->cells = sbufReadU8(src);
@@ -1876,6 +1944,15 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
+#else
+ sbufReadU16(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+#endif
currentBatteryProfileMutable->capacity.value = sbufReadU32(src);
currentBatteryProfileMutable->capacity.warning = sbufReadU32(src);
@@ -1895,6 +1972,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP2_INAV_SET_BATTERY_CONFIG:
if (dataSize == 29) {
+#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU16(src);
batteryMetersConfigMutable()->voltageSource = sbufReadU8(src);
currentBatteryProfileMutable->cells = sbufReadU8(src);
@@ -1902,6 +1980,15 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
currentBatteryProfileMutable->voltage.cellMin = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellMax = sbufReadU16(src);
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU16(src);
+#else
+ sbufReadU16(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+ sbufReadU16(src);
+#endif
batteryMetersConfigMutable()->current.offset = sbufReadU16(src);
batteryMetersConfigMutable()->current.scale = sbufReadU16(src);
@@ -2538,10 +2625,17 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
case MSP_SET_VOLTAGE_METER_CONFIG:
if (dataSize >= 4) {
+#ifdef USE_ADC
batteryMetersConfigMutable()->voltage.scale = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMin = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellMax = sbufReadU8(src) * 10;
currentBatteryProfileMutable->voltage.cellWarning = sbufReadU8(src) * 10;
+#else
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+ sbufReadU8(src);
+#endif
} else
return MSP_RESULT_ERROR;
break;
@@ -2570,15 +2664,25 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
rxConfigMutable()->maxcheck = sbufReadU16(src);
sbufReadU16(src); // midrc
rxConfigMutable()->mincheck = sbufReadU16(src);
+#ifdef USE_SPEKTRUM_BIND
rxConfigMutable()->spektrum_sat_bind = sbufReadU8(src);
+#else
+ sbufReadU8(src);
+#endif
rxConfigMutable()->rx_min_usec = sbufReadU16(src);
rxConfigMutable()->rx_max_usec = sbufReadU16(src);
sbufReadU8(src); // for compatibility with betaflight (rcInterpolation)
sbufReadU8(src); // for compatibility with betaflight (rcInterpolationInterval)
sbufReadU16(src); // for compatibility with betaflight (airModeActivateThreshold)
+#ifdef USE_RX_SPI
rxConfigMutable()->rx_spi_protocol = sbufReadU8(src);
rxConfigMutable()->rx_spi_id = sbufReadU32(src);
rxConfigMutable()->rx_spi_rf_channel_count = sbufReadU8(src);
+#else
+ sbufReadU8(src);
+ sbufReadU32(src);
+ sbufReadU8(src);
+#endif
sbufReadU8(src); // for compatibility with betaflight (fpvCamAngleDegrees)
rxConfigMutable()->receiverType = sbufReadU8(src); // Won't be modified if buffer is not large enough
} else
diff --git a/src/main/fc/fc_msp_box.h b/src/main/fc/fc_msp_box.h
index cefbeab29f..ac3604d809 100644
--- a/src/main/fc/fc_msp_box.h
+++ b/src/main/fc/fc_msp_box.h
@@ -19,9 +19,7 @@
#include "fc/rc_modes.h"
-#define BOX_PERMANENT_ID_USER1 47
-#define BOX_PERMANENT_ID_USER2 48
-#define BOX_PERMANENT_ID_NONE 255 // A permanent ID for no box mode
+#include "io/piniobox.h"
typedef struct box_s {
const uint8_t boxId; // see boxId_e
diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c
index 51b9b2d605..563d181fb6 100644
--- a/src/main/fc/rc_controls.c
+++ b/src/main/fc/rc_controls.c
@@ -44,6 +44,7 @@
#include "fc/rc_curves.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/pid.h"
#include "flight/failsafe.h"
@@ -73,22 +74,22 @@ FASTRAM int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and
PG_REGISTER_WITH_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig, PG_RC_CONTROLS_CONFIG, 2);
PG_RESET_TEMPLATE(rcControlsConfig_t, rcControlsConfig,
- .deadband = 5,
- .yaw_deadband = 5,
- .pos_hold_deadband = 10,
- .alt_hold_deadband = 50,
- .mid_throttle_deadband = 50,
- .airmodeHandlingType = STICK_CENTER,
- .airmodeThrottleThreshold = AIRMODE_THROTTLE_THRESHOLD,
+ .deadband = SETTING_DEADBAND_DEFAULT,
+ .yaw_deadband = SETTING_YAW_DEADBAND_DEFAULT,
+ .pos_hold_deadband = SETTING_POS_HOLD_DEADBAND_DEFAULT,
+ .alt_hold_deadband = SETTING_ALT_HOLD_DEADBAND_DEFAULT,
+ .mid_throttle_deadband = SETTING_3D_DEADBAND_THROTTLE_DEFAULT,
+ .airmodeHandlingType = SETTING_AIRMODE_TYPE_DEFAULT,
+ .airmodeThrottleThreshold = SETTING_AIRMODE_THROTTLE_THRESHOLD_DEFAULT,
);
PG_REGISTER_WITH_RESET_TEMPLATE(armingConfig_t, armingConfig, PG_ARMING_CONFIG, 2);
PG_RESET_TEMPLATE(armingConfig_t, armingConfig,
- .fixed_wing_auto_arm = 0,
- .disarm_kill_switch = 1,
- .switchDisarmDelayMs = DEFAULT_RC_SWITCH_DISARM_DELAY_MS,
- .prearmTimeoutMs = DEFAULT_PREARM_TIMEOUT,
+ .fixed_wing_auto_arm = SETTING_FIXED_WING_AUTO_ARM_DEFAULT,
+ .disarm_kill_switch = SETTING_DISARM_KILL_SWITCH_DEFAULT,
+ .switchDisarmDelayMs = SETTING_SWITCH_DISARM_DELAY_DEFAULT,
+ .prearmTimeoutMs = SETTING_PREARM_TIMEOUT_DEFAULT,
);
bool areSticksInApModePosition(uint16_t ap_mode)
diff --git a/src/main/fc/rc_modes.c b/src/main/fc/rc_modes.c
index 785660e384..48dface10e 100755
--- a/src/main/fc/rc_modes.c
+++ b/src/main/fc/rc_modes.c
@@ -34,6 +34,7 @@
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "rx/rx.h"
@@ -56,6 +57,10 @@ boxBitmask_t rcModeActivationMask; // one bit per mode defined in boxId_e
PG_REGISTER_ARRAY(modeActivationCondition_t, MAX_MODE_ACTIVATION_CONDITION_COUNT, modeActivationConditions, PG_MODE_ACTIVATION_PROFILE, 0);
PG_REGISTER(modeActivationOperatorConfig_t, modeActivationOperatorConfig, PG_MODE_ACTIVATION_OPERATOR_CONFIG, 0);
+PG_RESET_TEMPLATE(modeActivationOperatorConfig_t, modeActivationOperatorConfig,
+ .modeActivationOperator = SETTING_MODE_RANGE_LOGIC_OPERATOR_DEFAULT
+);
+
static void processAirmodeAirplane(void) {
if (feature(FEATURE_AIRMODE) || IS_RC_MODE_ACTIVE(BOXAIRMODE)) {
ENABLE_STATE(AIRMODE_ACTIVE);
diff --git a/src/main/fc/settings.yaml b/src/main/fc/settings.yaml
index 3a446cf6b6..264a1abfcb 100644
--- a/src/main/fc/settings.yaml
+++ b/src/main/fc/settings.yaml
@@ -171,11 +171,11 @@ groups:
members:
- name: looptime
description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible."
- default_value: "1000"
+ default_value: 1000
max: 9000
- name: gyro_sync
description: "This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf"
- default_value: "OFF"
+ default_value: ON
field: gyroSync
type: bool
- name: align_gyro
@@ -191,7 +191,7 @@ groups:
table: gyro_lpf
- name: gyro_lpf_hz
description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value."
- default_value: "60"
+ default_value: 60
field: gyro_soft_lpf_hz
max: 200
- name: gyro_lpf_type
@@ -201,72 +201,74 @@ groups:
table: filter_type
- name: moron_threshold
description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered."
- default_value: "32"
+ default_value: 32
field: gyroMovementCalibrationThreshold
max: 128
- name: gyro_notch_hz
field: gyro_notch_hz
max: 500
+ default_value: 0
- name: gyro_notch_cutoff
field: gyro_notch_cutoff
min: 1
max: 500
+ default_value: 1
- name: gyro_stage2_lowpass_hz
description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)"
- default_value: "0"
+ default_value: 0
field: gyro_stage2_lowpass_hz
min: 0
max: 500
- name: gyro_stage2_lowpass_type
description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
- default_value: "`BIQUAD`"
+ default_value: BIQUAD
field: gyro_stage2_lowpass_type
table: filter_type
- name: gyro_use_dyn_lpf
description: "Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position."
- default_value: "OFF"
+ default_value: OFF
field: useDynamicLpf
type: bool
- name: gyro_dyn_lpf_min_hz
description: "Minimum frequency of the gyro Dynamic LPF"
- default_value: "200"
+ default_value: 200
field: gyroDynamicLpfMinHz
min: 40
max: 400
- name: gyro_dyn_lpf_max_hz
description: "Maximum frequency of the gyro Dynamic LPF"
- default_value: "500"
+ default_value: 500
field: gyroDynamicLpfMaxHz
min: 40
max: 1000
- name: gyro_dyn_lpf_curve_expo
description: "Expo value for the throttle-to-frequency mapping for Dynamic LPF"
- default_value: "5"
+ default_value: 5
field: gyroDynamicLpfCurveExpo
min: 1
max: 10
- name: dynamic_gyro_notch_enabled
description: "Enable/disable dynamic gyro notch also known as Matrix Filter"
- default_value: "`OFF`"
+ default_value: OFF
field: dynamicGyroNotchEnabled
condition: USE_DYNAMIC_FILTERS
type: bool
- name: dynamic_gyro_notch_range
description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers"
- default_value: "`MEDIUM`"
+ default_value: "MEDIUM"
field: dynamicGyroNotchRange
condition: USE_DYNAMIC_FILTERS
table: dynamicFilterRangeTable
- name: dynamic_gyro_notch_q
description: "Q factor for dynamic notches"
- default_value: "120"
+ default_value: 120
field: dynamicGyroNotchQ
condition: USE_DYNAMIC_FILTERS
min: 1
max: 1000
- name: dynamic_gyro_notch_min_hz
description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`"
- default_value: "150"
+ default_value: 150
field: dynamicGyroNotchMinHz
condition: USE_DYNAMIC_FILTERS
min: 30
@@ -275,6 +277,7 @@ groups:
condition: USE_DUAL_GYRO
min: 0
max: 1
+ default_value: 0
- name: PG_ADC_CHANNEL_CONFIG
type: adcChannelConfig_t
@@ -283,25 +286,25 @@ groups:
members:
- name: vbat_adc_channel
description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled"
- default_value: "-"
+ default_value: :target
field: adcFunctionChannel[ADC_BATTERY]
min: ADC_CHN_NONE
max: ADC_CHN_MAX
- name: rssi_adc_channel
description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled"
- default_value: "-"
+ default_value: :target
field: adcFunctionChannel[ADC_RSSI]
min: ADC_CHN_NONE
max: ADC_CHN_MAX
- name: current_adc_channel
description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled"
- default_value: "-"
+ default_value: :target
field: adcFunctionChannel[ADC_CURRENT]
min: ADC_CHN_NONE
max: ADC_CHN_MAX
- name: airspeed_adc_channel
description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0"
- default_value: "0"
+ default_value: :target
field: adcFunctionChannel[ADC_AIRSPEED]
min: ADC_CHN_NONE
max: ADC_CHN_MAX
@@ -313,9 +316,11 @@ groups:
- name: acc_notch_hz
min: 0
max: 255
+ default_value: 0
- name: acc_notch_cutoff
min: 1
max: 255
+ default_value: 1
- name: align_acc
description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP."
default_value: "DEFAULT"
@@ -328,7 +333,7 @@ groups:
table: acc_hardware
- name: acc_lpf_hz
description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value."
- default_value: "15"
+ default_value: 15
min: 0
max: 200
- name: acc_lpf_type
@@ -338,37 +343,37 @@ groups:
table: filter_type
- name: acczero_x
description: "Calculated value after '6 position avanced calibration'. See Wiki page."
- default_value: "0"
+ default_value: 0
field: accZero.raw[X]
min: INT16_MIN
max: INT16_MAX
- name: acczero_y
description: "Calculated value after '6 position avanced calibration'. See Wiki page."
- default_value: "0"
+ default_value: 0
field: accZero.raw[Y]
min: INT16_MIN
max: INT16_MAX
- name: acczero_z
description: "Calculated value after '6 position avanced calibration'. See Wiki page."
- default_value: "0"
+ default_value: 0
field: accZero.raw[Z]
min: INT16_MIN
max: INT16_MAX
- name: accgain_x
description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
- default_value: "4096"
+ default_value: 4096
field: accGain.raw[X]
min: 1
max: 8192
- name: accgain_y
description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
- default_value: "4096"
+ default_value: 4096
field: accGain.raw[Y]
min: 1
max: 8192
- name: accgain_z
description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
- default_value: "4096"
+ default_value: 4096
field: accGain.raw[Z]
min: 1
max: 8192
@@ -384,7 +389,7 @@ groups:
default_value: "NONE"
- name: rangefinder_median_filter
description: "3-point median filtering for rangefinder readouts"
- default_value: "OFF"
+ default_value: OFF
field: use_median_filtering
type: bool
@@ -395,14 +400,15 @@ groups:
members:
- name: opflow_hardware
description: "Selection of OPFLOW hardware."
- default: "NONE"
+ default_value: NONE
table: opflow_hardware
- name: opflow_scale
min: 0
max: 10000
+ default_value: 10.5
- name: align_opflow
description: "Optical flow module alignment (default CW0_DEG_FLIP)"
- default_value: "5"
+ default_value: CW0FLIP
field: opflow_align
type: uint8_t
table: alignment
@@ -419,83 +425,83 @@ groups:
table: secondary_imu_hardware
- name: imu2_use_for_osd_heading
description: "If set to ON, Secondary IMU data will be used for Analog OSD heading"
- default_value: "OFF"
+ default_value: OFF
field: useForOsdHeading
type: bool
- name: imu2_use_for_osd_ahi
description: "If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon"
field: useForOsdAHI
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: imu2_use_for_stabilized
description: "If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH)"
field: useForStabilized
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: imu2_align_roll
description: "Roll alignment for Secondary IMU. 1/10 of a degree"
field: rollDeciDegrees
- default_value: "0"
+ default_value: 0
min: -1800
max: 3600
- name: imu2_align_pitch
description: "Pitch alignment for Secondary IMU. 1/10 of a degree"
field: pitchDeciDegrees
- default_value: "0"
+ default_value: 0
min: -1800
max: 3600
- name: imu2_align_yaw
description: "Yaw alignment for Secondary IMU. 1/10 of a degree"
field: yawDeciDegrees
- default_value: "0"
+ default_value: 0
min: -1800
max: 3600
- name: imu2_gain_acc_x
description: "Secondary IMU ACC calibration data"
field: calibrationOffsetAcc[X]
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_gain_acc_y
field: calibrationOffsetAcc[Y]
description: "Secondary IMU ACC calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_gain_acc_z
field: calibrationOffsetAcc[Z]
description: "Secondary IMU ACC calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_gain_mag_x
field: calibrationOffsetMag[X]
description: "Secondary IMU MAG calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_gain_mag_y
field: calibrationOffsetMag[Y]
description: "Secondary IMU MAG calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_gain_mag_z
field: calibrationOffsetMag[Z]
description: "Secondary IMU MAG calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_radius_acc
field: calibrationRadiusAcc
description: "Secondary IMU MAG calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
- name: imu2_radius_mag
field: calibrationRadiusMag
description: "Secondary IMU MAG calibration data"
- default_value: "0"
+ default_value: 0
min: INT16_MIN
max: INT16_MAX
@@ -516,48 +522,48 @@ groups:
table: mag_hardware
- name: mag_declination
description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix."
- default_value: "0"
+ default_value: 0
min: -18000
max: 18000
- name: magzero_x
description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed."
- default_value: "0"
+ default_value: :zero
field: magZero.raw[X]
min: INT16_MIN
max: INT16_MAX
- name: magzero_y
description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed."
- default_value: "0"
+ default_value: :zero
field: magZero.raw[Y]
min: INT16_MIN
max: INT16_MAX
- name: magzero_z
description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed."
- default_value: "0"
+ default_value: :zero
field: magZero.raw[Z]
min: INT16_MIN
max: INT16_MAX
- name: maggain_x
description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed"
- default_value: "1024"
+ default_value: 1024
field: magGain[X]
min: INT16_MIN
max: INT16_MAX
- name: maggain_y
description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed"
- default_value: "1024"
+ default_value: 1024
field: magGain[Y]
min: INT16_MIN
max: INT16_MAX
- name: maggain_z
description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed"
- default_value: "1024"
+ default_value: 1024
field: magGain[Z]
min: INT16_MIN
max: INT16_MAX
- name: mag_calibration_time
description: "Adjust how long time the Calibration of mag will last."
- default_value: "30"
+ default_value: 30
field: magCalibrationTimeLimit
min: 20
max: 120
@@ -566,21 +572,22 @@ groups:
condition: USE_DUAL_MAG
min: 0
max: 1
+ default_value: 0
- name: align_mag_roll
description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw."
- default_value: "0"
+ default_value: 0
field: rollDeciDegrees
min: -1800
max: 3600
- name: align_mag_pitch
description: "Same as align_mag_roll, but for the pitch axis."
- default_value: "0"
+ default_value: 0
field: pitchDeciDegrees
min: -1800
max: 3600
- name: align_mag_yaw
description: "Same as align_mag_roll, but for the yaw axis."
- default_value: "0"
+ default_value: 0
field: yawDeciDegrees
min: -1800
max: 3600
@@ -596,12 +603,12 @@ groups:
table: baro_hardware
- name: baro_median_filter
description: "3-point median filtering for barometer readouts. No reason to change this setting"
- default_value: "ON"
+ default_value: ON
field: use_median_filtering
type: bool
- name: baro_cal_tolerance
description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]."
- default_value: "150"
+ default_value: 150
field: baro_calibration_tolerance
min: 0
max: 1000
@@ -618,9 +625,11 @@ groups:
- name: pitot_lpf_milli_hz
min: 0
max: 10000
+ default_value: 350
- name: pitot_scale
min: 0
max: 100
+ default_value: 1.0
- name: PG_RX_CONFIG
type: rxConfig_t
@@ -628,40 +637,40 @@ groups:
members:
- name: receiver_type
description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`"
- default_value: "`TARGET dependent`"
+ default_value: :target
field: receiverType
table: receiver_type
- name: min_check
description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value."
- default_value: "1100"
+ default_value: 1100
field: mincheck
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: max_check
description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value."
- default_value: "1900"
+ default_value: 1900
field: maxcheck
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: rssi_source
description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`"
- default_value: "`AUTO`"
+ default_value: "AUTO"
field: rssi_source
table: rssi_source
- name: rssi_channel
description: "RX channel containing the RSSI signal"
- default_value: "0"
+ default_value: 0
min: 0
max: MAX_SUPPORTED_RC_CHANNEL_COUNT
- name: rssi_min
description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)."
- default_value: "0"
+ default_value: 0
field: rssiMin
min: RSSI_VISIBLE_VALUE_MIN
max: RSSI_VISIBLE_VALUE_MAX
- name: rssi_max
description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min."
- default_value: "100"
+ default_value: 100
field: rssiMax
min: RSSI_VISIBLE_VALUE_MIN
max: RSSI_VISIBLE_VALUE_MAX
@@ -669,53 +678,60 @@ groups:
field: sbusSyncInterval
min: 500
max: 10000
+ default_value: 3000
- name: rc_filter_frequency
description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values"
- default_value: "50"
+ default_value: 50
field: rcFilterFrequency
min: 0
max: 100
- name: serialrx_provider
description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section."
- default_value: "SPEK1024"
+ default_value: :target
condition: USE_SERIAL_RX
table: serial_rx
- name: serialrx_inverted
description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)."
- default_value: "OFF"
+ default_value: OFF
condition: USE_SERIAL_RX
type: bool
- name: rx_spi_protocol
condition: USE_RX_SPI
table: rx_spi_protocol
+ default_value: :target
- name: rx_spi_id
condition: USE_RX_SPI
min: 0
max: 0
+ default_value: :zero
- name: rx_spi_rf_channel_count
+ condition: USE_RX_SPI
min: 0
max: 8
+ default_value: :zero
- name: spektrum_sat_bind
description: "0 = disabled. Used to bind the spektrum satellite to RX"
- default_value: "0"
condition: USE_SPEKTRUM_BIND
min: SPEKTRUM_SAT_BIND_DISABLED
max: SPEKTRUM_SAT_BIND_MAX
+ default_value: :SPEKTRUM_SAT_BIND_DISABLED
- name: srxl2_unit_id
condition: USE_SERIALRX_SRXL2
min: 0
max: 15
+ default_value: 1
- name: srxl2_baud_fast
condition: USE_SERIALRX_SRXL2
- table: off_on
+ type: bool
+ default_value: ON
- name: rx_min_usec
description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc."
- default_value: "885"
+ default_value: 885
min: PWM_PULSE_MIN
max: PWM_PULSE_MAX
- name: rx_max_usec
description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc."
- default_value: "2115"
+ default_value: 2115
min: PWM_PULSE_MIN
max: PWM_PULSE_MAX
- name: serialrx_halfduplex
@@ -725,7 +741,7 @@ groups:
table: tristate
- name: msp_override_channels
description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode."
- default_value: "0"
+ default_value: 0
field: mspOverrideChannels
condition: USE_MSP_RC_OVERRIDE
min: 0
@@ -738,24 +754,24 @@ groups:
members:
- name: blackbox_rate_num
description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations"
- default_value: "1"
+ default_value: 1
field: rate_num
min: 1
max: 65535
- name: blackbox_rate_denom
description: "Blackbox logging rate denominator. See blackbox_rate_num."
- default_value: "1"
+ default_value: 1
field: rate_denom
min: 1
max: 65535
- name: blackbox_device
description: "Selection of where to write blackbox data"
- default_value: "SPIFLASH"
+ default_value: :target
field: device
table: blackbox_device
- name: sdcard_detect_inverted
description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value."
- default_value: "`TARGET dependent`"
+ default_value: :target
field: invertedCardDetection
condition: USE_SDCARD
type: bool
@@ -766,31 +782,31 @@ groups:
members:
- name: max_throttle
description: "This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000."
- default_value: "1850"
+ default_value: 1850
field: maxthrottle
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: min_command
description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once."
- default_value: "1000"
+ default_value: 1000
field: mincommand
min: 0
max: PWM_RANGE_MAX
- name: motor_pwm_rate
description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000."
- default_value: "400"
+ default_value: 400
field: motorPwmRate
min: 50
max: 32000
- name: motor_accel_time
description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]"
- default_value: "0"
+ default_value: 0
field: motorAccelTimeMs
min: 0
max: 1000
- name: motor_decel_time
description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]"
- default_value: "0"
+ default_value: 0
field: motorDecelTimeMs
min: 0
max: 1000
@@ -801,25 +817,25 @@ groups:
table: motor_pwm_protocol
- name: throttle_scale
description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
- default_value: "1.000"
+ default_value: 1.0
field: throttleScale
min: 0
max: 1
- name: throttle_idle
description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
- default_value: "15"
+ default_value: 15
field: throttleIdle
min: 0
max: 30
- name: motor_poles
field: motorPoleCount
description: "The number of motor poles. Required to compute motor RPM"
- default_value: "14"
min: 4
max: 255
+ default_value: 14
- name: flip_over_after_crash_power_factor
field: flipOverAfterPowerFactor
- default_value: "65"
+ default_value: 65
description: "flip over after crash power factor"
condition: "USE_DSHOT"
min: 0
@@ -831,27 +847,27 @@ groups:
members:
- name: failsafe_delay
description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)."
- default_value: "5"
+ default_value: 5
min: 0
max: 200
- name: failsafe_recovery_delay
description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)."
- default_value: "5"
+ default_value: 5
min: 0
max: 200
- name: failsafe_off_delay
description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)."
- default_value: "200"
+ default_value: 200
min: 0
max: 200
- name: failsafe_throttle
description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
- default_value: "1000"
+ default_value: 1000
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: failsafe_throttle_low_delay
description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout"
- default_value: "100"
+ default_value: 0
min: 0
max: 300
- name: failsafe_procedure
@@ -860,28 +876,28 @@ groups:
table: failsafe_procedure
- name: failsafe_stick_threshold
description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe."
- default_value: "50"
+ default_value: 50
field: failsafe_stick_motion_threshold
min: 0
max: 500
- name: failsafe_fw_roll_angle
description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll"
- default_value: "-200"
+ default_value: -200
min: -800
max: 800
- name: failsafe_fw_pitch_angle
description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb"
- default_value: "100"
+ default_value: 100
min: -800
max: 800
- name: failsafe_fw_yaw_rate
description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn"
- default_value: "-45"
+ default_value: -45
min: -1000
max: 1000
- name: failsafe_min_distance
description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken."
- default_value: "0"
+ default_value: 0
min: 0
max: 65000
- name: failsafe_min_distance_procedure
@@ -890,7 +906,7 @@ groups:
table: failsafe_procedure
- name: failsafe_mission
description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode"
- default_value: "ON"
+ default_value: ON
type: bool
- name: PG_LIGHTS_CONFIG
@@ -900,18 +916,18 @@ groups:
members:
- name: failsafe_lights
description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
- default_value: "ON"
+ default_value: ON
field: failsafe.enabled
type: bool
- name: failsafe_lights_flash_period
description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
- default_value: "1000"
+ default_value: 1000
field: failsafe.flash_period
min: 40
max: 65535
- name: failsafe_lights_flash_on_time
description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
- default_value: "100"
+ default_value: 100
field: failsafe.flash_on_time
min: 20
max: 65535
@@ -922,19 +938,19 @@ groups:
members:
- name: align_board_roll
description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
- default_value: "0"
+ default_value: :zero
field: rollDeciDegrees
min: -1800
max: 3600
- name: align_board_pitch
description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
- default_value: "0"
+ default_value: :zero
field: pitchDeciDegrees
min: -1800
max: 3600
- name: align_board_yaw
description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
- default_value: "0"
+ default_value: :zero
field: yawDeciDegrees
min: -1800
max: 3600
@@ -945,26 +961,27 @@ groups:
members:
- name: vbat_meter_type
description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
- default_value: "`ADC`"
+ condition: USE_ADC
+ default_value: ADC
field: voltage.type
table: voltage_sensor
type: uint8_t
- name: vbat_scale
description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli."
- default_value: "1100"
+ default_value: :target
field: voltage.scale
condition: USE_ADC
min: VBAT_SCALE_MIN
max: VBAT_SCALE_MAX
- name: current_meter_scale
description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt."
- default_value: "400"
+ default_value: :target
field: current.scale
min: -10000
max: 10000
- name: current_meter_offset
description: "This sets the output offset voltage of the current sensor in millivolts."
- default_value: "0"
+ default_value: :target
field: current.offset
min: -32768
max: 32767
@@ -982,24 +999,24 @@ groups:
type: uint8_t
- name: cruise_power
description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
- default_value: "0"
+ default_value: 0
field: cruise_power
min: 0
max: 4294967295
- name: idle_power
description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
- default_value: "0"
+ default_value: 0
field: idle_power
min: 0
max: 65535
- name: rth_energy_margin
description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
- default_value: "5"
+ default_value: 5
min: 0
max: 100
- name: thr_comp_weight
description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
- default_value: "0.692"
+ default_value: 1
field: throttle_compensation_weight
min: 0
max: 2
@@ -1011,54 +1028,54 @@ groups:
members:
- name: bat_cells
description: "Number of cells of the battery (0 = autodetect), see battery documentation. 7S, 9S and 11S batteries cannot be autodetected."
- default_value: "0"
+ default_value: 0
field: cells
condition: USE_ADC
min: 0
max: 12
- name: vbat_cell_detect_voltage
description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V."
- default_value: "425"
+ default_value: 425
field: voltage.cellDetect
condition: USE_ADC
min: 100
max: 500
- name: vbat_max_cell_voltage
description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
- default_value: "420"
+ default_value: 420
field: voltage.cellMax
condition: USE_ADC
min: 100
max: 500
- name: vbat_min_cell_voltage
description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
- default_value: "330"
+ default_value: 330
field: voltage.cellMin
condition: USE_ADC
min: 100
max: 500
- name: vbat_warning_cell_voltage
description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
- default_value: "350"
+ default_value: 350
field: voltage.cellWarning
condition: USE_ADC
min: 100
max: 500
- name: battery_capacity
description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
- default_value: "0"
+ default_value: 0
field: capacity.value
min: 0
max: 4294967295
- name: battery_capacity_warning
description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
- default_value: "0"
+ default_value: 0
field: capacity.warning
min: 0
max: 4294967295
- name: battery_capacity_critical
description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
- default_value: "0"
+ default_value: 0
field: capacity.critical
min: 0
max: 4294967295
@@ -1074,29 +1091,29 @@ groups:
members:
- name: motor_direction_inverted
description: "Use if you need to inverse yaw motor direction."
- default_value: "OFF"
+ default_value: OFF
field: motorDirectionInverted
type: bool
- name: platform_type
description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
- default_value: "\"MULTIROTOR\""
+ default_value: "MULTIROTOR"
field: platformType
type: uint8_t
table: platform_type
- name: has_flaps
description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot"
- default_value: "OFF"
+ default_value: OFF
field: hasFlaps
type: bool
- name: model_preview_type
description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
- default_value: "-1"
+ default_value: -1
field: appliedMixerPreset
min: -1
max: INT16_MAX
- name: fw_min_throttle_down_pitch
description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
- default_value: "0"
+ default_value: 0
field: fwMinThrottleDownPitchAngle
min: 0
max: 450
@@ -1106,19 +1123,19 @@ groups:
members:
- name: 3d_deadband_low
description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)"
- default_value: "1406"
+ default_value: 1406
field: deadband_low
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: 3d_deadband_high
description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
- default_value: "1514"
+ default_value: 1514
field: deadband_high
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: 3d_neutral
description: "Neutral (stop) throttle value for 3D mode"
- default_value: "1460"
+ default_value: 1460
field: neutral
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
@@ -1134,30 +1151,30 @@ groups:
table: servo_protocol
- name: servo_center_pulse
description: "Servo midpoint"
- default_value: "1500"
+ default_value: 1500
field: servoCenterPulse
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: servo_pwm_rate
description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz."
- default_value: "50"
+ default_value: 50
field: servoPwmRate
min: 50
max: 498
- name: servo_lpf_hz
description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
- default_value: "20"
+ default_value: 20
field: servo_lowpass_freq
min: 0
max: 400
- name: flaperon_throw_offset
description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated."
- default_value: "200"
+ default_value: 200
min: FLAPERON_THROW_MIN
max: FLAPERON_THROW_MAX
- name: tri_unarmed_servo
description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF."
- default_value: "ON"
+ default_value: ON
type: bool
- name: PG_CONTROL_RATE_PROFILES
@@ -1167,43 +1184,43 @@ groups:
members:
- name: thr_mid
description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
- default_value: "50"
+ default_value: 50
field: throttle.rcMid8
min: 0
max: 100
- name: thr_expo
description: "Throttle exposition value"
- default_value: "0"
+ default_value: 0
field: throttle.rcExpo8
min: 0
max: 100
- name: tpa_rate
description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate."
- default_value: "0"
+ default_value: 0
field: throttle.dynPID
min: 0
max: CONTROL_RATE_CONFIG_TPA_MAX
- name: tpa_breakpoint
description: "See tpa_rate."
- default_value: "1500"
+ default_value: 1500
field: throttle.pa_breakpoint
min: PWM_RANGE_MIN
max: PWM_RANGE_MAX
- name: fw_tpa_time_constant
description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups"
- default_value: "0"
+ default_value: 0
field: throttle.fixedWingTauMs
min: 0
max: 5000
- name: rc_expo
description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
- default_value: "70"
+ default_value: 70
field: stabilized.rcExpo8
min: 0
max: 100
- name: rc_yaw_expo
description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
- default_value: "20"
+ default_value: 20
field: stabilized.rcYawExpo8
min: 0
max: 100
@@ -1211,49 +1228,49 @@ groups:
# Rate 180 (1800dps) is max. value gyro can measure reliably
- name: roll_rate
description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
- default_value: "20"
+ default_value: 20
field: stabilized.rates[FD_ROLL]
min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN
max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
- name: pitch_rate
description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
- default_value: "20"
+ default_value: 20
field: stabilized.rates[FD_PITCH]
min: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN
max: CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
- name: yaw_rate
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"
+ default_value: 20
field: stabilized.rates[FD_YAW]
min: CONTROL_RATE_CONFIG_YAW_RATE_MIN
max: CONTROL_RATE_CONFIG_YAW_RATE_MAX
- name: manual_rc_expo
description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
- default_value: "70"
+ default_value: 70
field: manual.rcExpo8
min: 0
max: 100
- name: manual_rc_yaw_expo
description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
- default_value: "20"
+ default_value: 20
field: manual.rcYawExpo8
min: 0
max: 100
- name: manual_roll_rate
description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
- default_value: "100"
+ default_value: 100
field: manual.rates[FD_ROLL]
min: 0
max: 100
- name: manual_pitch_rate
description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
- default_value: "100"
+ default_value: 100
field: manual.rates[FD_PITCH]
min: 0
max: 100
- name: manual_yaw_rate
description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
- default_value: "100"
+ default_value: 100
field: manual.rates[FD_YAW]
min: 0
max: 100
@@ -1261,6 +1278,7 @@ groups:
field: misc.fpvCamAngleDegrees
min: 0
max: 50
+ default_value: 0
- name: PG_SERIAL_CONFIG
type: serialConfig_t
@@ -1268,7 +1286,7 @@ groups:
members:
- name: reboot_character
description: "Special character used to trigger reboot"
- default_value: "82"
+ default_value: 82
min: 48
max: 126
@@ -1278,38 +1296,38 @@ groups:
members:
- name: imu_dcm_kp
description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
- default_value: "2500"
+ default_value: 2500
field: dcm_kp_acc
max: UINT16_MAX
- name: imu_dcm_ki
description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
- default_value: "50"
+ default_value: 50
field: dcm_ki_acc
max: UINT16_MAX
- name: imu_dcm_kp_mag
description: "Inertial Measurement Unit KP Gain for compass measurements"
- default_value: "10000"
+ default_value: 10000
field: dcm_kp_mag
max: UINT16_MAX
- name: imu_dcm_ki_mag
description: "Inertial Measurement Unit KI Gain for compass measurements"
- default_value: "0"
+ default_value: 0
field: dcm_ki_mag
max: UINT16_MAX
- name: small_angle
description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
- default_value: "25"
+ default_value: 25
min: 0
max: 180
- name: imu_acc_ignore_rate
description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes"
- default_value: "0"
+ default_value: 0
field: acc_ignore_rate
min: 0
max: 20
- name: imu_acc_ignore_slope
description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
- default_value: "0"
+ default_value: 0
field: acc_ignore_slope
min: 0
max: 5
@@ -1319,21 +1337,21 @@ groups:
members:
- name: fixed_wing_auto_arm
description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured."
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: disarm_kill_switch
description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel."
- default_value: "ON"
+ default_value: ON
type: bool
- name: switch_disarm_delay
description: "Delay before disarming when requested by switch (ms) [0-1000]"
- default_value: "250"
+ default_value: 250
field: switchDisarmDelayMs
min: 0
max: 1000
- name: prearm_timeout
description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
- default_value: "10000"
+ default_value: 10000
field: prearmTimeoutMs
min: 0
max: 10000
@@ -1344,7 +1362,7 @@ groups:
members:
- name: applied_defaults
description: "Internal (configurator) hint. Should not be changed manually"
- default_value: "0"
+ default_value: 0
field: appliedDefaults
type: uint8_t
min: 0
@@ -1357,26 +1375,26 @@ groups:
members:
- name: rpm_gyro_filter_enabled
description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV"
- default_value: "`OFF`"
+ default_value: OFF
field: gyro_filter_enabled
type: bool
- name: rpm_gyro_harmonics
description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
- default_value: "1"
+ default_value: 1
field: gyro_harmonics
type: uint8_t
min: 1
max: 3
- name: rpm_gyro_min_hz
description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`"
- default_value: "150"
+ default_value: 100
field: gyro_min_hz
type: uint8_t
min: 30
max: 200
- name: rpm_gyro_q
description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
- default_value: "500"
+ default_value: 500
field: gyro_q
type: uint16_t
min: 1
@@ -1405,22 +1423,22 @@ groups:
type: uint8_t
- name: gps_auto_config
description: "Enable automatic configuration of UBlox GPS receivers."
- default_value: "ON"
+ default_value: ON
field: autoConfig
type: bool
- name: gps_auto_baud
description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports"
- default_value: "ON"
+ default_value: ON
field: autoBaud
type: bool
- name: gps_ublox_use_galileo
description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]."
- default_value: "OFF"
+ default_value: OFF
field: ubloxUseGalileo
type: bool
- name: gps_min_sats
description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count."
- default_value: "6"
+ default_value: 6
field: gpsMinSats
min: 5
max: 10
@@ -1431,27 +1449,27 @@ groups:
members:
- name: deadband
description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle."
- default_value: "5"
+ default_value: 5
min: 0
max: 32
- name: yaw_deadband
description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle."
- default_value: "5"
+ default_value: 5
min: 0
max: 100
- name: pos_hold_deadband
description: "Stick deadband in [r/c points], applied after r/c deadband and expo"
- default_value: "20"
+ default_value: 10
min: 2
max: 250
- name: alt_hold_deadband
description: "Defines the deadband of throttle during alt_hold [r/c points]"
- default_value: "50"
+ default_value: 50
min: 10
max: 250
- name: 3d_deadband_throttle
description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
- default_value: "50"
+ default_value: 50
field: mid_throttle_deadband
min: 0
max: 200
@@ -1462,7 +1480,7 @@ groups:
table: airmodeHandlingType
- name: airmode_throttle_threshold
description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
- default_value: "1300"
+ default_value: 1300
field: airmodeThrottleThreshold
min: 1000
max: 2000
@@ -1474,224 +1492,224 @@ groups:
members:
- name: mc_p_pitch
description: "Multicopter rate stabilisation P-gain for PITCH"
- default_value: "40"
+ default_value: 40
field: bank_mc.pid[PID_PITCH].P
min: 0
max: 200
- name: mc_i_pitch
description: "Multicopter rate stabilisation I-gain for PITCH"
- default_value: "30"
+ default_value: 30
field: bank_mc.pid[PID_PITCH].I
min: 0
max: 200
- name: mc_d_pitch
description: "Multicopter rate stabilisation D-gain for PITCH"
- default_value: "23"
+ default_value: 23
field: bank_mc.pid[PID_PITCH].D
min: 0
max: 200
- name: mc_cd_pitch
description: "Multicopter Control Derivative gain for PITCH"
- default_value: "60"
+ default_value: 60
field: bank_mc.pid[PID_PITCH].FF
min: 0
max: 200
- name: mc_p_roll
description: "Multicopter rate stabilisation P-gain for ROLL"
- default_value: "40"
+ default_value: 40
field: bank_mc.pid[PID_ROLL].P
min: 0
max: 200
- name: mc_i_roll
description: "Multicopter rate stabilisation I-gain for ROLL"
- default_value: "30"
+ default_value: 30
field: bank_mc.pid[PID_ROLL].I
min: 0
max: 200
- name: mc_d_roll
description: "Multicopter rate stabilisation D-gain for ROLL"
- default_value: "23"
+ default_value: 23
field: bank_mc.pid[PID_ROLL].D
min: 0
max: 200
- name: mc_cd_roll
description: "Multicopter Control Derivative gain for ROLL"
- default_value: "60"
+ default_value: 60
field: bank_mc.pid[PID_ROLL].FF
min: 0
max: 200
- name: mc_p_yaw
description: "Multicopter rate stabilisation P-gain for YAW"
- default_value: "85"
+ default_value: 85
field: bank_mc.pid[PID_YAW].P
min: 0
max: 200
- name: mc_i_yaw
description: "Multicopter rate stabilisation I-gain for YAW"
- default_value: "45"
+ default_value: 45
field: bank_mc.pid[PID_YAW].I
min: 0
max: 200
- name: mc_d_yaw
description: "Multicopter rate stabilisation D-gain for YAW"
- default_value: "0"
+ default_value: 0
field: bank_mc.pid[PID_YAW].D
min: 0
max: 200
- name: mc_cd_yaw
description: "Multicopter Control Derivative gain for YAW"
- default_value: "60"
+ default_value: 60
field: bank_mc.pid[PID_YAW].FF
min: 0
max: 200
- name: mc_p_level
description: "Multicopter attitude stabilisation P-gain"
- default_value: "20"
+ default_value: 20
field: bank_mc.pid[PID_LEVEL].P
min: 0
max: 200
- name: mc_i_level
description: "Multicopter attitude stabilisation low-pass filter cutoff"
- default_value: "15"
+ default_value: 15
field: bank_mc.pid[PID_LEVEL].I
min: 0
max: 200
- name: mc_d_level
description: "Multicopter attitude stabilisation HORIZON transition point"
- default_value: "75"
+ default_value: 75
field: bank_mc.pid[PID_LEVEL].D
min: 0
max: 200
- name: fw_p_pitch
description: "Fixed-wing rate stabilisation P-gain for PITCH"
- default_value: "5"
+ default_value: 5
field: bank_fw.pid[PID_PITCH].P
min: 0
max: 200
- name: fw_i_pitch
description: "Fixed-wing rate stabilisation I-gain for PITCH"
- default_value: "7"
+ default_value: 7
field: bank_fw.pid[PID_PITCH].I
min: 0
max: 200
- name: fw_d_pitch
description: "Fixed wing rate stabilisation D-gain for PITCH"
- default_value: "0"
+ default_value: 0
field: bank_fw.pid[PID_PITCH].D
min: 0
max: 200
- name: fw_ff_pitch
description: "Fixed-wing rate stabilisation FF-gain for PITCH"
- default_value: "50"
+ default_value: 50
field: bank_fw.pid[PID_PITCH].FF
min: 0
max: 200
- name: fw_p_roll
description: "Fixed-wing rate stabilisation P-gain for ROLL"
- default_value: "5"
+ default_value: 5
field: bank_fw.pid[PID_ROLL].P
min: 0
max: 200
- name: fw_i_roll
description: "Fixed-wing rate stabilisation I-gain for ROLL"
- default_value: "7"
+ default_value: 7
field: bank_fw.pid[PID_ROLL].I
min: 0
max: 200
- name: fw_d_roll
description: "Fixed wing rate stabilisation D-gain for ROLL"
- default_value: "0"
+ default_value: 0
field: bank_fw.pid[PID_ROLL].D
min: 0
max: 200
- name: fw_ff_roll
description: "Fixed-wing rate stabilisation FF-gain for ROLL"
- default_value: "50"
+ default_value: 50
field: bank_fw.pid[PID_ROLL].FF
min: 0
max: 200
- name: fw_p_yaw
description: "Fixed-wing rate stabilisation P-gain for YAW"
- default_value: "6"
+ default_value: 6
field: bank_fw.pid[PID_YAW].P
min: 0
max: 200
- name: fw_i_yaw
description: "Fixed-wing rate stabilisation I-gain for YAW"
- default_value: "10"
+ default_value: 10
field: bank_fw.pid[PID_YAW].I
min: 0
max: 200
- name: fw_d_yaw
description: "Fixed wing rate stabilisation D-gain for YAW"
- default_value: "0"
+ default_value: 0
field: bank_fw.pid[PID_YAW].D
min: 0
max: 200
- name: fw_ff_yaw
description: "Fixed-wing rate stabilisation FF-gain for YAW"
- default_value: "60"
+ default_value: 60
field: bank_fw.pid[PID_YAW].FF
min: 0
max: 200
- name: fw_p_level
description: "Fixed-wing attitude stabilisation P-gain"
- default_value: "20"
+ default_value: 20
field: bank_fw.pid[PID_LEVEL].P
min: 0
max: 200
- name: fw_i_level
description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
- default_value: "5"
+ default_value: 5
field: bank_fw.pid[PID_LEVEL].I
min: 0
max: 200
- name: fw_d_level
description: "Fixed-wing attitude stabilisation HORIZON transition point"
- default_value: "75"
+ default_value: 75
field: bank_fw.pid[PID_LEVEL].D
min: 0
max: 200
- name: max_angle_inclination_rll
description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
- default_value: "300"
+ default_value: 300
field: max_angle_inclination[FD_ROLL]
min: 100
max: 900
- name: max_angle_inclination_pit
description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
- default_value: "300"
+ default_value: 300
field: max_angle_inclination[FD_PITCH]
min: 100
max: 900
- name: dterm_lpf_hz
description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value"
- default_value: "40"
+ default_value: 40
min: 0
max: 500
- name: dterm_lpf_type
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
- default_value: "`BIQUAD`"
+ default_value: "BIQUAD"
field: dterm_lpf_type
table: filter_type
- name: dterm_lpf2_hz
description: "Cutoff frequency for stage 2 D-term low pass filter"
- default_value: "0"
+ default_value: 0
min: 0
max: 500
- name: dterm_lpf2_type
description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
- default_value: "`BIQUAD`"
+ default_value: "BIQUAD"
field: dterm_lpf2_type
table: filter_type
- name: yaw_lpf_hz
description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
- default_value: "30"
+ default_value: 0
min: 0
max: 200
- name: fw_iterm_throw_limit
description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely."
- default_value: "165"
+ default_value: 165
field: fixedWingItermThrowLimit
min: FW_ITERM_THROW_LIMIT_MIN
max: FW_ITERM_THROW_LIMIT_MAX
@@ -1703,132 +1721,134 @@ groups:
table: direction
- name: fw_reference_airspeed
description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present."
- default_value: "1000"
+ default_value: 1000
field: fixedWingReferenceAirspeed
min: 1
max: 5000
- name: fw_turn_assist_yaw_gain
description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter"
- default_value: "1"
+ default_value: 1
field: fixedWingCoordinatedYawGain
min: 0
max: 2
- name: fw_turn_assist_pitch_gain
description: "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_value: "1"
+ default_value: 1
field: fixedWingCoordinatedPitchGain
min: 0
max: 2
- name: fw_iterm_limit_stick_position
description: "Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side"
- default_value: "0.5"
+ default_value: 0.5
field: fixedWingItermLimitOnStickPosition
min: 0
max: 1
- name: fw_yaw_iterm_freeze_bank_angle
description: "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_value: "0"
+ default_value: 0
field: fixedWingYawItermBankFreeze
min: 0
max: 90
- name: pidsum_limit
description: "A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help"
- default_value: "500"
+ default_value: 500
field: pidSumLimit
min: PID_SUM_LIMIT_MIN
max: PID_SUM_LIMIT_MAX
- name: pidsum_limit_yaw
description: "A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help"
- default_value: "400"
+ default_value: 350
field: pidSumLimitYaw
min: PID_SUM_LIMIT_MIN
max: PID_SUM_LIMIT_MAX
- name: iterm_windup
description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)"
- default_value: "50"
+ default_value: 50
field: itermWindupPointPercent
min: 0
max: 90
- name: rate_accel_limit_roll_pitch
description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting."
- default_value: "0"
+ default_value: 0
field: axisAccelerationLimitRollPitch
max: 500000
- name: rate_accel_limit_yaw
description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting."
- default_value: "10000"
+ default_value: 10000
field: axisAccelerationLimitYaw
max: 500000
- name: heading_hold_rate_limit
description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes."
- default_value: "90"
min: HEADING_HOLD_RATE_LIMIT_MIN
max: HEADING_HOLD_RATE_LIMIT_MAX
+ default_value: 90
- name: nav_mc_pos_z_p
description: "P gain of altitude PID controller (Multirotor)"
- default_value: "50"
field: bank_mc.pid[PID_POS_Z].P
condition: USE_NAV
min: 0
max: 255
+ default_value: 50
- name: nav_mc_vel_z_p
description: "P gain of velocity PID controller"
- default_value: "100"
field: bank_mc.pid[PID_VEL_Z].P
condition: USE_NAV
min: 0
max: 255
+ default_value: 100
- name: nav_mc_vel_z_i
description: "I gain of velocity PID controller"
- default_value: "50"
field: bank_mc.pid[PID_VEL_Z].I
condition: USE_NAV
min: 0
max: 255
+ default_value: 50
- name: nav_mc_vel_z_d
description: "D gain of velocity PID controller"
- default_value: "10"
+ default_value: 10
field: bank_mc.pid[PID_VEL_Z].D
condition: USE_NAV
min: 0
max: 255
+ default_value: 10
- name: nav_mc_pos_xy_p
description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
- default_value: "65"
field: bank_mc.pid[PID_POS_XY].P
condition: USE_NAV
min: 0
max: 255
+ default_value: 65
- name: nav_mc_vel_xy_p
description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations"
- default_value: "40"
field: bank_mc.pid[PID_VEL_XY].P
condition: USE_NAV
min: 0
max: 255
+ default_value: 40
- name: nav_mc_vel_xy_i
description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot"
- default_value: "15"
field: bank_mc.pid[PID_VEL_XY].I
condition: USE_NAV
min: 0
max: 255
+ default_value: 15
- name: nav_mc_vel_xy_d
description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target."
- default_value: "100"
field: bank_mc.pid[PID_VEL_XY].D
condition: USE_NAV
min: 0
max: 255
+ default_value: 100
- name: nav_mc_vel_xy_ff
field: bank_mc.pid[PID_VEL_XY].FF
condition: USE_NAV
min: 0
max: 255
+ default_value: 40
- name: nav_mc_heading_p
description: "P gain of Heading Hold controller (Multirotor)"
- default_value: "60"
+ default_value: 60
field: bank_mc.pid[PID_HEADING].P
condition: USE_NAV
min: 0
@@ -1837,139 +1857,145 @@ groups:
field: navVelXyDTermLpfHz
min: 0
max: 100
+ default_value: 2
- name: nav_mc_vel_xy_dterm_attenuation
description: "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_value: "90"
field: navVelXyDtermAttenuation
min: 0
max: 100
+ default_value: 90
- name: nav_mc_vel_xy_dterm_attenuation_start
description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
- default_value: 10"
+ default_value: 10
field: navVelXyDtermAttenuationStart
min: 0
max: 100
- name: nav_mc_vel_xy_dterm_attenuation_end
description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
- default_value: "60"
+ default_value: 60
field: navVelXyDtermAttenuationEnd
min: 0
max: 100
- name: nav_fw_pos_z_p
description: "P gain of altitude PID controller (Fixedwing)"
- default_value: "50"
+ default_value: 40
field: bank_fw.pid[PID_POS_Z].P
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_z_i
description: "I gain of altitude PID controller (Fixedwing)"
- default_value: "0"
+ default_value: 5
field: bank_fw.pid[PID_POS_Z].I
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_z_d
description: "D gain of altitude PID controller (Fixedwing)"
- default_value: "0"
+ default_value: 10
field: bank_fw.pid[PID_POS_Z].D
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_xy_p
description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
- default_value: "75"
+ default_value: 75
field: bank_fw.pid[PID_POS_XY].P
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_xy_i
description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
- default_value: "5"
+ default_value: 5
field: bank_fw.pid[PID_POS_XY].I
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_xy_d
description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
- default_value: "8"
+ default_value: 8
field: bank_fw.pid[PID_POS_XY].D
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_heading_p
description: "P gain of Heading Hold controller (Fixedwing)"
- default_value: "60"
+ default_value: 60
field: bank_fw.pid[PID_HEADING].P
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_hdg_p
description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
- default_value: "60"
+ default_value: 30
field: bank_fw.pid[PID_POS_HEADING].P
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_hdg_i
description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
- default_value: "0"
+ default_value: 2
field: bank_fw.pid[PID_POS_HEADING].I
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_hdg_d
description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
- default_value: "0"
+ default_value: 0
field: bank_fw.pid[PID_POS_HEADING].D
condition: USE_NAV
min: 0
max: 255
- name: nav_fw_pos_hdg_pidsum_limit
description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
- default_value: "350"
+ default_value: 350
field: navFwPosHdgPidsumLimit
min: PID_SUM_LIMIT_MIN
max: PID_SUM_LIMIT_MAX
- name: mc_iterm_relax
field: iterm_relax
table: iterm_relax
+ default_value: RP
- name: mc_iterm_relax_cutoff
field: iterm_relax_cutoff
min: 1
max: 100
+ default_value: 15
- name: d_boost_factor
field: dBoostFactor
condition: USE_D_BOOST
min: 1
max: 3
+ default_value: 1.25
- name: d_boost_max_at_acceleration
field: dBoostMaxAtAlleceleration
condition: USE_D_BOOST
min: 1000
max: 16000
+ default_value: 7500
- name: d_boost_gyro_delta_lpf_hz
field: dBoostGyroDeltaLpfHz
condition: USE_D_BOOST
min: 10
max: 250
+ default_value: 80
- name: antigravity_gain
description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
- default_value: "1"
+ default_value: 1
field: antigravityGain
condition: USE_ANTIGRAVITY
min: 1
max: 20
- name: antigravity_accelerator
description: ""
- default_value: "1"
+ default_value: 1
field: antigravityAccelerator
condition: USE_ANTIGRAVITY
min: 1
max: 20
- name: antigravity_cutoff_lpf_hz
description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain"
- default_value: "15"
+ default_value: 15
field: antigravityCutoff
condition: USE_ANTIGRAVITY
min: 1
@@ -1978,42 +2004,43 @@ groups:
description: "Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`"
field: pidControllerType
table: pidTypeTable
+ default_value: AUTO
- name: mc_cd_lpf_hz
description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky"
- default_value: "30"
+ default_value: 30
field: controlDerivativeLpfHz
min: 0
max: 200
- name: setpoint_kalman_enabled
description: "Enable Kalman filter on the PID controller setpoint"
- default_value: "OFF"
+ default_value: OFF
condition: USE_GYRO_KALMAN
field: kalmanEnabled
type: bool
- name: setpoint_kalman_q
description: "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_value: "100"
+ default_value: 100
field: kalman_q
condition: USE_GYRO_KALMAN
min: 1
max: 16000
- name: setpoint_kalman_w
description: "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_value: "4"
+ default_value: 4
field: kalman_w
condition: USE_GYRO_KALMAN
min: 1
max: 40
- name: setpoint_kalman_sharpness
description: "Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets"
- default_value: "100"
+ default_value: 100
field: kalman_sharpness
condition: USE_GYRO_KALMAN
min: 1
max: 16000
- name: fw_level_pitch_trim
description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
- default_value: "0"
+ default_value: 0
field: fixedWingLevelTrim
min: -10
max: 10
@@ -2024,31 +2051,31 @@ groups:
members:
- name: fw_autotune_overshoot_time
description: "Time [ms] to detect sustained overshoot"
- default_value: "100"
+ default_value: 100
field: fw_overshoot_time
min: 50
max: 500
- name: fw_autotune_undershoot_time
description: "Time [ms] to detect sustained undershoot"
- default_value: "200"
+ default_value: 200
field: fw_undershoot_time
min: 50
max: 500
- name: fw_autotune_threshold
description: "Threshold [%] of max rate to consider overshoot/undershoot detection"
- default_value: "50"
+ default_value: 50
field: fw_max_rate_threshold
min: 0
max: 100
- name: fw_autotune_ff_to_p_gain
description: "FF to P gain (strength relationship) [%]"
- default_value: "10"
+ default_value: 10
field: fw_ff_to_p_gain
min: 0
max: 100
- name: fw_autotune_ff_to_i_tc
description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]"
- default_value: "600"
+ default_value: 600
field: fw_ff_to_i_time_constant
min: 100
max: 5000
@@ -2059,26 +2086,27 @@ groups:
members:
- name: inav_auto_mag_decl
description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
- default_value: "ON"
+ default_value: ON
field: automatic_mag_declination
type: bool
- name: inav_gravity_cal_tolerance
description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
- default_value: "5"
+ default_value: 5
field: gravity_calibration_tolerance
min: 0
max: 255
- name: inav_use_gps_velned
description: "Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance."
- default_value: "ON"
+ default_value: ON
field: use_gps_velned
type: bool
- name: inav_use_gps_no_baro
field: use_gps_no_baro
type: bool
+ default_value: OFF
- name: inav_allow_dead_reckoning
description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
- default_value: "OFF"
+ default_value: OFF
field: allow_dead_reckoning
type: bool
- name: inav_reset_altitude
@@ -2093,7 +2121,7 @@ groups:
table: reset_type
- name: inav_max_surface_altitude
description: "Max allowed altitude for surface following mode. [cm]"
- default_value: "200"
+ default_value: 200
field: max_surface_altitude
min: 0
max: 1000
@@ -2101,57 +2129,61 @@ groups:
field: w_z_surface_p
min: 0
max: 100
+ default_value: 3.5
- name: inav_w_z_surface_v
field: w_z_surface_v
min: 0
max: 100
+ default_value: 6.1
- name: inav_w_xy_flow_p
field: w_xy_flow_p
min: 0
max: 100
+ default_value: 1.0
- name: inav_w_xy_flow_v
field: w_xy_flow_v
min: 0
max: 100
+ default_value: 2.0
- name: inav_w_z_baro_p
description: "Weight of barometer measurements in estimated altitude and climb rate"
- default_value: "0.350"
field: w_z_baro_p
min: 0
max: 10
+ default_value: 0.35
- name: inav_w_z_gps_p
description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes"
- default_value: "0.200"
field: w_z_gps_p
min: 0
max: 10
+ default_value: 0.2
- name: inav_w_z_gps_v
description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero"
- default_value: "0.500"
field: w_z_gps_v
min: 0
max: 10
+ default_value: 0.1
- name: inav_w_xy_gps_p
description: "Weight of GPS coordinates in estimated UAV position and speed."
- default_value: "1.000"
+ default_value: 1.0
field: w_xy_gps_p
min: 0
max: 10
- name: inav_w_xy_gps_v
description: "Weight of GPS velocity data in estimated UAV speed"
- default_value: "2.000"
+ default_value: 2.0
field: w_xy_gps_v
min: 0
max: 10
- name: inav_w_z_res_v
description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
- default_value: "0.500"
+ default_value: 0.5
field: w_z_res_v
min: 0
max: 10
- name: inav_w_xy_res_v
description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
- default_value: "0.500"
+ default_value: 0.5
field: w_xy_res_v
min: 0
max: 10
@@ -2159,21 +2191,22 @@ groups:
field: w_xyz_acc_p
min: 0
max: 1
+ default_value: 1.0
- name: inav_w_acc_bias
description: "Weight for accelerometer drift estimation"
- default_value: "0.010"
+ default_value: 0.01
field: w_acc_bias
min: 0
max: 1
- name: inav_max_eph_epv
description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
- default_value: "1000.000"
+ default_value: 1000
field: max_eph_epv
min: 0
max: 9999
- name: inav_baro_epv
description: "Uncertainty value for barometric sensor [cm]"
- default_value: "100.000"
+ default_value: 100
field: baro_epv
min: 0
max: 9999
@@ -2185,12 +2218,12 @@ groups:
members:
- name: nav_disarm_on_landing
description: "If set to ON, iNav disarms the FC after landing"
- default_value: "OFF"
+ default_value: OFF
field: general.flags.disarm_on_landing
type: bool
- name: nav_use_midthr_for_althold
description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude"
- default_value: "OFF"
+ default_value: OFF
field: general.flags.use_thr_mid_for_althold
type: bool
- name: nav_extra_arming_safety
@@ -2205,72 +2238,72 @@ groups:
table: nav_user_control_mode
- name: nav_position_timeout
description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
- default_value: "5"
+ default_value: 5
field: general.pos_failure_timeout
min: 0
max: 10
- name: nav_wp_radius
description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
- default_value: "100"
+ default_value: 100
field: general.waypoint_radius
min: 10
max: 10000
- name: nav_wp_safe_distance
description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check."
- default_value: "10000"
+ default_value: 10000
field: general.waypoint_safe_distance
max: 65000
- name: nav_auto_speed
description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]"
- default_value: "300"
+ default_value: 300
field: general.max_auto_speed
min: 10
max: 2000
- name: nav_auto_climb_rate
description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
- default_value: "500"
+ default_value: 500
field: general.max_auto_climb_rate
min: 10
max: 2000
- name: nav_manual_speed
description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
- default_value: "500"
+ default_value: 500
field: general.max_manual_speed
min: 10
max: 2000
- name: nav_manual_climb_rate
description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
- default_value: "200"
+ default_value: 200
field: general.max_manual_climb_rate
min: 10
max: 2000
- name: nav_landing_speed
description: "Vertical descent velocity during the RTH landing phase. [cm/s]"
- default_value: "200"
+ default_value: 200
field: general.land_descent_rate
min: 100
max: 2000
- name: nav_land_slowdown_minalt
description: "Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm]"
- default_value: "500"
+ default_value: 500
field: general.land_slowdown_minalt
min: 50
max: 1000
- name: nav_land_slowdown_maxalt
description: "Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm]"
- default_value: "2000"
+ default_value: 2000
field: general.land_slowdown_maxalt
min: 500
max: 4000
- name: nav_emerg_landing_speed
description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
- default_value: "500"
+ default_value: 500
field: general.emerg_descent_rate
min: 100
max: 2000
- name: nav_min_rth_distance
description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase."
- default_value: "500"
+ default_value: 500
field: general.min_rth_distance
min: 0
max: 5000
@@ -2281,17 +2314,17 @@ groups:
table: nav_overrides_motor_stop
- name: nav_rth_climb_first
description: "If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way."
- default_value: "ON"
+ default_value: ON
field: general.flags.rth_climb_first
type: bool
- name: nav_rth_climb_ignore_emerg
description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
- default_value: "OFF"
+ default_value: OFF
field: general.flags.rth_climb_ignore_emerg
type: bool
- name: nav_rth_tail_first
description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
- default_value: "OFF"
+ default_value: OFF
field: general.flags.rth_tail_first
type: bool
- name: nav_rth_allow_landing
@@ -2306,7 +2339,7 @@ groups:
table: nav_rth_alt_mode
- name: nav_rth_abort_threshold
description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm]"
- default_value: "50000"
+ default_value: 50000
field: general.rth_abort_threshold
max: 65000
- name: nav_max_terrain_follow_alt
@@ -2314,191 +2347,192 @@ groups:
default_value: "100"
description: "Max allowed above the ground altitude for terrain following mode"
max: 1000
+ default_value: 100
- name: nav_rth_altitude
description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
- default_value: "1000"
+ default_value: 1000
field: general.rth_altitude
max: 65000
- name: nav_rth_home_altitude
description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]"
- default_value: "0"
+ default_value: 0
field: general.rth_home_altitude
max: 65000
- name: safehome_max_distance
description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
- default_value: "20000"
+ default_value: 20000
field: general.safehome_max_distance
min: 0
max: 65000
- name: nav_mc_bank_angle
description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
- default_value: "30"
+ default_value: 30
field: mc.max_bank_angle
min: 15
max: 45
- name: nav_mc_hover_thr
description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
- default_value: "1500"
+ default_value: 1500
field: mc.hover_throttle
min: 1000
max: 2000
- name: nav_mc_auto_disarm_delay
description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)"
- default_value: "2000"
+ default_value: 2000
field: mc.auto_disarm_delay
min: 100
max: 10000
- name: nav_mc_braking_speed_threshold
description: "min speed in cm/s above which braking can happen"
- default_value: "100"
+ default_value: 100
field: mc.braking_speed_threshold
condition: USE_MR_BRAKING_MODE
min: 0
max: 1000
- name: nav_mc_braking_disengage_speed
description: "braking is disabled when speed goes below this value"
- default_value: "75"
+ default_value: 75
field: mc.braking_disengage_speed
condition: USE_MR_BRAKING_MODE
min: 0
max: 1000
- name: nav_mc_braking_timeout
description: "timeout in ms for braking"
- default_value: "2000"
+ default_value: 2000
field: mc.braking_timeout
condition: USE_MR_BRAKING_MODE
min: 100
max: 5000
- name: nav_mc_braking_boost_factor
description: "acceleration factor for BOOST phase"
- default_value: "100"
+ default_value: 100
field: mc.braking_boost_factor
condition: USE_MR_BRAKING_MODE
min: 0
max: 200
- name: nav_mc_braking_boost_timeout
description: "how long in ms BOOST phase can happen"
- default_value: "750"
+ default_value: 750
field: mc.braking_boost_timeout
condition: USE_MR_BRAKING_MODE
min: 0
max: 5000
- name: nav_mc_braking_boost_speed_threshold
description: "BOOST can be enabled when speed is above this value"
- default_value: "150"
+ default_value: 150
field: mc.braking_boost_speed_threshold
condition: USE_MR_BRAKING_MODE
min: 100
max: 1000
- name: nav_mc_braking_boost_disengage_speed
description: "BOOST will be disabled when speed goes below this value"
- default_value: "100"
+ default_value: 100
field: mc.braking_boost_disengage_speed
condition: USE_MR_BRAKING_MODE
min: 0
max: 1000
- name: nav_mc_braking_bank_angle
description: "max angle that MR is allowed to bank in BOOST mode"
- default_value: "40"
+ default_value: 40
field: mc.braking_bank_angle
condition: USE_MR_BRAKING_MODE
min: 15
max: 60
- name: nav_mc_pos_deceleration_time
description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting"
- default_value: "120"
+ default_value: 120
field: mc.posDecelerationTime
condition: USE_NAV
min: 0
max: 255
- name: nav_mc_pos_expo
description: "Expo for PosHold control"
- default_value: "10"
+ default_value: 10
field: mc.posResponseExpo
condition: USE_NAV
min: 0
max: 255
- name: nav_mc_wp_slowdown
description: "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_value: "ON"
+ default_value: ON
field: mc.slowDownForTurning
type: bool
- name: nav_fw_cruise_thr
description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )"
- default_value: "1400"
+ default_value: 1400
field: fw.cruise_throttle
min: 1000
max: 2000
- name: nav_fw_min_thr
description: "Minimum throttle for flying wing in GPS assisted modes"
- default_value: "1200"
+ default_value: 1200
field: fw.min_throttle
min: 1000
max: 2000
- name: nav_fw_max_thr
description: "Maximum throttle for flying wing in GPS assisted modes"
- default_value: "1700"
+ default_value: 1700
field: fw.max_throttle
min: 1000
max: 2000
- name: nav_fw_bank_angle
description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
- default_value: "20"
+ default_value: 35
field: fw.max_bank_angle
min: 5
max: 80
- name: nav_fw_climb_angle
description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
- default_value: "20"
+ default_value: 20
field: fw.max_climb_angle
min: 5
max: 80
- name: nav_fw_dive_angle
description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
- default_value: "15"
+ default_value: 15
field: fw.max_dive_angle
min: 5
max: 80
- name: nav_fw_pitch2thr
description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)"
- default_value: "10"
+ default_value: 10
field: fw.pitch_to_throttle
min: 0
max: 100
- name: nav_fw_pitch2thr_smoothing
description: "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
- default_value: "6"
+ default_value: 6
field: fw.pitch_to_throttle_smooth
min: 0
max: 9
- name: nav_fw_pitch2thr_threshold
description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
- default_value: "50"
+ default_value: 50
field: fw.pitch_to_throttle_thresh
min: 0
max: 900
- name: nav_fw_loiter_radius
description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
- default_value: "7500"
+ default_value: 7500
field: fw.loiter_radius
min: 0
max: 10000
- name: nav_fw_cruise_speed
description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
- default_value: "0"
+ default_value: 0
field: fw.cruise_speed
min: 0
max: 65535
- name: nav_fw_control_smoothness
description: "How smoothly the autopilot controls the airplane to correct the navigation error"
- default_value: "0"
+ default_value: 0
field: fw.control_smoothness
min: 0
max: 9
- name: nav_fw_land_dive_angle
description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees"
- default_value: "2"
+ default_value: 2
field: fw.land_dive_angle
condition: NAV_FIXED_WING_LANDING
min: -20
@@ -2506,100 +2540,100 @@ groups:
- name: nav_fw_launch_velocity
description: "Forward velocity threshold for swing-launch detection [cm/s]"
- default_value: "300"
+ default_value: 300
field: fw.launch_velocity_thresh
min: 100
max: 10000
- name: nav_fw_launch_accel
description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s"
- default_value: "1863"
+ default_value: 1863
field: fw.launch_accel_thresh
min: 1000
max: 20000
- name: nav_fw_launch_max_angle
description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
- default_value: "45"
+ default_value: 45
field: fw.launch_max_angle
min: 5
max: 180
- name: nav_fw_launch_detect_time
description: "Time for which thresholds have to breached to consider launch happened [ms]"
- default_value: "40"
+ default_value: 40
field: fw.launch_time_thresh
min: 10
max: 1000
- name: nav_fw_launch_thr
description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
- default_value: "1700"
+ default_value: 1700
field: fw.launch_throttle
min: 1000
max: 2000
- name: nav_fw_launch_idle_thr
description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)"
- default_value: "1000"
+ default_value: 1000
field: fw.launch_idle_throttle
min: 1000
max: 2000
- name: nav_fw_launch_motor_delay
description: "Delay between detected launch and launch sequence start and throttling up (ms)"
- default_value: "500"
+ default_value: 500
field: fw.launch_motor_timer
min: 0
max: 5000
- name: nav_fw_launch_spinup_time
description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
- default_value: "100"
+ default_value: 100
field: fw.launch_motor_spinup_time
min: 0
max: 1000
- name: nav_fw_launch_end_time
description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
- default_value: "2000"
+ default_value: 3000
field: fw.launch_end_time
min: 0
max: 5000
- name: nav_fw_launch_min_time
description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
- default_value: "0"
+ default_value: 0
field: fw.launch_min_time
min: 0
max: 60000
- name: nav_fw_launch_timeout
description: "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)"
- default_value: "5000"
+ default_value: 5000
field: fw.launch_timeout
max: 60000
- name: nav_fw_launch_max_altitude
description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
- default_value: "0"
+ default_value: 0
field: fw.launch_max_altitude
min: 0
max: 60000
- name: nav_fw_launch_climb_angle
description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
- default_value: "18"
+ default_value: 18
field: fw.launch_climb_angle
min: 5
max: 45
- name: nav_fw_cruise_yaw_rate
description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]"
- default_value: "20"
+ default_value: 20
field: fw.cruise_yaw_rate
min: 0
max: 60
- name: nav_fw_allow_manual_thr_increase
description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
- default_value: "OFF"
+ default_value: OFF
field: fw.allow_manual_thr_increase
type: bool
- name: nav_use_fw_yaw_control
description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
- default_value: "OFF"
+ default_value: OFF
field: fw.useFwNavYawControl
type: bool
- name: nav_fw_yaw_deadband
description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
- default_value: "0"
+ default_value: 0
field: fw.yawControlDeadband
min: 0
max: 90
@@ -2611,27 +2645,27 @@ groups:
members:
- name: telemetry_switch
description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: telemetry_inverted
description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used."
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: frsky_default_latitude
description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired."
- default_value: "0.000"
+ default_value: 0
field: gpsNoFixLatitude
min: -90
max: 90
- name: frsky_default_longitude
description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired."
- default_value: "0.000"
+ default_value: 0
field: gpsNoFixLongitude
min: -180
max: 180
- name: frsky_coordinates_format
description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA"
- default_value: "0"
+ default_value: 0
field: frsky_coordinate_format
min: 0
max: FRSKY_FORMAT_NMEA
@@ -2643,26 +2677,26 @@ groups:
type: uint8_t
- name: frsky_vfas_precision
description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method"
- default_value: "0"
+ default_value: 0
min: FRSKY_VFAS_PRECISION_LOW
max: FRSKY_VFAS_PRECISION_HIGH
- name: frsky_pitch_roll
description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: report_cell_voltage
description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON"
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: hott_alarm_sound_interval
description: "Battery alarm delay in seconds for Hott telemetry"
- default_value: "5"
+ default_value: 5
field: hottAlarmSoundInterval
min: 0
max: 120
- name: telemetry_halfduplex
description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
- default_value: "OFF"
+ default_value: ON
field: halfDuplex
type: bool
- name: smartport_fuel_unit
@@ -2674,7 +2708,7 @@ groups:
table: smartport_fuel_unit
- name: ibus_telemetry_type
description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
- default_value: "0"
+ default_value: 0
field: ibusTelemetryType
min: 0
max: 255
@@ -2686,36 +2720,31 @@ groups:
table: ltm_rates
- name: sim_ground_station_number
description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module."
- default_value: "Empty string"
+ default_value: ""
field: simGroundStationNumber
condition: USE_TELEMETRY_SIM
- type: string
- max: 16
- name: sim_pin
description: "PIN code for the SIM module"
- default_value: "Empty string"
+ default_value: "0000"
field: simPin
condition: USE_TELEMETRY_SIM
- type: string
- max: 8
- name: sim_transmit_interval
description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
- default_value: "60"
+ default_value: 60
field: simTransmitInterval
condition: USE_TELEMETRY_SIM
type: uint16_t
min: SIM_MIN_TRANSMIT_INTERVAL
max: 65535
- name: sim_transmit_flags
- description: "String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low"
- default_value: "F"
+ description: "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_value: :SIM_TX_FLAG_FAILSAFE
field: simTransmitFlags
condition: USE_TELEMETRY_SIM
- type: string
- max: SIM_N_TX_FLAGS
+ max: 63
- name: acc_event_threshold_high
description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off."
- default_value: "0"
+ default_value: 0
field: accEventThresholdHigh
condition: USE_TELEMETRY_SIM
type: uint16_t
@@ -2723,7 +2752,7 @@ groups:
max: 65535
- name: acc_event_threshold_low
description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off."
- default_value: "0"
+ default_value: 0
field: accEventThresholdLow
condition: USE_TELEMETRY_SIM
type: uint16_t
@@ -2731,7 +2760,7 @@ groups:
max: 900
- name: acc_event_threshold_neg_x
description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off."
- default_value: "0"
+ default_value: 0
field: accEventThresholdNegX
condition: USE_TELEMETRY_SIM
type: uint16_t
@@ -2739,7 +2768,7 @@ groups:
max: 65535
- name: sim_low_altitude
description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
- default_value: "0"
+ default_value: -32767
field: simLowAltitude
condition: USE_TELEMETRY_SIM
type: int16_t
@@ -2750,31 +2779,37 @@ groups:
type: uint8_t
min: 0
max: 255
+ default_value: 2
- name: mavlink_rc_chan_rate
field: mavlink.rc_channels_rate
type: uint8_t
min: 0
max: 255
+ default_value: 5
- name: mavlink_pos_rate
field: mavlink.position_rate
type: uint8_t
min: 0
max: 255
+ default_value: 2
- name: mavlink_extra1_rate
field: mavlink.extra1_rate
type: uint8_t
min: 0
max: 255
+ default_value: 10
- name: mavlink_extra2_rate
field: mavlink.extra2_rate
type: uint8_t
min: 0
max: 255
+ default_value: 2
- name: mavlink_extra3_rate
field: mavlink.extra3_rate
type: uint8_t
min: 0
max: 255
+ default_value: 1
- name: PG_ELERES_CONFIG
type: eleresConfig_t
headers: ["rx/eleres.h"]
@@ -2784,27 +2819,34 @@ groups:
field: eleresFreq
min: 415
max: 450
+ default_value: 435
- name: eleres_telemetry_en
field: eleresTelemetryEn
type: bool
+ default_value: OFF
- name: eleres_telemetry_power
field: eleresTelemetryPower
min: 0
max: 7
+ default_value: 7
- name: eleres_loc_en
field: eleresLocEn
type: bool
+ default_value: OFF
- name: eleres_loc_power
field: eleresLocPower
min: 0
max: 7
+ default_value: 7
- name: eleres_loc_delay
field: eleresLocDelay
min: 30
max: 1800
+ default_value: 240
- name: eleres_signature
field: eleresSignature
max: UINT32_MAX
+ default_value: :zero
- name: PG_LED_STRIP_CONFIG
type: ledStripConfig_t
@@ -2813,7 +2855,7 @@ groups:
members:
- name: ledstrip_visual_beeper
description: ""
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: PG_OSD_CONFIG
@@ -2829,7 +2871,7 @@ groups:
type: uint8_t
- name: osd_row_shiftdown
description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
- default_value: "0"
+ default_value: 0
field: row_shiftdown
min: 0
max: 1
@@ -2848,92 +2890,92 @@ groups:
- name: osd_rssi_alarm
description: "Value below which to make the OSD RSSI indicator blink"
- default_value: "20"
+ default_value: 20
field: rssi_alarm
min: 0
max: 100
- name: osd_time_alarm
description: "Value above which to make the OSD flight time indicator blink (minutes)"
- default_value: "10"
+ default_value: 10
field: time_alarm
min: 0
max: 600
- name: osd_alt_alarm
description: "Value above which to make the OSD relative altitude indicator blink (meters)"
- default_value: "100"
+ default_value: 100
field: alt_alarm
min: 0
max: 10000
- name: osd_dist_alarm
description: "Value above which to make the OSD distance from home indicator blink (meters)"
- default_value: "1000"
+ default_value: 1000
field: dist_alarm
min: 0
max: 50000
- name: osd_neg_alt_alarm
description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
- default_value: "5"
+ default_value: 5
field: neg_alt_alarm
min: 0
max: 10000
- name: osd_current_alarm
description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
- default_value: "0"
+ default_value: 0
field: current_alarm
min: 0
max: 255
- name: osd_gforce_alarm
description: "Value above which the OSD g force indicator will blink (g)"
- default_value: "5"
+ default_value: 5
field: gforce_alarm
min: 0
max: 20
- name: osd_gforce_axis_alarm_min
description: "Value under which the OSD axis g force indicators will blink (g)"
- default_value: "-5"
+ default_value: -5
field: gforce_axis_alarm_min
min: -20
max: 20
- name: osd_gforce_axis_alarm_max
description: "Value above which the OSD axis g force indicators will blink (g)"
- default_value: "5"
+ default_value: 5
field: gforce_axis_alarm_max
min: -20
max: 20
- name: osd_imu_temp_alarm_min
description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "-200"
+ default_value: -200
field: imu_temp_alarm_min
min: -550
max: 1250
- name: osd_imu_temp_alarm_max
description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "600"
+ default_value: 600
field: imu_temp_alarm_max
min: -550
max: 1250
- name: osd_esc_temp_alarm_max
description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "900"
+ default_value: 900
field: esc_temp_alarm_max
min: -550
max: 1500
- name: osd_esc_temp_alarm_min
description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "-200"
+ default_value: -200
field: esc_temp_alarm_min
min: -550
max: 1500
- name: osd_baro_temp_alarm_min
description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "-200"
+ default_value: -200
field: baro_temp_alarm_min
condition: USE_BARO
min: -550
max: 1250
- name: osd_baro_temp_alarm_max
description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
- default_value: "600"
+ default_value: 600
field: baro_temp_alarm_max
condition: USE_BARO
min: -550
@@ -2941,14 +2983,14 @@ groups:
- name: osd_snr_alarm
condition: USE_SERIALRX_CRSF
description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
- default_value: "4"
+ default_value: 4
field: snr_alarm
min: -20
max: 10
- name: osd_link_quality_alarm
condition: USE_SERIALRX_CRSF
description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
- default_value: "70"
+ default_value: 70
field: link_quality_alarm
min: 0
max: 100
@@ -2963,12 +3005,14 @@ groups:
- name: osd_ahi_reverse_roll
field: ahi_reverse_roll
type: bool
+ default_value: OFF
- name: osd_ahi_max_pitch
description: "Max pitch, in degrees, for OSD artificial horizon"
- default_value: "20"
+ default_value: 20
field: ahi_max_pitch
min: 10
max: 90
+ default_value: 20
- name: osd_crosshairs_style
description: "To set the visual type for the crosshair"
default_value: "DEFAULT"
@@ -2983,77 +3027,77 @@ groups:
type: uint8_t
- name: osd_horizon_offset
description: "To vertically adjust the whole OSD and AHI and scrolling bars"
- default_value: "0"
+ default_value: 0
field: horizon_offset
min: -2
max: 2
- name: osd_camera_uptilt
description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal"
- default_value: "0"
+ default_value: 0
field: camera_uptilt
min: -40
max: 80
- name: osd_camera_fov_h
description: "Horizontal field of view for the camera in degres"
- default_value: "135"
+ default_value: 135
field: camera_fov_h
min: 60
max: 150
- name: osd_camera_fov_v
description: "Vertical field of view for the camera in degres"
- default_value: "85"
+ default_value: 85
field: camera_fov_v
min: 30
max: 120
- name: osd_hud_margin_h
description: "Left and right margins for the hud area"
- default_value: "3"
+ default_value: 3
field: hud_margin_h
min: 0
max: 4
- name: osd_hud_margin_v
description: "Top and bottom margins for the hud area"
- default_value: "3"
+ default_value: 3
field: hud_margin_v
min: 1
max: 3
- name: osd_hud_homing
description: "To display little arrows around the crossair showing where the home point is in the hud"
- default_value: "0"
+ default_value: OFF
field: hud_homing
type: bool
- name: osd_hud_homepoint
description: "To 3D-display the home point location in the hud"
- default_value: "0"
+ default_value: OFF
field: hud_homepoint
type: bool
- name: osd_hud_radar_disp
description: "Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc"
- default_value: "0"
+ default_value: 0
field: hud_radar_disp
min: 0
max: 4
- name: osd_hud_radar_range_min
description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
- default_value: "3"
+ default_value: 3
field: hud_radar_range_min
min: 1
max: 30
- name: osd_hud_radar_range_max
description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
- default_value: 4000"
+ default_value: 4000
field: hud_radar_range_max
min: 100
max: 9990
- name: osd_hud_radar_nearest
description: "To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in °, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable."
- default_value: "0"
+ default_value: 0
field: hud_radar_nearest
min: 0
max: 4000
- name: osd_hud_wp_disp
description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)"
- default_value: "0"
+ default_value: 0
field: hud_wp_disp
min: 0
@@ -3062,16 +3106,19 @@ groups:
field: left_sidebar_scroll
table: osd_sidebar_scroll
type: uint8_t
+ default_value: NONE
- name: osd_right_sidebar_scroll
field: right_sidebar_scroll
table: osd_sidebar_scroll
type: uint8_t
+ default_value: NONE
- name: osd_sidebar_scroll_arrows
field: sidebar_scroll_arrows
type: bool
+ default_value: OFF
- name: osd_main_voltage_decimals
description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
- default_value: "1"
+ default_value: 1
field: main_voltage_decimals
min: 1
max: 2
@@ -3079,23 +3126,24 @@ groups:
field: coordinate_digits
min: 8
max: 11
+ default_value: 9
- name: osd_estimations_wind_compensation
description: "Use wind estimation for remaining flight time/distance estimation"
- default_value: "ON"
+ default_value: ON
condition: USE_WIND_ESTIMATOR
field: estimations_wind_compensation
type: bool
- name: osd_failsafe_switch_layout
description: "If enabled the OSD automatically switches to the first layout during failsafe"
- default_value: "OFF"
+ default_value: OFF
type: bool
- name: osd_plus_code_digits
description: "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."
field: plus_code_digits
- default_value: 10
+ default_value: 11
min: 10
max: 13
- name: osd_plus_code_short
@@ -3103,24 +3151,25 @@ groups:
field: plus_code_short
default_value: "0"
table: osd_plus_code_short
- type: uint8_t
- name: osd_ahi_style
description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
+ field: ahi_style
default_value: "DEFAULT"
table: osd_ahi_style
+ type: uint8_t
- name: osd_force_grid
field: force_grid
type: bool
- default_value: "OFF"
+ default_value: OFF
description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
- name: osd_ahi_bordered
field: ahi_bordered
type: bool
description: Shows a border/corners around the AHI region (pixel OSD only)
- default_value: "OFF"
+ default_value: OFF
- name: osd_ahi_width
field: ahi_width
@@ -3139,7 +3188,7 @@ groups:
min: -128
max: 127
description: AHI vertical offset from center (pixel OSD only)
- default_value: 0
+ default_value: -18
- name: osd_sidebar_horizontal_offset
field: sidebar_horizontal_offset
@@ -3162,7 +3211,7 @@ groups:
- name: osd_home_position_arm_screen
type: bool
- default_value: "ON"
+ default_value: ON
description: Should home position coordinates be displayed on the arming screen.
- name: osd_pan_servo_index
@@ -3170,6 +3219,7 @@ groups:
field: pan_servo_index
min: 0
max: 10
+ default_value: 0
- name: osd_pan_servo_pwm2centideg
description: 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.
@@ -3190,7 +3240,7 @@ groups:
table: i2c_speed
- name: cpu_underclock
description: "This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz"
- default_value: "OFF"
+ default_value: OFF
field: cpuUnderclock
condition: USE_UNDERCLOCK
type: bool
@@ -3200,13 +3250,13 @@ groups:
table: debug_modes
- name: throttle_tilt_comp_str
description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
- default_value: "0"
+ default_value: 0
field: throttle_tilt_compensation_strength
min: 0
max: 100
- name: name
description: "Craft name"
- default_value: "Empty string"
+ default_value: ""
- name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
type: modeActivationOperatorConfig_t
@@ -3226,20 +3276,21 @@ groups:
members:
- name: stats
description: "General switch of the statistics recording feature (a.k.a. odometer)"
- default_value: "OFF"
+ default_value: OFF
field: stats_enabled
type: bool
- name: stats_total_time
description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
- default_value: "0"
+ default_value: 0
max: INT32_MAX
- name: stats_total_dist
description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
- default_value: "0"
+ default_value: 0
max: INT32_MAX
- name: stats_total_energy
max: INT32_MAX
condition: USE_ADC
+ default_value: 0
- name: PG_TIME_CONFIG
type: timeConfig_t
@@ -3247,7 +3298,7 @@ groups:
members:
- name: tz_offset
description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
- default_value: "0"
+ default_value: 0
min: -1440
max: 1440
- name: tz_automatic_dst
@@ -3262,7 +3313,7 @@ groups:
members:
- name: display_force_sw_blink
description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
- default_value: "OFF"
+ default_value: OFF
field: force_sw_blink
type: bool
@@ -3273,12 +3324,12 @@ groups:
members:
- name: vtx_halfduplex
description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
- default_value: "ON"
+ default_value: ON
field: halfDuplex
type: bool
- name: vtx_smartaudio_early_akk_workaround
description: "Enable workaround for early AKK SAudio-enabled VTX bug."
- default_value: "ON"
+ default_value: ON
field: smartAudioEarlyAkkWorkaroundEnable
type: bool
@@ -3289,19 +3340,19 @@ groups:
members:
- name: vtx_band
description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
- default_value: "4"
+ default_value: 4
field: band
min: VTX_SETTINGS_NO_BAND
max: VTX_SETTINGS_MAX_BAND
- name: vtx_channel
description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
- default_value: "1"
+ default_value: 1
field: channel
min: VTX_SETTINGS_MIN_CHANNEL
max: VTX_SETTINGS_MAX_CHANNEL
- name: vtx_power
description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
- default_value: "1"
+ default_value: 1
field: power
min: VTX_SETTINGS_MIN_POWER
max: VTX_SETTINGS_MAX_POWER
@@ -3315,9 +3366,10 @@ groups:
field: pitModeChan
min: VTX_SETTINGS_MIN_CHANNEL
max: VTX_SETTINGS_MAX_CHANNEL
+ default_value: 1
- name: vtx_max_power_override
description: "Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities"
- default_value: "0"
+ default_value: 0
field: maxPowerOverride
min: 0
max: 10000
@@ -3333,6 +3385,7 @@ groups:
default_value: "target specific"
min: 0
max: 255
+ default_value: :BOX_PERMANENT_ID_NONE
type: uint8_t
- name: pinio_box2
field: permanentId[1]
@@ -3340,6 +3393,7 @@ groups:
description: "Mode assignment for PINIO#1"
min: 0
max: 255
+ default_value: :BOX_PERMANENT_ID_NONE
type: uint8_t
- name: pinio_box3
field: permanentId[2]
@@ -3347,6 +3401,7 @@ groups:
description: "Mode assignment for PINIO#1"
min: 0
max: 255
+ default_value: :BOX_PERMANENT_ID_NONE
type: uint8_t
- name: pinio_box4
field: permanentId[3]
@@ -3354,6 +3409,7 @@ groups:
description: "Mode assignment for PINIO#1"
min: 0
max: 255
+ default_value: :BOX_PERMANENT_ID_NONE
type: uint8_t
- name: PG_LOG_CONFIG
@@ -3365,13 +3421,13 @@ groups:
field: level
table: log_level
description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
- default_value: "`ERROR`"
+ default_value: "ERROR"
- name: log_topics
field: topics
min: 0
max: UINT32_MAX
description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
- default_value: "0"
+ default_value: 0
- name: PG_ESC_SENSOR_CONFIG
type: escSensorConfig_t
@@ -3379,10 +3435,11 @@ groups:
condition: USE_ESC_SENSOR
members:
- name: esc_sensor_listen_only
- default_value: "OFF"
+ default_value: OFF
description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
field: listenOnly
type: bool
+ default_value: OFF
- name: PG_SMARTPORT_MASTER_CONFIG
type: smartportMasterConfig_t
@@ -3392,9 +3449,11 @@ groups:
- name: smartport_master_halfduplex
field: halfDuplex
type: bool
+ default_value: ON
- name: smartport_master_inverted
field: inverted
type: bool
+ default_value: OFF
- name: PG_DJI_OSD_CONFIG
type: djiOsdConfig_t
@@ -3406,9 +3465,10 @@ groups:
field: proto_workarounds
min: 0
max: UINT8_MAX
+ default_value: 1
- name: dji_use_name_for_messages
description: "Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance"
- default_value: "ON"
+ default_value: ON
field: use_name_for_messages
type: bool
- name: dji_esc_temp_source
diff --git a/src/main/fc/stats.c b/src/main/fc/stats.c
index 43534a62a0..f34e2d949f 100644
--- a/src/main/fc/stats.c
+++ b/src/main/fc/stats.c
@@ -3,6 +3,7 @@
#ifdef USE_STATS
+#include "fc/settings.h"
#include "fc/stats.h"
#include "sensors/battery.h"
@@ -20,11 +21,11 @@
PG_REGISTER_WITH_RESET_TEMPLATE(statsConfig_t, statsConfig, PG_STATS_CONFIG, 1);
PG_RESET_TEMPLATE(statsConfig_t, statsConfig,
- .stats_enabled = 0,
- .stats_total_time = 0,
- .stats_total_dist = 0,
+ .stats_enabled = SETTING_STATS_DEFAULT,
+ .stats_total_time = SETTING_STATS_TOTAL_TIME_DEFAULT,
+ .stats_total_dist = SETTING_STATS_TOTAL_DIST_DEFAULT,
#ifdef USE_ADC
- .stats_total_energy = 0
+ .stats_total_energy = SETTING_STATS_TOTAL_ENERGY_DEFAULT
#endif
);
diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c
index 6ac2783c18..7a0c3612d7 100644
--- a/src/main/flight/failsafe.c
+++ b/src/main/flight/failsafe.c
@@ -40,6 +40,7 @@
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/controlrate_profile.h"
+#include "fc/settings.h"
#include "flight/failsafe.h"
#include "flight/mixer.h"
@@ -67,19 +68,19 @@ static failsafeState_t failsafeState;
PG_REGISTER_WITH_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 1);
PG_RESET_TEMPLATE(failsafeConfig_t, failsafeConfig,
- .failsafe_delay = 5, // 0.5 sec
- .failsafe_recovery_delay = 5, // 0.5 seconds (plus 200ms explicit delay)
- .failsafe_off_delay = 200, // 20sec
- .failsafe_throttle = 1000, // default throttle off.
- .failsafe_throttle_low_delay = 0, // default throttle low delay for "just disarm" on failsafe condition
- .failsafe_procedure = FAILSAFE_PROCEDURE_AUTO_LANDING, // default full failsafe procedure
- .failsafe_fw_roll_angle = -200, // 20 deg left
- .failsafe_fw_pitch_angle = 100, // 10 deg dive (yes, positive means dive)
- .failsafe_fw_yaw_rate = -45, // 45 deg/s left yaw (left is negative, 8s for full turn)
- .failsafe_stick_motion_threshold = 50,
- .failsafe_min_distance = 0, // No minimum distance for failsafe by default
- .failsafe_min_distance_procedure = FAILSAFE_PROCEDURE_DROP_IT, // default minimum distance failsafe procedure
- .failsafe_mission = true, // Enable failsafe in WP mode or not
+ .failsafe_delay = SETTING_FAILSAFE_DELAY_DEFAULT, // 0.5 sec
+ .failsafe_recovery_delay = SETTING_FAILSAFE_RECOVERY_DELAY_DEFAULT, // 0.5 seconds (plus 200ms explicit delay)
+ .failsafe_off_delay = SETTING_FAILSAFE_OFF_DELAY_DEFAULT, // 20sec
+ .failsafe_throttle = SETTING_FAILSAFE_THROTTLE_DEFAULT, // default throttle off.
+ .failsafe_throttle_low_delay = SETTING_FAILSAFE_THROTTLE_LOW_DELAY_DEFAULT, // default throttle low delay for "just disarm" on failsafe condition
+ .failsafe_procedure = SETTING_FAILSAFE_PROCEDURE_DEFAULT, // default full failsafe procedure
+ .failsafe_fw_roll_angle = SETTING_FAILSAFE_FW_ROLL_ANGLE_DEFAULT, // 20 deg left
+ .failsafe_fw_pitch_angle = SETTING_FAILSAFE_FW_PITCH_ANGLE_DEFAULT, // 10 deg dive (yes, positive means dive)
+ .failsafe_fw_yaw_rate = SETTING_FAILSAFE_FW_YAW_RATE_DEFAULT, // 45 deg/s left yaw (left is negative, 8s for full turn)
+ .failsafe_stick_motion_threshold = SETTING_FAILSAFE_STICK_THRESHOLD_DEFAULT,
+ .failsafe_min_distance = SETTING_FAILSAFE_MIN_DISTANCE_DEFAULT, // No minimum distance for failsafe by default
+ .failsafe_min_distance_procedure = SETTING_FAILSAFE_MIN_DISTANCE_PROCEDURE_DEFAULT, // default minimum distance failsafe procedure
+ .failsafe_mission = SETTING_FAILSAFE_MISSION_DEFAULT, // Enable failsafe in WP mode or not
);
typedef enum {
diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c
index d75f416f8f..3401e3b00c 100644
--- a/src/main/flight/imu.c
+++ b/src/main/flight/imu.c
@@ -45,6 +45,7 @@ FILE_COMPILE_FOR_SPEED
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/hil.h"
#include "flight/imu.h"
@@ -99,13 +100,13 @@ STATIC_FASTRAM bool gpsHeadingInitialized;
PG_REGISTER_WITH_RESET_TEMPLATE(imuConfig_t, imuConfig, PG_IMU_CONFIG, 2);
PG_RESET_TEMPLATE(imuConfig_t, imuConfig,
- .dcm_kp_acc = 2500, // 0.25 * 10000
- .dcm_ki_acc = 50, // 0.005 * 10000
- .dcm_kp_mag = 10000, // 1.00 * 10000
- .dcm_ki_mag = 0, // 0.00 * 10000
- .small_angle = 25,
- .acc_ignore_rate = 0,
- .acc_ignore_slope = 0
+ .dcm_kp_acc = SETTING_IMU_DCM_KP_DEFAULT, // 0.25 * 10000
+ .dcm_ki_acc = SETTING_IMU_DCM_KI_DEFAULT, // 0.005 * 10000
+ .dcm_kp_mag = SETTING_IMU_DCM_KP_MAG_DEFAULT, // 1.00 * 10000
+ .dcm_ki_mag = SETTING_IMU_DCM_KI_MAG_DEFAULT, // 0.00 * 10000
+ .small_angle = SETTING_SMALL_ANGLE_DEFAULT,
+ .acc_ignore_rate = SETTING_IMU_ACC_IGNORE_RATE_DEFAULT,
+ .acc_ignore_slope = SETTING_IMU_ACC_IGNORE_SLOPE_DEFAULT
);
STATIC_UNIT_TESTED void imuComputeRotationMatrix(void)
@@ -156,8 +157,13 @@ void imuInit(void)
gpsHeadingInitialized = false;
// Create magnetic declination matrix
+#ifdef USE_MAG
const int deg = compassConfig()->mag_declination / 100;
const int min = compassConfig()->mag_declination % 100;
+#else
+ const int deg = 0;
+ const int min = 0;
+#endif
imuSetMagneticDeclination(deg + min / 60.0f);
quaternionInitUnit(&orientation);
diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c
index f5d7ba2279..af1ca40a20 100755
--- a/src/main/flight/mixer.c
+++ b/src/main/flight/mixer.c
@@ -43,6 +43,7 @@ FILE_COMPILE_FOR_SPEED
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/controlrate_profile.h"
+#include "fc/settings.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
@@ -75,19 +76,19 @@ static EXTENDED_FASTRAM int8_t motorYawMultiplier = 1;
PG_REGISTER_WITH_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig, PG_REVERSIBLE_MOTORS_CONFIG, 0);
PG_RESET_TEMPLATE(reversibleMotorsConfig_t, reversibleMotorsConfig,
- .deadband_low = 1406,
- .deadband_high = 1514,
- .neutral = 1460
+ .deadband_low = SETTING_3D_DEADBAND_LOW_DEFAULT,
+ .deadband_high = SETTING_3D_DEADBAND_HIGH_DEFAULT,
+ .neutral = SETTING_3D_NEUTRAL_DEFAULT
);
PG_REGISTER_WITH_RESET_TEMPLATE(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 3);
PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
- .motorDirectionInverted = 0,
- .platformType = PLATFORM_MULTIROTOR,
- .hasFlaps = false,
- .appliedMixerPreset = -1, //This flag is not available in CLI and used by Configurator only
- .fwMinThrottleDownPitchAngle = 0
+ .motorDirectionInverted = SETTING_MOTOR_DIRECTION_INVERTED_DEFAULT,
+ .platformType = SETTING_PLATFORM_TYPE_DEFAULT,
+ .hasFlaps = SETTING_HAS_FLAPS_DEFAULT,
+ .appliedMixerPreset = SETTING_MODEL_PREVIEW_TYPE_DEFAULT, //This flag is not available in CLI and used by Configurator only
+ .fwMinThrottleDownPitchAngle = SETTING_FW_MIN_THROTTLE_DOWN_PITCH_DEFAULT
);
#ifdef BRUSHED_MOTORS
@@ -103,16 +104,18 @@ PG_RESET_TEMPLATE(mixerConfig_t, mixerConfig,
PG_REGISTER_WITH_RESET_TEMPLATE(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 7);
PG_RESET_TEMPLATE(motorConfig_t, motorConfig,
- .motorPwmProtocol = DEFAULT_PWM_PROTOCOL,
- .motorPwmRate = DEFAULT_PWM_RATE,
- .maxthrottle = DEFAULT_MAX_THROTTLE,
- .mincommand = 1000,
- .motorAccelTimeMs = 0,
- .motorDecelTimeMs = 0,
- .throttleIdle = 15.0f,
- .throttleScale = 1.0f,
- .motorPoleCount = 14, // Most brushless motors that we use are 14 poles
- .flipOverAfterPowerFactor = 65
+ .motorPwmProtocol = SETTING_MOTOR_PWM_PROTOCOL_DEFAULT,
+ .motorPwmRate = SETTING_MOTOR_PWM_RATE_DEFAULT,
+ .maxthrottle = SETTING_MAX_THROTTLE_DEFAULT,
+ .mincommand = SETTING_MIN_COMMAND_DEFAULT,
+ .motorAccelTimeMs = SETTING_MOTOR_ACCEL_TIME_DEFAULT,
+ .motorDecelTimeMs = SETTING_MOTOR_DECEL_TIME_DEFAULT,
+ .throttleIdle = SETTING_THROTTLE_IDLE_DEFAULT,
+ .throttleScale = SETTING_THROTTLE_SCALE_DEFAULT,
+ .motorPoleCount = SETTING_MOTOR_POLES_DEFAULT, // Most brushless motors that we use are 14 poles
+#ifdef USE_DSHOT
+ .flipOverAfterPowerFactor = SETTING_FLIP_OVER_AFTER_CRASH_POWER_FACTOR_DEFAULT,
+#endif
);
PG_REGISTER_ARRAY(motorMixer_t, MAX_SUPPORTED_MOTORS, primaryMotorMixer, PG_MOTOR_MIXER, 0);
diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c
index 2bb7c4a204..b8c4b94e24 100644
--- a/src/main/flight/pid.c
+++ b/src/main/flight/pid.c
@@ -40,6 +40,7 @@ FILE_COMPILE_FOR_SPEED
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/pid.h"
#include "flight/imu.h"
@@ -163,38 +164,38 @@ PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.bank_mc = {
.pid = {
- [PID_ROLL] = { 40, 30, 23, 60 },
- [PID_PITCH] = { 40, 30, 23, 60 },
- [PID_YAW] = { 85, 45, 0, 60 },
+ [PID_ROLL] = { SETTING_MC_P_ROLL_DEFAULT, SETTING_MC_I_ROLL_DEFAULT, SETTING_MC_D_ROLL_DEFAULT, SETTING_MC_CD_ROLL_DEFAULT },
+ [PID_PITCH] = { SETTING_MC_P_PITCH_DEFAULT, SETTING_MC_I_PITCH_DEFAULT, SETTING_MC_D_PITCH_DEFAULT, SETTING_MC_CD_PITCH_DEFAULT },
+ [PID_YAW] = { SETTING_MC_P_YAW_DEFAULT, SETTING_MC_I_YAW_DEFAULT, SETTING_MC_D_YAW_DEFAULT, SETTING_MC_CD_YAW_DEFAULT },
[PID_LEVEL] = {
- .P = 20, // Self-level strength
- .I = 15, // Self-leveing low-pass frequency (0 - disabled)
- .D = 75, // 75% horizon strength
+ .P = SETTING_MC_P_LEVEL_DEFAULT, // Self-level strength
+ .I = SETTING_MC_I_LEVEL_DEFAULT, // Self-leveing low-pass frequency (0 - disabled)
+ .D = SETTING_MC_D_LEVEL_DEFAULT, // 75% horizon strength
.FF = 0,
},
- [PID_HEADING] = { 60, 0, 0, 0 },
+ [PID_HEADING] = { SETTING_NAV_MC_HEADING_P_DEFAULT, 0, 0, 0 },
[PID_POS_XY] = {
- .P = 65, // NAV_POS_XY_P * 100
+ .P = SETTING_NAV_MC_POS_XY_P_DEFAULT, // NAV_POS_XY_P * 100
.I = 0,
.D = 0,
.FF = 0,
},
[PID_VEL_XY] = {
- .P = 40, // NAV_VEL_XY_P * 20
- .I = 15, // NAV_VEL_XY_I * 100
- .D = 100, // NAV_VEL_XY_D * 100
- .FF = 40, // NAV_VEL_XY_D * 100
+ .P = SETTING_NAV_MC_VEL_XY_P_DEFAULT, // NAV_VEL_XY_P * 20
+ .I = SETTING_NAV_MC_VEL_XY_I_DEFAULT, // NAV_VEL_XY_I * 100
+ .D = SETTING_NAV_MC_VEL_XY_D_DEFAULT, // NAV_VEL_XY_D * 100
+ .FF = SETTING_NAV_MC_VEL_XY_FF_DEFAULT, // NAV_VEL_XY_D * 100
},
[PID_POS_Z] = {
- .P = 50, // NAV_POS_Z_P * 100
- .I = 0, // not used
- .D = 0, // not used
+ .P = SETTING_NAV_MC_POS_Z_P_DEFAULT, // NAV_POS_Z_P * 100
+ .I = 0, // not used
+ .D = 0, // not used
.FF = 0,
},
[PID_VEL_Z] = {
- .P = 100, // NAV_VEL_Z_P * 66.7
- .I = 50, // NAV_VEL_Z_I * 20
- .D = 10, // NAV_VEL_Z_D * 100
+ .P = SETTING_NAV_MC_VEL_Z_P_DEFAULT, // NAV_VEL_Z_P * 66.7
+ .I = SETTING_NAV_MC_VEL_Z_I_DEFAULT, // NAV_VEL_Z_I * 20
+ .D = SETTING_NAV_MC_VEL_Z_D_DEFAULT, // NAV_VEL_Z_D * 100
.FF = 0,
},
[PID_POS_HEADING] = {
@@ -208,83 +209,94 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
.bank_fw = {
.pid = {
- [PID_ROLL] = { 5, 7, 0, 50 },
- [PID_PITCH] = { 5, 7, 0, 50 },
- [PID_YAW] = { 6, 10, 0, 60 },
+ [PID_ROLL] = { SETTING_FW_P_ROLL_DEFAULT, SETTING_FW_I_ROLL_DEFAULT, 0, SETTING_FW_FF_ROLL_DEFAULT },
+ [PID_PITCH] = { SETTING_FW_P_PITCH_DEFAULT, SETTING_FW_I_PITCH_DEFAULT, 0, SETTING_FW_FF_PITCH_DEFAULT },
+ [PID_YAW] = { SETTING_FW_P_YAW_DEFAULT, SETTING_FW_I_YAW_DEFAULT, 0, SETTING_FW_FF_YAW_DEFAULT },
[PID_LEVEL] = {
- .P = 20, // Self-level strength
- .I = 5, // Self-leveing low-pass frequency (0 - disabled)
- .D = 75, // 75% horizon strength
+ .P = SETTING_FW_P_LEVEL_DEFAULT, // Self-level strength
+ .I = SETTING_FW_I_LEVEL_DEFAULT, // Self-leveing low-pass frequency (0 - disabled)
+ .D = SETTING_FW_D_LEVEL_DEFAULT, // 75% horizon strength
.FF = 0,
},
- [PID_HEADING] = { 60, 0, 0, 0 },
+ [PID_HEADING] = { SETTING_NAV_FW_HEADING_P_DEFAULT, 0, 0, 0 },
[PID_POS_Z] = {
- .P = 40, // FW_POS_Z_P * 10
- .I = 5, // FW_POS_Z_I * 10
- .D = 10, // FW_POS_Z_D * 10
+ .P = SETTING_NAV_FW_POS_Z_P_DEFAULT, // FW_POS_Z_P * 10
+ .I = SETTING_NAV_FW_POS_Z_I_DEFAULT, // FW_POS_Z_I * 10
+ .D = SETTING_NAV_FW_POS_Z_D_DEFAULT, // FW_POS_Z_D * 10
.FF = 0,
},
[PID_POS_XY] = {
- .P = 75, // FW_POS_XY_P * 100
- .I = 5, // FW_POS_XY_I * 100
- .D = 8, // FW_POS_XY_D * 100
+ .P = SETTING_NAV_FW_POS_XY_P_DEFAULT, // FW_POS_XY_P * 100
+ .I = SETTING_NAV_FW_POS_XY_I_DEFAULT, // FW_POS_XY_I * 100
+ .D = SETTING_NAV_FW_POS_XY_D_DEFAULT, // FW_POS_XY_D * 100
.FF = 0,
},
[PID_POS_HEADING] = {
- .P = 30,
- .I = 2,
- .D = 0,
+ .P = SETTING_NAV_FW_POS_HDG_P_DEFAULT,
+ .I = SETTING_NAV_FW_POS_HDG_I_DEFAULT,
+ .D = SETTING_NAV_FW_POS_HDG_D_DEFAULT,
.FF = 0
}
}
},
- .dterm_lpf_type = 1, //Default to BIQUAD
- .dterm_lpf_hz = 40,
- .dterm_lpf2_type = 1, //Default to BIQUAD
- .dterm_lpf2_hz = 0, // Off by default
- .yaw_lpf_hz = 0,
+ .dterm_lpf_type = SETTING_DTERM_LPF_TYPE_DEFAULT,
+ .dterm_lpf_hz = SETTING_DTERM_LPF_HZ_DEFAULT,
+ .dterm_lpf2_type = SETTING_DTERM_LPF2_TYPE_DEFAULT,
+ .dterm_lpf2_hz = SETTING_DTERM_LPF2_HZ_DEFAULT,
+ .yaw_lpf_hz = SETTING_YAW_LPF_HZ_DEFAULT,
- .itermWindupPointPercent = 50, // Percent
+ .itermWindupPointPercent = SETTING_ITERM_WINDUP_DEFAULT,
- .axisAccelerationLimitYaw = 10000, // dps/s
- .axisAccelerationLimitRollPitch = 0, // dps/s
+ .axisAccelerationLimitYaw = SETTING_RATE_ACCEL_LIMIT_YAW_DEFAULT,
+ .axisAccelerationLimitRollPitch = SETTING_RATE_ACCEL_LIMIT_ROLL_PITCH_DEFAULT,
- .heading_hold_rate_limit = HEADING_HOLD_RATE_LIMIT_DEFAULT,
+ .heading_hold_rate_limit = SETTING_HEADING_HOLD_RATE_LIMIT_DEFAULT,
- .max_angle_inclination[FD_ROLL] = 300, // 30 degrees
- .max_angle_inclination[FD_PITCH] = 300, // 30 degrees
- .pidSumLimit = PID_SUM_LIMIT_DEFAULT,
- .pidSumLimitYaw = PID_SUM_LIMIT_YAW_DEFAULT,
+ .max_angle_inclination[FD_ROLL] = SETTING_MAX_ANGLE_INCLINATION_RLL_DEFAULT,
+ .max_angle_inclination[FD_PITCH] = SETTING_MAX_ANGLE_INCLINATION_PIT_DEFAULT,
+ .pidSumLimit = SETTING_PIDSUM_LIMIT_DEFAULT,
+ .pidSumLimitYaw = SETTING_PIDSUM_LIMIT_YAW_DEFAULT,
- .fixedWingItermThrowLimit = FW_ITERM_THROW_LIMIT_DEFAULT,
- .fixedWingReferenceAirspeed = 1000,
- .fixedWingCoordinatedYawGain = 1.0f,
- .fixedWingCoordinatedPitchGain = 1.0f,
- .fixedWingItermLimitOnStickPosition = 0.5f,
- .fixedWingYawItermBankFreeze = 0,
+ .fixedWingItermThrowLimit = SETTING_FW_ITERM_THROW_LIMIT_DEFAULT,
+ .fixedWingReferenceAirspeed = SETTING_FW_REFERENCE_AIRSPEED_DEFAULT,
+ .fixedWingCoordinatedYawGain = SETTING_FW_TURN_ASSIST_YAW_GAIN_DEFAULT,
+ .fixedWingCoordinatedPitchGain = SETTING_FW_TURN_ASSIST_PITCH_GAIN_DEFAULT,
+ .fixedWingItermLimitOnStickPosition = SETTING_FW_ITERM_LIMIT_STICK_POSITION_DEFAULT,
+ .fixedWingYawItermBankFreeze = SETTING_FW_YAW_ITERM_FREEZE_BANK_ANGLE_DEFAULT,
- .loiter_direction = NAV_LOITER_RIGHT,
- .navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ,
- .navVelXyDtermAttenuation = 90,
- .navVelXyDtermAttenuationStart = 10,
- .navVelXyDtermAttenuationEnd = 60,
- .iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT,
- .iterm_relax = ITERM_RELAX_RP,
- .dBoostFactor = 1.25f,
- .dBoostMaxAtAlleceleration = 7500.0f,
- .dBoostGyroDeltaLpfHz = D_BOOST_GYRO_LPF_HZ,
- .antigravityGain = 1.0f,
- .antigravityAccelerator = 1.0f,
- .antigravityCutoff = ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF,
- .pidControllerType = PID_TYPE_AUTO,
- .navFwPosHdgPidsumLimit = PID_SUM_LIMIT_YAW_DEFAULT,
- .controlDerivativeLpfHz = 30,
- .kalman_q = 100,
- .kalman_w = 4,
- .kalman_sharpness = 100,
- .kalmanEnabled = 0,
- .fixedWingLevelTrim = 0,
+ .loiter_direction = SETTING_FW_LOITER_DIRECTION_DEFAULT,
+ .navVelXyDTermLpfHz = SETTING_NAV_MC_VEL_XY_DTERM_LPF_HZ_DEFAULT,
+ .navVelXyDtermAttenuation = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_DEFAULT,
+ .navVelXyDtermAttenuationStart = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_START_DEFAULT,
+ .navVelXyDtermAttenuationEnd = SETTING_NAV_MC_VEL_XY_DTERM_ATTENUATION_END_DEFAULT,
+ .iterm_relax_cutoff = SETTING_MC_ITERM_RELAX_CUTOFF_DEFAULT,
+ .iterm_relax = SETTING_MC_ITERM_RELAX_DEFAULT,
+
+#ifdef USE_D_BOOST
+ .dBoostFactor = SETTING_D_BOOST_FACTOR_DEFAULT,
+ .dBoostMaxAtAlleceleration = SETTING_D_BOOST_MAX_AT_ACCELERATION_DEFAULT,
+ .dBoostGyroDeltaLpfHz = SETTING_D_BOOST_GYRO_DELTA_LPF_HZ_DEFAULT,
+#endif
+
+#ifdef USE_ANTIGRAVITY
+ .antigravityGain = SETTING_ANTIGRAVITY_GAIN_DEFAULT,
+ .antigravityAccelerator = SETTING_ANTIGRAVITY_ACCELERATOR_DEFAULT,
+ .antigravityCutoff = SETTING_ANTIGRAVITY_CUTOFF_LPF_HZ_DEFAULT,
+#endif
+
+ .pidControllerType = SETTING_PID_TYPE_DEFAULT,
+ .navFwPosHdgPidsumLimit = SETTING_NAV_FW_POS_HDG_PIDSUM_LIMIT_DEFAULT,
+ .controlDerivativeLpfHz = SETTING_MC_CD_LPF_HZ_DEFAULT,
+
+#ifdef USE_GYRO_KALMAN
+ .kalman_q = SETTING_SETPOINT_KALMAN_Q_DEFAULT,
+ .kalman_w = SETTING_SETPOINT_KALMAN_W_DEFAULT,
+ .kalman_sharpness = SETTING_SETPOINT_KALMAN_SHARPNESS_DEFAULT,
+ .kalmanEnabled = SETTING_SETPOINT_KALMAN_ENABLED_DEFAULT,
+#endif
+
+ .fixedWingLevelTrim = SETTING_FW_LEVEL_PITCH_TRIM_DEFAULT,
);
bool pidInitFilters(void)
diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h
index 900e54575e..3f3d5a3bcc 100644
--- a/src/main/flight/pid.h
+++ b/src/main/flight/pid.h
@@ -138,19 +138,27 @@ typedef struct pidProfile_s {
uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
uint8_t iterm_relax; // Enable iterm suppression during stick input
+#ifdef USE_D_BOOST
float dBoostFactor;
float dBoostMaxAtAlleceleration;
uint8_t dBoostGyroDeltaLpfHz;
+#endif
+
+#ifdef USE_ANTIGRAVITY
float antigravityGain;
float antigravityAccelerator;
uint8_t antigravityCutoff;
+#endif
uint16_t navFwPosHdgPidsumLimit;
uint8_t controlDerivativeLpfHz;
+
+#ifdef USE_GYRO_KALMAN
uint16_t kalman_q;
uint16_t kalman_w;
uint16_t kalman_sharpness;
uint8_t kalmanEnabled;
+#endif
float fixedWingLevelTrim;
} pidProfile_t;
diff --git a/src/main/flight/pid_autotune.c b/src/main/flight/pid_autotune.c
index 245571c2f4..684f42d1b7 100755
--- a/src/main/flight/pid_autotune.c
+++ b/src/main/flight/pid_autotune.c
@@ -40,11 +40,10 @@
#include "fc/rc_controls.h"
#include "fc/rc_adjustments.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/pid.h"
-#define AUTOTUNE_FIXED_WING_OVERSHOOT_TIME 100
-#define AUTOTUNE_FIXED_WING_UNDERSHOOT_TIME 200
#define AUTOTUNE_FIXED_WING_INTEGRATOR_TC 600
#define AUTOTUNE_FIXED_WING_DECREASE_STEP 8 // 8%
#define AUTOTUNE_FIXED_WING_INCREASE_STEP 5 // 5%
@@ -54,11 +53,11 @@
PG_REGISTER_WITH_RESET_TEMPLATE(pidAutotuneConfig_t, pidAutotuneConfig, PG_PID_AUTOTUNE_CONFIG, 0);
PG_RESET_TEMPLATE(pidAutotuneConfig_t, pidAutotuneConfig,
- .fw_overshoot_time = AUTOTUNE_FIXED_WING_OVERSHOOT_TIME,
- .fw_undershoot_time = AUTOTUNE_FIXED_WING_UNDERSHOOT_TIME,
- .fw_max_rate_threshold = 50,
- .fw_ff_to_p_gain = 10,
- .fw_ff_to_i_time_constant = AUTOTUNE_FIXED_WING_INTEGRATOR_TC,
+ .fw_overshoot_time = SETTING_FW_AUTOTUNE_OVERSHOOT_TIME_DEFAULT,
+ .fw_undershoot_time = SETTING_FW_AUTOTUNE_UNDERSHOOT_TIME_DEFAULT,
+ .fw_max_rate_threshold = SETTING_FW_AUTOTUNE_THRESHOLD_DEFAULT,
+ .fw_ff_to_p_gain = SETTING_FW_AUTOTUNE_FF_TO_P_GAIN_DEFAULT,
+ .fw_ff_to_i_time_constant = SETTING_FW_AUTOTUNE_FF_TO_I_TC_DEFAULT,
);
typedef enum {
diff --git a/src/main/flight/rpm_filter.c b/src/main/flight/rpm_filter.c
index 6a9604651e..183220461e 100644
--- a/src/main/flight/rpm_filter.c
+++ b/src/main/flight/rpm_filter.c
@@ -38,6 +38,7 @@
#include "flight/mixer.h"
#include "sensors/esc_sensor.h"
#include "fc/config.h"
+#include "fc/settings.h"
#ifdef USE_RPM_FILTER
@@ -48,10 +49,10 @@
PG_REGISTER_WITH_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig, PG_RPM_FILTER_CONFIG, 1);
PG_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig,
- .gyro_filter_enabled = 0,
- .gyro_harmonics = 1,
- .gyro_min_hz = 100,
- .gyro_q = 500, );
+ .gyro_filter_enabled = SETTING_RPM_GYRO_FILTER_ENABLED_DEFAULT,
+ .gyro_harmonics = SETTING_RPM_GYRO_HARMONICS_DEFAULT,
+ .gyro_min_hz = SETTING_RPM_GYRO_MIN_HZ_DEFAULT,
+ .gyro_q = SETTING_RPM_GYRO_Q_DEFAULT, );
typedef struct
{
@@ -203,4 +204,4 @@ float rpmFilterGyroApply(uint8_t axis, float input)
return rpmGyroApplyFn(&gyroRpmFilters, axis, input);
}
-#endif
\ No newline at end of file
+#endif
diff --git a/src/main/flight/secondary_imu.c b/src/main/flight/secondary_imu.c
index da3a4dfde7..93cd11b9d1 100644
--- a/src/main/flight/secondary_imu.c
+++ b/src/main/flight/secondary_imu.c
@@ -21,19 +21,26 @@
* 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 "stdint.h"
-#include "common/utils.h"
-#include "common/axis.h"
-#include "flight/secondary_imu.h"
-#include "config/parameter_group_ids.h"
-#include "sensors/boardalignment.h"
-#include "sensors/compass.h"
#include "build/debug.h"
+#include "common/utils.h"
+#include "common/axis.h"
+
+#include "config/parameter_group_ids.h"
+
#include "drivers/sensor.h"
#include "drivers/accgyro/accgyro_bno055.h"
+#include "fc/settings.h"
+
+#include "flight/secondary_imu.h"
+
+#include "sensors/boardalignment.h"
+#include "sensors/compass.h"
+
PG_REGISTER_WITH_RESET_FN(secondaryImuConfig_t, secondaryImuConfig, PG_SECONDARY_IMU, 1);
EXTENDED_FASTRAM secondaryImuState_t secondaryImuState;
@@ -62,8 +69,13 @@ void secondaryImuInit(void)
{
secondaryImuState.active = false;
// Create magnetic declination matrix
+#ifdef USE_MAG
const int deg = compassConfig()->mag_declination / 100;
const int min = compassConfig()->mag_declination % 100;
+#else
+ const int deg = 0;
+ const int min = 0;
+#endif
secondaryImuSetMagneticDeclination(deg + min / 60.0f);
@@ -171,4 +183,4 @@ void secondaryImuFetchCalibration(void) {
void secondaryImuSetMagneticDeclination(float declination) { //Incoming units are degrees
secondaryImuState.magDeclination = declination * 10.0f; //Internally declination is stored in decidegrees
-}
\ No newline at end of file
+}
diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c
index 918a20ce99..df58e6f649 100755
--- a/src/main/flight/servos.c
+++ b/src/main/flight/servos.c
@@ -44,6 +44,7 @@
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "fc/controlrate_profile.h"
+#include "fc/settings.h"
#include "flight/imu.h"
#include "flight/mixer.h"
@@ -57,12 +58,12 @@
PG_REGISTER_WITH_RESET_TEMPLATE(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 1);
PG_RESET_TEMPLATE(servoConfig_t, servoConfig,
- .servoCenterPulse = 1500,
- .servoPwmRate = 50, // Default for analog servos
- .servo_lowpass_freq = 20, // Default servo update rate is 50Hz, everything above Nyquist frequency (25Hz) is going to fold and cause distortions
- .servo_protocol = SERVO_TYPE_PWM,
- .flaperon_throw_offset = FLAPERON_THROW_DEFAULT,
- .tri_unarmed_servo = 1
+ .servoCenterPulse = SETTING_SERVO_CENTER_PULSE_DEFAULT,
+ .servoPwmRate = SETTING_SERVO_PWM_RATE_DEFAULT, // Default for analog servos
+ .servo_lowpass_freq = SETTING_SERVO_LPF_HZ_DEFAULT, // Default servo update rate is 50Hz, everything above Nyquist frequency (25Hz) is going to fold and cause distortions
+ .servo_protocol = SETTING_SERVO_PROTOCOL_DEFAULT,
+ .flaperon_throw_offset = SETTING_FLAPERON_THROW_OFFSET_DEFAULT,
+ .tri_unarmed_servo = SETTING_TRI_UNARMED_SERVO_DEFAULT
);
PG_REGISTER_ARRAY_WITH_RESET_FN(servoMixer_t, MAX_SERVO_RULES, customServoMixers, PG_SERVO_MIXER, 1);
diff --git a/src/main/io/gps.c b/src/main/io/gps.c
index 2dbfd77766..3d693deba8 100755
--- a/src/main/io/gps.c
+++ b/src/main/io/gps.c
@@ -58,6 +58,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
typedef struct {
bool isDriverBased;
@@ -125,13 +126,13 @@ static gpsProviderDescriptor_t gpsProviders[GPS_PROVIDER_COUNT] = {
PG_REGISTER_WITH_RESET_TEMPLATE(gpsConfig_t, gpsConfig, PG_GPS_CONFIG, 0);
PG_RESET_TEMPLATE(gpsConfig_t, gpsConfig,
- .provider = GPS_UBLOX,
- .sbasMode = SBAS_NONE,
- .autoConfig = GPS_AUTOCONFIG_ON,
- .autoBaud = GPS_AUTOBAUD_ON,
- .dynModel = GPS_DYNMODEL_AIR_1G,
- .gpsMinSats = 6,
- .ubloxUseGalileo = false
+ .provider = SETTING_GPS_PROVIDER_DEFAULT,
+ .sbasMode = SETTING_GPS_SBAS_MODE_DEFAULT,
+ .autoConfig = SETTING_GPS_AUTO_CONFIG_DEFAULT,
+ .autoBaud = SETTING_GPS_AUTO_BAUD_DEFAULT,
+ .dynModel = SETTING_GPS_DYN_MODEL_DEFAULT,
+ .gpsMinSats = SETTING_GPS_MIN_SATS_DEFAULT,
+ .ubloxUseGalileo = SETTING_GPS_UBLOX_USE_GALILEO_DEFAULT
);
void gpsSetState(gpsState_e state)
diff --git a/src/main/io/lights.c b/src/main/io/lights.c
index fa6bd2fe4a..2329aa8bf0 100644
--- a/src/main/io/lights.c
+++ b/src/main/io/lights.c
@@ -31,9 +31,9 @@ PG_REGISTER_WITH_RESET_TEMPLATE(lightsConfig_t, lightsConfig, PG_LIGHTS_CONFIG,
PG_RESET_TEMPLATE(lightsConfig_t, lightsConfig,
.failsafe = {
- .enabled = true,
- .flash_period = 1000,
- .flash_on_time = 100
+ .enabled = SETTING_FAILSAFE_LIGHTS_DEFAULT,
+ .flash_period = SETTING_FAILSAFE_LIGHTS_FLASH_PERIOD_DEFAULT,
+ .flash_on_time = SETTING_FAILSAFE_LIGHTS_FLASH_ON_TIME_DEFAULT
}
);
diff --git a/src/main/io/osd.c b/src/main/io/osd.c
index 6861f8a675..b6943791f7 100644
--- a/src/main/io/osd.c
+++ b/src/main/io/osd.c
@@ -1615,7 +1615,11 @@ static bool osdDrawSingleElement(uint8_t item)
timeUs_t currentTimeUs = micros();
static int32_t timeSeconds = -1;
if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= 1000000) {
+#ifdef USE_WIND_ESTIMATOR
timeSeconds = calculateRemainingFlightTimeBeforeRTH(osdConfig()->estimations_wind_compensation);
+#else
+ timeSeconds = calculateRemainingFlightTimeBeforeRTH(false);
+#endif
updatedTimestamp = currentTimeUs;
}
if ((!ARMING_FLAG(ARMED)) || (timeSeconds == -1)) {
@@ -1642,7 +1646,11 @@ static bool osdDrawSingleElement(uint8_t item)
timeUs_t currentTimeUs = micros();
static int32_t distanceMeters = -1;
if (cmpTimeUs(currentTimeUs, updatedTimestamp) >= 1000000) {
+#ifdef USE_WIND_ESTIMATOR
distanceMeters = calculateRemainingDistanceBeforeRTH(osdConfig()->estimations_wind_compensation);
+#else
+ distanceMeters = calculateRemainingDistanceBeforeRTH(false);
+#endif
updatedTimestamp = currentTimeUs;
}
buff[0] = SYM_TRIP_DIST;
@@ -2659,71 +2667,84 @@ void osdDrawNextElement(void)
}
PG_RESET_TEMPLATE(osdConfig_t, osdConfig,
- .rssi_alarm = 20,
- .time_alarm = 10,
- .alt_alarm = 100,
- .dist_alarm = 1000,
- .neg_alt_alarm = 5,
- .current_alarm = 0,
- .imu_temp_alarm_min = -200,
- .imu_temp_alarm_max = 600,
- .esc_temp_alarm_min = -200,
- .esc_temp_alarm_max = 900,
- .gforce_alarm = 5,
- .gforce_axis_alarm_min = -5,
- .gforce_axis_alarm_max = 5,
+ .rssi_alarm = SETTING_OSD_RSSI_ALARM_DEFAULT,
+ .time_alarm = SETTING_OSD_TIME_ALARM_DEFAULT,
+ .alt_alarm = SETTING_OSD_ALT_ALARM_DEFAULT,
+ .dist_alarm = SETTING_OSD_DIST_ALARM_DEFAULT,
+ .neg_alt_alarm = SETTING_OSD_NEG_ALT_ALARM_DEFAULT,
+ .current_alarm = SETTING_OSD_CURRENT_ALARM_DEFAULT,
+ .imu_temp_alarm_min = SETTING_OSD_IMU_TEMP_ALARM_MIN_DEFAULT,
+ .imu_temp_alarm_max = SETTING_OSD_IMU_TEMP_ALARM_MAX_DEFAULT,
+ .esc_temp_alarm_min = SETTING_OSD_ESC_TEMP_ALARM_MIN_DEFAULT,
+ .esc_temp_alarm_max = SETTING_OSD_ESC_TEMP_ALARM_MAX_DEFAULT,
+ .gforce_alarm = SETTING_OSD_GFORCE_ALARM_DEFAULT,
+ .gforce_axis_alarm_min = SETTING_OSD_GFORCE_AXIS_ALARM_MIN_DEFAULT,
+ .gforce_axis_alarm_max = SETTING_OSD_GFORCE_AXIS_ALARM_MAX_DEFAULT,
#ifdef USE_BARO
- .baro_temp_alarm_min = -200,
- .baro_temp_alarm_max = 600,
+ .baro_temp_alarm_min = SETTING_OSD_BARO_TEMP_ALARM_MIN_DEFAULT,
+ .baro_temp_alarm_max = SETTING_OSD_BARO_TEMP_ALARM_MAX_DEFAULT,
#endif
#ifdef USE_SERIALRX_CRSF
- .snr_alarm = 4,
- .crsf_lq_format = OSD_CRSF_LQ_TYPE1,
- .link_quality_alarm = 70,
+ .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,
#endif
#ifdef USE_TEMPERATURE_SENSOR
- .temp_label_align = OSD_ALIGN_LEFT,
+ .temp_label_align = SETTING_OSD_TEMP_LABEL_ALIGN_DEFAULT,
#endif
- .video_system = VIDEO_SYSTEM_AUTO,
+ .video_system = SETTING_OSD_VIDEO_SYSTEM_DEFAULT,
+ .row_shiftdown = SETTING_OSD_ROW_SHIFTDOWN_DEFAULT,
- .ahi_reverse_roll = 0,
- .ahi_max_pitch = AH_MAX_PITCH_DEFAULT,
- .crosshairs_style = OSD_CROSSHAIRS_STYLE_DEFAULT,
- .horizon_offset = 0,
- .camera_uptilt = 0,
- .camera_fov_h = 135,
- .camera_fov_v = 85,
- .hud_margin_h = 3,
- .hud_margin_v = 3,
- .hud_homing = 0,
- .hud_homepoint = 0,
- .hud_radar_disp = 0,
- .hud_radar_range_min = 3,
- .hud_radar_range_max = 4000,
- .hud_radar_nearest = 0,
- .hud_wp_disp = 0,
- .left_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE,
- .right_sidebar_scroll = OSD_SIDEBAR_SCROLL_NONE,
- .sidebar_scroll_arrows = 0,
- .osd_home_position_arm_screen = true,
- .pan_servo_index = 0,
- .pan_servo_pwm2centideg = 0,
+ .ahi_reverse_roll = SETTING_OSD_AHI_REVERSE_ROLL_DEFAULT,
+ .ahi_max_pitch = SETTING_OSD_AHI_MAX_PITCH_DEFAULT,
+ .crosshairs_style = SETTING_OSD_CROSSHAIRS_STYLE_DEFAULT,
+ .horizon_offset = SETTING_OSD_HORIZON_OFFSET_DEFAULT,
+ .camera_uptilt = SETTING_OSD_CAMERA_UPTILT_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,
+ .hud_margin_v = SETTING_OSD_HUD_MARGIN_V_DEFAULT,
+ .hud_homing = SETTING_OSD_HUD_HOMING_DEFAULT,
+ .hud_homepoint = SETTING_OSD_HUD_HOMEPOINT_DEFAULT,
+ .hud_radar_disp = SETTING_OSD_HUD_RADAR_DISP_DEFAULT,
+ .hud_radar_range_min = SETTING_OSD_HUD_RADAR_RANGE_MIN_DEFAULT,
+ .hud_radar_range_max = SETTING_OSD_HUD_RADAR_RANGE_MAX_DEFAULT,
+ .hud_radar_nearest = SETTING_OSD_HUD_RADAR_NEAREST_DEFAULT,
+ .hud_wp_disp = SETTING_OSD_HUD_WP_DISP_DEFAULT,
+ .left_sidebar_scroll = SETTING_OSD_LEFT_SIDEBAR_SCROLL_DEFAULT,
+ .right_sidebar_scroll = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_DEFAULT,
+ .sidebar_scroll_arrows = SETTING_OSD_SIDEBAR_SCROLL_ARROWS_DEFAULT,
+ .sidebar_horizontal_offset = SETTING_OSD_SIDEBAR_HORIZONTAL_OFFSET_DEFAULT,
+ .left_sidebar_scroll_step = SETTING_OSD_LEFT_SIDEBAR_SCROLL_STEP_DEFAULT,
+ .right_sidebar_scroll_step = SETTING_OSD_RIGHT_SIDEBAR_SCROLL_STEP_DEFAULT,
+ .osd_home_position_arm_screen = SETTING_OSD_HOME_POSITION_ARM_SCREEN_DEFAULT,
+ .pan_servo_index = SETTING_OSD_PAN_SERVO_INDEX_DEFAULT,
+ .pan_servo_pwm2centideg = SETTING_OSD_PAN_SERVO_PWM2CENTIDEG_DEFAULT,
- .units = OSD_UNIT_METRIC,
- .main_voltage_decimals = 1,
+ .units = SETTING_OSD_UNITS_DEFAULT,
+ .main_voltage_decimals = SETTING_OSD_MAIN_VOLTAGE_DECIMALS_DEFAULT,
- .estimations_wind_compensation = true,
- .coordinate_digits = 9,
+#ifdef USE_WIND_ESTIMATOR
+ .estimations_wind_compensation = SETTING_OSD_ESTIMATIONS_WIND_COMPENSATION_DEFAULT,
+#endif
- .osd_failsafe_switch_layout = false,
+ .coordinate_digits = SETTING_OSD_COORDINATE_DIGITS_DEFAULT,
- .plus_code_digits = 11,
- .plus_code_short = 0,
+ .osd_failsafe_switch_layout = SETTING_OSD_FAILSAFE_SWITCH_LAYOUT_DEFAULT,
- .ahi_width = OSD_AHI_WIDTH * OSD_CHAR_WIDTH,
- .ahi_height = OSD_AHI_HEIGHT * OSD_CHAR_HEIGHT,
- .ahi_vertical_offset = -OSD_CHAR_HEIGHT,
+ .plus_code_digits = SETTING_OSD_PLUS_CODE_DIGITS_DEFAULT,
+ .plus_code_short = SETTING_OSD_PLUS_CODE_SHORT_DEFAULT,
+
+ .ahi_width = SETTING_OSD_AHI_WIDTH_DEFAULT,
+ .ahi_height = SETTING_OSD_AHI_HEIGHT_DEFAULT,
+ .ahi_vertical_offset = SETTING_OSD_AHI_VERTICAL_OFFSET_DEFAULT,
+ .ahi_bordered = SETTING_OSD_AHI_BORDERED_DEFAULT,
+ .ahi_style = SETTING_OSD_AHI_STYLE_DEFAULT,
+
+ .force_grid = SETTING_OSD_FORCE_GRID_DEFAULT,
+
+ .stats_energy_unit = SETTING_OSD_STATS_ENERGY_UNIT_DEFAULT
);
void pgResetFn_osdLayoutsConfig(osdLayoutsConfig_t *osdLayoutsConfig)
diff --git a/src/main/io/osd.h b/src/main/io/osd.h
index fe35e28b71..1dc185b0d1 100755
--- a/src/main/io/osd.h
+++ b/src/main/io/osd.h
@@ -333,13 +333,16 @@ typedef struct osdConfig_s {
uint8_t units; // from osd_unit_e
uint8_t stats_energy_unit; // from osd_stats_energy_unit_e
+#ifdef USE_WIND_ESTIMATOR
bool estimations_wind_compensation; // use wind compensation for estimated remaining flight/distance
+#endif
+
uint8_t coordinate_digits;
bool osd_failsafe_switch_layout;
uint8_t plus_code_digits; // Number of digits to use in OSD_PLUS_CODE
uint8_t plus_code_short;
- uint8_t osd_ahi_style;
+ uint8_t ahi_style;
uint8_t force_grid; // Force a pixel based OSD to use grid mode.
uint8_t ahi_bordered; // Only used by the AHI widget
uint8_t ahi_width; // In pixels, only used by the AHI widget
diff --git a/src/main/io/osd_canvas.c b/src/main/io/osd_canvas.c
index cab358f09c..5044e93c26 100644
--- a/src/main/io/osd_canvas.c
+++ b/src/main/io/osd_canvas.c
@@ -354,7 +354,7 @@ static bool osdCanvasDrawArtificialHorizonWidget(displayPort_t *display, display
}
if (!configured) {
widgetAHIStyle_e ahiStyle = 0;
- switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) {
+ switch ((osd_ahi_style_e)osdConfig()->ahi_style) {
case OSD_AHI_STYLE_DEFAULT:
ahiStyle = DISPLAY_WIDGET_AHI_STYLE_STAIRCASE;
break;
@@ -381,7 +381,7 @@ static bool osdCanvasDrawArtificialHorizonWidget(displayPort_t *display, display
// so that's 135degs each direction. Map that to the configured limit.
const float halfRange = 135.0f;
const float limit = halfRange / 180.0f * M_PIf;
- float multiplier = osdConfig()->osd_ahi_style == OSD_AHI_STYLE_DEFAULT ? 1.0f : halfRange / osdConfig()->ahi_max_pitch;
+ float multiplier = osdConfig()->ahi_style == OSD_AHI_STYLE_DEFAULT ? 1.0f : halfRange / osdConfig()->ahi_max_pitch;
widgetAHIData_t data = {
.pitch = constrainf(pitchAngle * multiplier, -limit, limit),
.roll = rollAngle,
@@ -413,7 +413,7 @@ void osdCanvasDrawArtificialHorizon(displayPort_t *display, displayCanvas_t *can
if ((now > nextDrawMinMs && totalError > 0.05f)|| now > nextDrawMaxMs) {
if (!osdCanvasDrawArtificialHorizonWidget(display, canvas, p, pitchAngle, rollAngle)) {
- switch ((osd_ahi_style_e)osdConfig()->osd_ahi_style) {
+ switch ((osd_ahi_style_e)osdConfig()->ahi_style) {
case OSD_AHI_STYLE_DEFAULT:
{
int x, y, w, h;
diff --git a/src/main/io/osd_dji_hd.c b/src/main/io/osd_dji_hd.c
index 023fb47037..ed72a973d3 100644
--- a/src/main/io/osd_dji_hd.c
+++ b/src/main/io/osd_dji_hd.c
@@ -122,10 +122,10 @@
PG_REGISTER_WITH_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig, PG_DJI_OSD_CONFIG, 2);
PG_RESET_TEMPLATE(djiOsdConfig_t, djiOsdConfig,
- .use_name_for_messages = true,
- .esc_temperature_source = DJI_OSD_TEMP_ESC,
- .proto_workarounds = DJI_OSD_USE_NON_STANDARD_MSP_ESC_SENSOR_DATA,
- .speedSource = DJI_OSD_SPEED_GROUND,
+ .use_name_for_messages = SETTING_DJI_USE_NAME_FOR_MESSAGES_DEFAULT,
+ .esc_temperature_source = SETTING_DJI_ESC_TEMP_SOURCE_DEFAULT,
+ .proto_workarounds = SETTING_DJI_WORKAROUNDS_DEFAULT,
+ .speedSource = SETTING_DJI_SPEED_SOURCE_DEFAULT,
);
// External dependency on looptime
diff --git a/src/main/io/piniobox.c b/src/main/io/piniobox.c
index b8b01ad329..4fbcc657e4 100644
--- a/src/main/io/piniobox.c
+++ b/src/main/io/piniobox.c
@@ -33,6 +33,7 @@
#include "fc/fc_msp.h"
#include "fc/fc_msp_box.h"
+#include "fc/settings.h"
#include "io/piniobox.h"
@@ -40,7 +41,7 @@
PG_REGISTER_WITH_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig, PG_PINIOBOX_CONFIG, 1);
PG_RESET_TEMPLATE(pinioBoxConfig_t, pinioBoxConfig,
- { BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE, BOX_PERMANENT_ID_NONE }
+ { SETTING_PINIO_BOX1_DEFAULT, SETTING_PINIO_BOX2_DEFAULT, SETTING_PINIO_BOX3_DEFAULT, SETTING_PINIO_BOX4_DEFAULT }
);
typedef struct pinioBoxRuntimeConfig_s {
@@ -68,4 +69,4 @@ void pinioBoxUpdate(void)
}
}
-#endif
\ No newline at end of file
+#endif
diff --git a/src/main/io/piniobox.h b/src/main/io/piniobox.h
index 74ba398a32..638fd04b4e 100644
--- a/src/main/io/piniobox.h
+++ b/src/main/io/piniobox.h
@@ -26,6 +26,12 @@
#include "common/time.h"
#include "drivers/pinio.h"
+
+#define BOX_PERMANENT_ID_USER1 47
+#define BOX_PERMANENT_ID_USER2 48
+#define BOX_PERMANENT_ID_NONE 255 // A permanent ID for no box mode
+
+
typedef struct pinioBoxConfig_s {
uint8_t permanentId[PINIO_COUNT];
} pinioBoxConfig_t;
diff --git a/src/main/io/serial.c b/src/main/io/serial.c
index d8dc546c6e..7c6360c43c 100644
--- a/src/main/io/serial.c
+++ b/src/main/io/serial.c
@@ -49,6 +49,7 @@
#include "io/serial.h"
#include "fc/cli.h"
+#include "fc/settings.h"
#include "msp/msp_serial.h"
@@ -147,7 +148,7 @@ void pgResetFn_serialConfig(serialConfig_t *serialConfig)
}
#endif
- serialConfig->reboot_character = 'R';
+ serialConfig->reboot_character = SETTING_REBOOT_CHARACTER_DEFAULT;
}
baudRate_e lookupBaudRateIndex(uint32_t baudRate)
diff --git a/src/main/io/smartport_master.c b/src/main/io/smartport_master.c
index 95e1c74b22..ade2b00acc 100644
--- a/src/main/io/smartport_master.c
+++ b/src/main/io/smartport_master.c
@@ -34,6 +34,8 @@ FILE_COMPILE_FOR_SPEED
#include "drivers/serial.h"
#include "drivers/time.h"
+#include "fc/settings.h"
+
#include "io/serial.h"
#include "io/smartport_master.h"
@@ -137,8 +139,8 @@ typedef struct {
PG_REGISTER_WITH_RESET_TEMPLATE(smartportMasterConfig_t, smartportMasterConfig, PG_SMARTPORT_MASTER_CONFIG, 0);
PG_RESET_TEMPLATE(smartportMasterConfig_t, smartportMasterConfig,
- .halfDuplex = true,
- .inverted = false
+ .halfDuplex = SETTING_SMARTPORT_MASTER_HALFDUPLEX_DEFAULT,
+ .inverted = SETTING_SMARTPORT_MASTER_INVERTED_DEFAULT
);
static serialPort_t *smartportMasterSerialPort = NULL;
diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c
index f4b999a534..eabe0d1f00 100644
--- a/src/main/io/vtx.c
+++ b/src/main/io/vtx.c
@@ -36,6 +36,7 @@
#include "fc/config.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/failsafe.h"
@@ -46,12 +47,12 @@
PG_REGISTER_WITH_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig, PG_VTX_SETTINGS_CONFIG, 2);
PG_RESET_TEMPLATE(vtxSettingsConfig_t, vtxSettingsConfig,
- .band = VTX_SETTINGS_DEFAULT_BAND,
- .channel = VTX_SETTINGS_DEFAULT_CHANNEL,
- .power = VTX_SETTINGS_DEFAULT_POWER,
- .pitModeChan = VTX_SETTINGS_DEFAULT_PITMODE_CHANNEL,
- .lowPowerDisarm = VTX_LOW_POWER_DISARM_OFF,
- .maxPowerOverride = 0,
+ .band = SETTING_VTX_BAND_DEFAULT,
+ .channel = SETTING_VTX_CHANNEL_DEFAULT,
+ .power = SETTING_VTX_POWER_DEFAULT,
+ .pitModeChan = SETTING_VTX_PIT_MODE_CHAN_DEFAULT,
+ .lowPowerDisarm = SETTING_VTX_LOW_POWER_DISARM_DEFAULT,
+ .maxPowerOverride = SETTING_VTX_MAX_POWER_OVERRIDE_DEFAULT,
);
typedef enum {
diff --git a/src/main/io/vtx_control.c b/src/main/io/vtx_control.c
index f80b992c29..9a3c2ef633 100644
--- a/src/main/io/vtx_control.c
+++ b/src/main/io/vtx_control.c
@@ -31,6 +31,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "io/beeper.h"
#include "io/osd.h"
@@ -42,8 +43,8 @@
PG_REGISTER_WITH_RESET_TEMPLATE(vtxConfig_t, vtxConfig, PG_VTX_CONFIG, 3);
PG_RESET_TEMPLATE(vtxConfig_t, vtxConfig,
- .halfDuplex = true,
- .smartAudioEarlyAkkWorkaroundEnable = true,
+ .halfDuplex = SETTING_VTX_HALFDUPLEX_DEFAULT,
+ .smartAudioEarlyAkkWorkaroundEnable = SETTING_VTX_SMARTAUDIO_EARLY_AKK_WORKAROUND_DEFAULT,
);
static uint8_t locked = 0;
@@ -182,4 +183,3 @@ void vtxCyclePower(const uint8_t powerStep)
}
#endif
-
diff --git a/src/main/io/vtx_smartaudio.c b/src/main/io/vtx_smartaudio.c
index cb057f0fc5..31030573d5 100644
--- a/src/main/io/vtx_smartaudio.c
+++ b/src/main/io/vtx_smartaudio.c
@@ -43,6 +43,8 @@
#include "drivers/time.h"
#include "drivers/vtx_common.h"
+#include "fc/settings.h"
+
#include "io/serial.h"
#include "io/vtx.h"
#include "io/vtx_control.h"
@@ -129,8 +131,8 @@ saPowerTable_t saPowerTable[VTX_SMARTAUDIO_MAX_POWER_COUNT] = {
smartAudioDevice_t saDevice = {
.version = SA_UNKNOWN,
- .channel = -1,
- .power = -1,
+ .channel = SETTING_VTX_CHANNEL_DEFAULT,
+ .power = SETTING_VTX_POWER_DEFAULT,
.mode = 0,
.freq = 0,
.orfreq = 0,
diff --git a/src/main/navigation/navigation.c b/src/main/navigation/navigation.c
index 9cc98a7260..c953686269 100755
--- a/src/main/navigation/navigation.c
+++ b/src/main/navigation/navigation.c
@@ -39,6 +39,7 @@
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "flight/imu.h"
#include "flight/mixer.h"
@@ -97,92 +98,96 @@ PG_RESET_TEMPLATE(navConfig_t, navConfig,
.general = {
.flags = {
- .use_thr_mid_for_althold = 0,
- .extra_arming_safety = NAV_EXTRA_ARMING_SAFETY_ON,
- .user_control_mode = NAV_GPS_ATTI,
- .rth_alt_control_mode = NAV_RTH_AT_LEAST_ALT,
- .rth_climb_first = 1, // Climb first, turn after reaching safe altitude
- .rth_climb_ignore_emerg = 0, // Ignore GPS loss on initial climb
- .rth_tail_first = 0,
- .disarm_on_landing = 0,
- .rth_allow_landing = NAV_RTH_ALLOW_LANDING_ALWAYS,
- .nav_overrides_motor_stop = NOMS_ALL_NAV,
+ .use_thr_mid_for_althold = SETTING_NAV_USE_MIDTHR_FOR_ALTHOLD_DEFAULT,
+ .extra_arming_safety = SETTING_NAV_EXTRA_ARMING_SAFETY_DEFAULT,
+ .user_control_mode = SETTING_NAV_USER_CONTROL_MODE_DEFAULT,
+ .rth_alt_control_mode = SETTING_NAV_RTH_ALT_MODE_DEFAULT,
+ .rth_climb_first = SETTING_NAV_RTH_CLIMB_FIRST_DEFAULT, // Climb first, turn after reaching safe altitude
+ .rth_climb_ignore_emerg = SETTING_NAV_RTH_CLIMB_IGNORE_EMERG_DEFAULT, // Ignore GPS loss on initial climb
+ .rth_tail_first = SETTING_NAV_RTH_TAIL_FIRST_DEFAULT,
+ .disarm_on_landing = SETTING_NAV_DISARM_ON_LANDING_DEFAULT,
+ .rth_allow_landing = SETTING_NAV_RTH_ALLOW_LANDING_DEFAULT,
+ .nav_overrides_motor_stop = SETTING_NAV_OVERRIDES_MOTOR_STOP_DEFAULT,
},
// General navigation parameters
- .pos_failure_timeout = 5, // 5 sec
- .waypoint_radius = 100, // 2m diameter
- .waypoint_safe_distance = 10000, // centimeters - first waypoint should be closer than this
- .max_auto_speed = 300, // 3 m/s = 10.8 km/h
- .max_auto_climb_rate = 500, // 5 m/s
- .max_manual_speed = 500,
- .max_manual_climb_rate = 200,
- .land_descent_rate = 200, // centimeters/s
- .land_slowdown_minalt = 500, // altitude in centimeters
- .land_slowdown_maxalt = 2000, // altitude in meters
- .emerg_descent_rate = 500, // centimeters/s
- .min_rth_distance = 500, // centimeters, if closer than this land immediately
- .rth_altitude = 1000, // altitude in centimeters
- .rth_home_altitude = 0, // altitude in centimeters
- .rth_abort_threshold = 50000, // centimeters - 500m should be safe for all aircraft
- .max_terrain_follow_altitude = 100, // max altitude in centimeters in terrain following mode
- .safehome_max_distance = 20000, // Max distance that a safehome is from the arming point
+ .pos_failure_timeout = SETTING_NAV_POSITION_TIMEOUT_DEFAULT, // 5 sec
+ .waypoint_radius = SETTING_NAV_WP_RADIUS_DEFAULT, // 2m diameter
+ .waypoint_safe_distance = SETTING_NAV_WP_SAFE_DISTANCE_DEFAULT, // centimeters - first waypoint should be closer than this
+ .max_auto_speed = SETTING_NAV_AUTO_SPEED_DEFAULT, // 3 m/s = 10.8 km/h
+ .max_auto_climb_rate = SETTING_NAV_AUTO_CLIMB_RATE_DEFAULT, // 5 m/s
+ .max_manual_speed = SETTING_NAV_MANUAL_SPEED_DEFAULT,
+ .max_manual_climb_rate = SETTING_NAV_MANUAL_CLIMB_RATE_DEFAULT,
+ .land_descent_rate = SETTING_NAV_LANDING_SPEED_DEFAULT, // centimeters/s
+ .land_slowdown_minalt = SETTING_NAV_LAND_SLOWDOWN_MINALT_DEFAULT, // altitude in centimeters
+ .land_slowdown_maxalt = SETTING_NAV_LAND_SLOWDOWN_MAXALT_DEFAULT, // altitude in meters
+ .emerg_descent_rate = SETTING_NAV_EMERG_LANDING_SPEED_DEFAULT, // centimeters/s
+ .min_rth_distance = SETTING_NAV_MIN_RTH_DISTANCE_DEFAULT, // centimeters, if closer than this land immediately
+ .rth_altitude = SETTING_NAV_RTH_ALTITUDE_DEFAULT, // altitude in centimeters
+ .rth_home_altitude = SETTING_NAV_RTH_HOME_ALTITUDE_DEFAULT, // altitude in centimeters
+ .rth_abort_threshold = SETTING_NAV_RTH_ABORT_THRESHOLD_DEFAULT, // centimeters - 500m should be safe for all aircraft
+ .max_terrain_follow_altitude = SETTING_NAV_MAX_TERRAIN_FOLLOW_ALT_DEFAULT, // max altitude in centimeters in terrain following mode
+ .safehome_max_distance = SETTING_SAFEHOME_MAX_DISTANCE_DEFAULT, // Max distance that a safehome is from the arming point
},
// MC-specific
.mc = {
- .max_bank_angle = 30, // degrees
- .hover_throttle = 1500,
- .auto_disarm_delay = 2000, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed
- .braking_speed_threshold = 100, // Braking can become active above 1m/s
- .braking_disengage_speed = 75, // Stop when speed goes below 0.75m/s
- .braking_timeout = 2000, // Timeout barking after 2s
- .braking_boost_factor = 100, // A 100% boost by default
- .braking_boost_timeout = 750, // Timout boost after 750ms
- .braking_boost_speed_threshold = 150, // Boost can happen only above 1.5m/s
- .braking_boost_disengage_speed = 100, // Disable boost at 1m/s
- .braking_bank_angle = 40, // Max braking angle
- .posDecelerationTime = 120, // posDecelerationTime * 100
- .posResponseExpo = 10, // posResponseExpo * 100
- .slowDownForTurning = true,
+ .max_bank_angle = SETTING_NAV_MC_BANK_ANGLE_DEFAULT, // degrees
+ .hover_throttle = SETTING_NAV_MC_HOVER_THR_DEFAULT,
+ .auto_disarm_delay = SETTING_NAV_MC_AUTO_DISARM_DELAY_DEFAULT, // milliseconds - time before disarming when auto disarm is enabled and landing is confirmed
+
+#ifdef USE_MR_BRAKING_MODE
+ .braking_speed_threshold = SETTING_NAV_MC_BRAKING_SPEED_THRESHOLD_DEFAULT, // Braking can become active above 1m/s
+ .braking_disengage_speed = SETTING_NAV_MC_BRAKING_DISENGAGE_SPEED_DEFAULT, // Stop when speed goes below 0.75m/s
+ .braking_timeout = SETTING_NAV_MC_BRAKING_TIMEOUT_DEFAULT, // Timeout barking after 2s
+ .braking_boost_factor = SETTING_NAV_MC_BRAKING_BOOST_FACTOR_DEFAULT, // A 100% boost by default
+ .braking_boost_timeout = SETTING_NAV_MC_BRAKING_BOOST_TIMEOUT_DEFAULT, // Timout boost after 750ms
+ .braking_boost_speed_threshold = SETTING_NAV_MC_BRAKING_BOOST_SPEED_THRESHOLD_DEFAULT, // Boost can happen only above 1.5m/s
+ .braking_boost_disengage_speed = SETTING_NAV_MC_BRAKING_BOOST_DISENGAGE_SPEED_DEFAULT, // Disable boost at 1m/s
+ .braking_bank_angle = SETTING_NAV_MC_BRAKING_BANK_ANGLE_DEFAULT, // Max braking angle
+#endif
+
+ .posDecelerationTime = SETTING_NAV_MC_POS_DECELERATION_TIME_DEFAULT, // posDecelerationTime * 100
+ .posResponseExpo = SETTING_NAV_MC_POS_EXPO_DEFAULT, // posResponseExpo * 100
+ .slowDownForTurning = SETTING_NAV_MC_WP_SLOWDOWN_DEFAULT,
},
// Fixed wing
.fw = {
- .max_bank_angle = 35, // degrees
- .max_climb_angle = 20, // degrees
- .max_dive_angle = 15, // degrees
- .cruise_throttle = 1400,
- .cruise_speed = 0, // cm/s
- .control_smoothness = 0,
- .max_throttle = 1700,
- .min_throttle = 1200,
- .pitch_to_throttle = 10, // pwm units per degree of pitch (10pwm units ~ 1% throttle)
- .pitch_to_throttle_smooth = 6,
- .pitch_to_throttle_thresh = 50,
- .loiter_radius = 7500, // 75m
+ .max_bank_angle = SETTING_NAV_FW_BANK_ANGLE_DEFAULT, // degrees
+ .max_climb_angle = SETTING_NAV_FW_CLIMB_ANGLE_DEFAULT, // degrees
+ .max_dive_angle = SETTING_NAV_FW_DIVE_ANGLE_DEFAULT, // degrees
+ .cruise_throttle = SETTING_NAV_FW_CRUISE_THR_DEFAULT,
+ .cruise_speed = SETTING_NAV_FW_CRUISE_SPEED_DEFAULT, // cm/s
+ .control_smoothness = SETTING_NAV_FW_CONTROL_SMOOTHNESS_DEFAULT,
+ .max_throttle = SETTING_NAV_FW_MAX_THR_DEFAULT,
+ .min_throttle = SETTING_NAV_FW_MIN_THR_DEFAULT,
+ .pitch_to_throttle = SETTING_NAV_FW_PITCH2THR_DEFAULT, // pwm units per degree of pitch (10pwm units ~ 1% throttle)
+ .pitch_to_throttle_smooth = SETTING_NAV_FW_PITCH2THR_SMOOTHING_DEFAULT,
+ .pitch_to_throttle_thresh = SETTING_NAV_FW_PITCH2THR_THRESHOLD_DEFAULT,
+ .loiter_radius = SETTING_NAV_FW_LOITER_RADIUS_DEFAULT, // 75m
//Fixed wing landing
- .land_dive_angle = 2, // 2 degrees dive by default
+ .land_dive_angle = SETTING_NAV_FW_LAND_DIVE_ANGLE_DEFAULT, // 2 degrees dive by default
// Fixed wing launch
- .launch_velocity_thresh = 300, // 3 m/s
- .launch_accel_thresh = 1.9f * 981, // cm/s/s (1.9*G)
- .launch_time_thresh = 40, // 40ms
- .launch_throttle = 1700,
- .launch_idle_throttle = 1000, // Motor idle or MOTOR_STOP
- .launch_motor_timer = 500, // ms
- .launch_motor_spinup_time = 100, // ms, time to gredually increase throttle from idle to launch
- .launch_end_time = 3000, // ms, time to gradually decrease/increase throttle and decrease pitch angle from launch to the current flight mode
- .launch_min_time = 0, // ms, min time in launch mode
- .launch_timeout = 5000, // ms, timeout for launch procedure
- .launch_max_altitude = 0, // cm, altitude where to consider launch ended
- .launch_climb_angle = 18, // 18 degrees
- .launch_max_angle = 45, // 45 deg
- .cruise_yaw_rate = 20, // 20dps
- .allow_manual_thr_increase = false,
- .useFwNavYawControl = 0,
- .yawControlDeadband = 0,
+ .launch_velocity_thresh = SETTING_NAV_FW_LAUNCH_VELOCITY_DEFAULT, // 3 m/s
+ .launch_accel_thresh = SETTING_NAV_FW_LAUNCH_ACCEL_DEFAULT, // cm/s/s (1.9*G)
+ .launch_time_thresh = SETTING_NAV_FW_LAUNCH_DETECT_TIME_DEFAULT, // 40ms
+ .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_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
+ .launch_timeout = SETTING_NAV_FW_LAUNCH_TIMEOUT_DEFAULT, // ms, timeout for launch procedure
+ .launch_max_altitude = SETTING_NAV_FW_LAUNCH_MAX_ALTITUDE_DEFAULT, // cm, altitude where to consider launch ended
+ .launch_climb_angle = SETTING_NAV_FW_LAUNCH_CLIMB_ANGLE_DEFAULT, // 18 degrees
+ .launch_max_angle = SETTING_NAV_FW_LAUNCH_MAX_ANGLE_DEFAULT, // 45 deg
+ .cruise_yaw_rate = SETTING_NAV_FW_CRUISE_YAW_RATE_DEFAULT, // 20dps
+ .allow_manual_thr_increase = SETTING_NAV_FW_ALLOW_MANUAL_THR_INCREASE_DEFAULT,
+ .useFwNavYawControl = SETTING_NAV_USE_FW_YAW_CONTROL_DEFAULT,
+ .yawControlDeadband = SETTING_NAV_FW_YAW_DEADBAND_DEFAULT,
}
);
@@ -3432,7 +3437,10 @@ void navigationUsePIDs(void)
multicopterPosXyCoefficients.dTermAttenuation = pidProfile()->navVelXyDtermAttenuation / 100.0f;
multicopterPosXyCoefficients.dTermAttenuationStart = pidProfile()->navVelXyDtermAttenuationStart / 100.0f;
multicopterPosXyCoefficients.dTermAttenuationEnd = pidProfile()->navVelXyDtermAttenuationEnd / 100.0f;
+
+#ifdef USE_MR_BRAKING_MODE
multicopterPosXyCoefficients.breakingBoostFactor = (float) navConfig()->mc.braking_boost_factor / 100.0f;
+#endif
// Initialize altitude hold PID-controllers (pos_z, vel_z, acc_z
navPidInit(
diff --git a/src/main/navigation/navigation.h b/src/main/navigation/navigation.h
index 1bd5e858fb..9fd15582dd 100755
--- a/src/main/navigation/navigation.h
+++ b/src/main/navigation/navigation.h
@@ -209,6 +209,8 @@ typedef struct navConfig_s {
uint8_t max_bank_angle; // multicopter max banking angle (deg)
uint16_t hover_throttle; // multicopter hover throttle
uint16_t auto_disarm_delay; // multicopter safety delay for landing detector
+
+#ifdef USE_MR_BRAKING_MODE
uint16_t braking_speed_threshold; // above this speed braking routine might kick in
uint16_t braking_disengage_speed; // below this speed braking will be disengaged
uint16_t braking_timeout; // Timeout for braking mode
@@ -217,6 +219,8 @@ typedef struct navConfig_s {
uint16_t braking_boost_speed_threshold; // Above this speed braking boost mode can engage
uint16_t braking_boost_disengage_speed; // Below this speed braking boost will disengage
uint8_t braking_bank_angle; // Max angle [deg] that MR is allowed duing braking boost phase
+#endif
+
uint8_t posDecelerationTime; // Brake time parameter
uint8_t posResponseExpo; // Position controller expo (taret vel expo for MC)
bool slowDownForTurning; // Slow down during WP missions when changing heading on next waypoint
diff --git a/src/main/navigation/navigation_pos_estimator.c b/src/main/navigation/navigation_pos_estimator.c
index 496aeb6c1f..f62de049ce 100755
--- a/src/main/navigation/navigation_pos_estimator.c
+++ b/src/main/navigation/navigation_pos_estimator.c
@@ -37,6 +37,7 @@
#include "drivers/time.h"
#include "fc/config.h"
+#include "fc/settings.h"
#include "flight/imu.h"
#include "flight/secondary_imu.h"
@@ -59,39 +60,39 @@ PG_REGISTER_WITH_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationCo
PG_RESET_TEMPLATE(positionEstimationConfig_t, positionEstimationConfig,
// Inertial position estimator parameters
- .automatic_mag_declination = 1,
- .reset_altitude_type = NAV_RESET_ON_FIRST_ARM,
- .reset_home_type = NAV_RESET_ON_FIRST_ARM,
- .gravity_calibration_tolerance = 5, // 5 cm/s/s calibration error accepted (0.5% of gravity)
- .use_gps_velned = 1, // "Disabled" is mandatory with gps_dyn_model = Pedestrian
- .use_gps_no_baro = 0, // Use GPS altitude if no baro is available on all aircrafts
- .allow_dead_reckoning = 0,
+ .automatic_mag_declination = SETTING_INAV_AUTO_MAG_DECL_DEFAULT,
+ .reset_altitude_type = SETTING_INAV_RESET_ALTITUDE_DEFAULT,
+ .reset_home_type = SETTING_INAV_RESET_HOME_DEFAULT,
+ .gravity_calibration_tolerance = SETTING_INAV_GRAVITY_CAL_TOLERANCE_DEFAULT, // 5 cm/s/s calibration error accepted (0.5% of gravity)
+ .use_gps_velned = SETTING_INAV_USE_GPS_VELNED_DEFAULT, // "Disabled" is mandatory with gps_dyn_model = Pedestrian
+ .use_gps_no_baro = SETTING_INAV_USE_GPS_NO_BARO_DEFAULT, // Use GPS altitude if no baro is available on all aircrafts
+ .allow_dead_reckoning = SETTING_INAV_ALLOW_DEAD_RECKONING_DEFAULT,
- .max_surface_altitude = 200,
+ .max_surface_altitude = SETTING_INAV_MAX_SURFACE_ALTITUDE_DEFAULT,
- .w_xyz_acc_p = 1.0f,
+ .w_xyz_acc_p = SETTING_INAV_W_XYZ_ACC_P_DEFAULT,
- .w_z_baro_p = 0.35f,
+ .w_z_baro_p = SETTING_INAV_W_Z_BARO_P_DEFAULT,
- .w_z_surface_p = 3.500f,
- .w_z_surface_v = 6.100f,
+ .w_z_surface_p = SETTING_INAV_W_Z_SURFACE_P_DEFAULT,
+ .w_z_surface_v = SETTING_INAV_W_Z_SURFACE_V_DEFAULT,
- .w_z_gps_p = 0.2f,
- .w_z_gps_v = 0.1f,
+ .w_z_gps_p = SETTING_INAV_W_Z_GPS_P_DEFAULT,
+ .w_z_gps_v = SETTING_INAV_W_Z_GPS_V_DEFAULT,
- .w_xy_gps_p = 1.0f,
- .w_xy_gps_v = 2.0f,
+ .w_xy_gps_p = SETTING_INAV_W_XY_GPS_P_DEFAULT,
+ .w_xy_gps_v = SETTING_INAV_W_XY_GPS_V_DEFAULT,
- .w_xy_flow_p = 1.0f,
- .w_xy_flow_v = 2.0f,
+ .w_xy_flow_p = SETTING_INAV_W_XY_FLOW_P_DEFAULT,
+ .w_xy_flow_v = SETTING_INAV_W_XY_FLOW_V_DEFAULT,
- .w_z_res_v = 0.5f,
- .w_xy_res_v = 0.5f,
+ .w_z_res_v = SETTING_INAV_W_Z_RES_V_DEFAULT,
+ .w_xy_res_v = SETTING_INAV_W_XY_RES_V_DEFAULT,
- .w_acc_bias = 0.01f,
+ .w_acc_bias = SETTING_INAV_W_ACC_BIAS_DEFAULT,
- .max_eph_epv = 1000.0f,
- .baro_epv = 100.0f
+ .max_eph_epv = SETTING_INAV_MAX_EPH_EPV_DEFAULT,
+ .baro_epv = SETTING_INAV_BARO_EPV_DEFAULT
);
#define resetTimer(tim, currentTimeUs) { (tim)->deltaTime = 0; (tim)->lastTriggeredTime = currentTimeUs; }
diff --git a/src/main/rx/eleres.c b/src/main/rx/eleres.c
index 638818c531..705c4b7e15 100755
--- a/src/main/rx/eleres.c
+++ b/src/main/rx/eleres.c
@@ -72,12 +72,12 @@
PG_REGISTER_WITH_RESET_TEMPLATE(eleresConfig_t, eleresConfig, PG_ELERES_CONFIG, 0);
PG_RESET_TEMPLATE(eleresConfig_t, eleresConfig,
- .eleresFreq = 435,
- .eleresTelemetryEn = 0,
- .eleresTelemetryPower = 7,
- .eleresLocEn = 0,
- .eleresLocPower = 7,
- .eleresLocDelay = 240
+ .eleresFreq = SETTING_ELERES_FREQ_DEFAULT,
+ .eleresTelemetryEn = SETTING_ELERES_TELEMETRY_EN_DEFAULT,
+ .eleresTelemetryPower = SETTING_ELERES_TELEMETRY_POWER_DEFAULT,
+ .eleresLocEn = SETTING_ELERES_LOC_EN_DEFAULT,
+ .eleresLocPower = SETTING_ELERES_LOC_POWER_DEFAULT,
+ .eleresLocDelay = SETTING_ELERES_LOC_DELAY_DEFAULT
);
static uint8_t hoppingChannel = 1;
@@ -784,8 +784,6 @@ void eleresInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
channelHopping(1);
rfMode = RECEIVE;
localizerTime = millis() + (1000L * eleresConfig()->eleresLocDelay);
-
- return true;
}
uint8_t eleresBind(void)
diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c
index f028e73330..c8e1184594 100755
--- a/src/main/rx/rx.c
+++ b/src/main/rx/rx.c
@@ -45,6 +45,7 @@
#include "fc/config.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
+#include "fc/settings.h"
#include "flight/failsafe.h"
@@ -125,26 +126,32 @@ PG_REGISTER_WITH_RESET_TEMPLATE(rxConfig_t, rxConfig, PG_RX_CONFIG, 9);
PG_RESET_TEMPLATE(rxConfig_t, rxConfig,
.receiverType = DEFAULT_RX_TYPE,
.rcmap = {0, 1, 3, 2}, // Default to AETR map
- .halfDuplex = TRISTATE_AUTO,
+ .halfDuplex = SETTING_SERIALRX_HALFDUPLEX_DEFAULT,
.serialrx_provider = SERIALRX_PROVIDER,
+#ifdef USE_RX_SPI
.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL,
- .spektrum_sat_bind = 0,
- .serialrx_inverted = 0,
- .mincheck = 1100,
- .maxcheck = 1900,
- .rx_min_usec = RX_MIN_USEX, // any of first 4 channels below this value will trigger rx loss detection
- .rx_max_usec = 2115, // any of first 4 channels above this value will trigger rx loss detection
- .rssi_channel = 0,
- .rssiMin = RSSI_VISIBLE_VALUE_MIN,
- .rssiMax = RSSI_VISIBLE_VALUE_MAX,
- .sbusSyncInterval = SBUS_DEFAULT_INTERFRAME_DELAY_US,
- .rcFilterFrequency = 50,
-#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
- .mspOverrideChannels = 15,
#endif
- .rssi_source = RSSI_SOURCE_AUTO,
- .srxl2_unit_id = 1,
- .srxl2_baud_fast = 1,
+#ifdef USE_SPEKTRUM_BIND
+ .spektrum_sat_bind = SETTING_SPEKTRUM_SAT_BIND_DEFAULT,
+#endif
+ .serialrx_inverted = SETTING_SERIALRX_INVERTED_DEFAULT,
+ .mincheck = SETTING_MIN_CHECK_DEFAULT,
+ .maxcheck = SETTING_MAX_CHECK_DEFAULT,
+ .rx_min_usec = SETTING_RX_MIN_USEC_DEFAULT, // any of first 4 channels below this value will trigger rx loss detection
+ .rx_max_usec = SETTING_RX_MAX_USEC_DEFAULT, // any of first 4 channels above this value will trigger rx loss detection
+ .rssi_channel = SETTING_RSSI_CHANNEL_DEFAULT,
+ .rssiMin = SETTING_RSSI_MIN_DEFAULT,
+ .rssiMax = SETTING_RSSI_MAX_DEFAULT,
+ .sbusSyncInterval = SETTING_SBUS_SYNC_INTERVAL_DEFAULT,
+ .rcFilterFrequency = SETTING_RC_FILTER_FREQUENCY_DEFAULT,
+#if defined(USE_RX_MSP) && defined(USE_MSP_RC_OVERRIDE)
+ .mspOverrideChannels = SETTING_MSP_OVERRIDE_CHANNELS_DEFAULT,
+#endif
+ .rssi_source = SETTING_RSSI_SOURCE_DEFAULT,
+#ifdef USE_SERIALRX_SRXL2
+ .srxl2_unit_id = SETTING_SRXL2_UNIT_ID_DEFAULT,
+ .srxl2_baud_fast = SETTING_SRXL2_BAUD_FAST_DEFAULT,
+#endif
);
void resetAllRxChannelRangeConfigurations(void)
diff --git a/src/main/rx/rx.h b/src/main/rx/rx.h
index 0aee1e8353..dcc1804f5d 100644
--- a/src/main/rx/rx.h
+++ b/src/main/rx/rx.h
@@ -114,11 +114,15 @@ typedef struct rxConfig_s {
uint8_t serialrx_provider; // Type of UART-based receiver (rxSerialReceiverType_e enum). Only used if receiverType is RX_TYPE_SERIAL
uint8_t serialrx_inverted; // Flip the default inversion of the protocol - e.g. sbus (Futaba, FrSKY) is inverted if this is false, uninverted if it's true. Support for uninverted OpenLRS (and modified FrSKY) receivers.
uint8_t halfDuplex; // allow rx to operate in half duplex mode. From tristate_e.
+#ifdef USE_RX_SPI
uint8_t rx_spi_protocol; // type of SPI receiver protocol (rx_spi_protocol_e enum). Only used if receiverType is RX_TYPE_SPI
uint32_t rx_spi_id;
uint8_t rx_spi_rf_channel_count;
+#endif
+#ifdef USE_SPEKTRUM_BIND
uint8_t spektrum_sat_bind; // number of bind pulses for Spektrum satellite receivers
uint8_t spektrum_sat_bind_autoreset; // whenever we will reset (exit) binding mode after hard reboot
+#endif
uint8_t rssi_channel;
uint8_t rssiMin; // minimum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
uint8_t rssiMax; // maximum RSSI sent by the RX - [RSSI_VISIBLE_VALUE_MIN, RSSI_VISIBLE_VALUE_MAX]
@@ -130,8 +134,10 @@ typedef struct rxConfig_s {
uint8_t rcFilterFrequency; // RC filter cutoff frequency (smoothness vs response sharpness)
uint16_t mspOverrideChannels; // Channels to override with MSP RC when BOXMSPRCOVERRIDE is active
uint8_t rssi_source;
+#ifdef USE_SERIALRX_SRXL2
uint8_t srxl2_unit_id;
uint8_t srxl2_baud_fast;
+#endif
} rxConfig_t;
PG_DECLARE(rxConfig_t, rxConfig);
diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c
index 241f1c417a..aeb6af2965 100644
--- a/src/main/sensors/acceleration.c
+++ b/src/main/sensors/acceleration.c
@@ -58,6 +58,7 @@ FILE_COMPILE_FOR_SPEED
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "io/beeper.h"
@@ -93,22 +94,22 @@ PG_REGISTER_WITH_RESET_FN(accelerometerConfig_t, accelerometerConfig, PG_ACCELER
void pgResetFn_accelerometerConfig(accelerometerConfig_t *instance)
{
RESET_CONFIG_2(accelerometerConfig_t, instance,
- .acc_align = ALIGN_DEFAULT,
- .acc_hardware = ACC_AUTODETECT,
- .acc_lpf_hz = 15,
- .acc_notch_hz = 0,
- .acc_notch_cutoff = 1,
- .acc_soft_lpf_type = FILTER_BIQUAD
+ .acc_align = SETTING_ALIGN_ACC_DEFAULT,
+ .acc_hardware = SETTING_ACC_HARDWARE_DEFAULT,
+ .acc_lpf_hz = SETTING_ACC_LPF_HZ_DEFAULT,
+ .acc_notch_hz = SETTING_ACC_NOTCH_HZ_DEFAULT,
+ .acc_notch_cutoff = SETTING_ACC_NOTCH_CUTOFF_DEFAULT,
+ .acc_soft_lpf_type = SETTING_ACC_LPF_TYPE_DEFAULT
);
RESET_CONFIG_2(flightDynamicsTrims_t, &instance->accZero,
- .raw[X] = 0,
- .raw[Y] = 0,
- .raw[Z] = 0
+ .raw[X] = SETTING_ACCZERO_X_DEFAULT,
+ .raw[Y] = SETTING_ACCZERO_Y_DEFAULT,
+ .raw[Z] = SETTING_ACCZERO_Z_DEFAULT
);
RESET_CONFIG_2(flightDynamicsTrims_t, &instance->accGain,
- .raw[X] = 4096,
- .raw[Y] = 4096,
- .raw[Z] = 4096
+ .raw[X] = SETTING_ACCGAIN_X_DEFAULT,
+ .raw[Y] = SETTING_ACCGAIN_Y_DEFAULT,
+ .raw[Z] = SETTING_ACCGAIN_Z_DEFAULT
);
}
diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c
index bb1325aeeb..63532a3986 100644
--- a/src/main/sensors/barometer.c
+++ b/src/main/sensors/barometer.c
@@ -44,6 +44,7 @@
#include "drivers/time.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "sensors/barometer.h"
#include "sensors/sensors.h"
@@ -56,21 +57,16 @@
baro_t baro; // barometer access functions
+#ifdef USE_BARO
+
PG_REGISTER_WITH_RESET_TEMPLATE(barometerConfig_t, barometerConfig, PG_BAROMETER_CONFIG, 3);
-#ifdef USE_BARO
-#define BARO_HARDWARE_DEFAULT BARO_AUTODETECT
-#else
-#define BARO_HARDWARE_DEFAULT BARO_NONE
-#endif
PG_RESET_TEMPLATE(barometerConfig_t, barometerConfig,
- .baro_hardware = BARO_HARDWARE_DEFAULT,
- .use_median_filtering = 1,
- .baro_calibration_tolerance = 150
+ .baro_hardware = SETTING_BARO_HARDWARE_DEFAULT,
+ .use_median_filtering = SETTING_BARO_MEDIAN_FILTER_DEFAULT,
+ .baro_calibration_tolerance = SETTING_BARO_CAL_TOLERANCE_DEFAULT
);
-#ifdef USE_BARO
-
static zeroCalibrationScalar_t zeroCalibration;
static float baroGroundAltitude = 0;
static float baroGroundPressure = 101325.0f; // 101325 pascal, 1 standard atmosphere
diff --git a/src/main/sensors/barometer.h b/src/main/sensors/barometer.h
index 2e365fb115..3c04c86e46 100644
--- a/src/main/sensors/barometer.h
+++ b/src/main/sensors/barometer.h
@@ -37,14 +37,6 @@ typedef enum {
BARO_MAX = BARO_FAKE
} baroSensor_e;
-typedef struct barometerConfig_s {
- uint8_t baro_hardware; // Barometer hardware to use
- uint8_t use_median_filtering; // Use 3-point median filtering
- uint16_t baro_calibration_tolerance; // Baro calibration tolerance (cm at sea level)
-} barometerConfig_t;
-
-PG_DECLARE(barometerConfig_t, barometerConfig);
-
typedef struct baro_s {
baroDev_t dev;
int32_t BaroAlt;
@@ -54,6 +46,17 @@ typedef struct baro_s {
extern baro_t baro;
+#ifdef USE_BARO
+
+typedef struct barometerConfig_s {
+ uint8_t baro_hardware; // Barometer hardware to use
+ uint8_t use_median_filtering; // Use 3-point median filtering
+ uint16_t baro_calibration_tolerance; // Baro calibration tolerance (cm at sea level)
+} barometerConfig_t;
+
+PG_DECLARE(barometerConfig_t, barometerConfig);
+
+
bool baroInit(void);
bool baroIsCalibrationComplete(void);
void baroStartCalibration(void);
@@ -62,3 +65,5 @@ int32_t baroCalculateAltitude(void);
int32_t baroGetLatestAltitude(void);
int16_t baroGetTemperature(void);
bool baroIsHealthy(void);
+
+#endif
diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c
index 420a9790e9..1b62c01e9a 100644
--- a/src/main/sensors/battery.c
+++ b/src/main/sensors/battery.c
@@ -39,6 +39,7 @@
#include "fc/fc_core.h"
#include "fc/runtime_config.h"
#include "fc/stats.h"
+#include "fc/settings.h"
#include "flight/imu.h"
#include "flight/mixer.h"
@@ -97,20 +98,22 @@ void pgResetFn_batteryProfiles(batteryProfile_t *instance)
{
for (int i = 0; i < MAX_BATTERY_PROFILE_COUNT; i++) {
RESET_CONFIG(batteryProfile_t, &instance[i],
- .cells = 0,
+#ifdef USE_ADC
+ .cells = SETTING_BAT_CELLS_DEFAULT,
.voltage = {
- .cellDetect = 425,
- .cellMax = 420,
- .cellMin = 330,
- .cellWarning = 350
+ .cellDetect = SETTING_VBAT_CELL_DETECT_VOLTAGE_DEFAULT,
+ .cellMax = SETTING_VBAT_MAX_CELL_VOLTAGE_DEFAULT,
+ .cellMin = SETTING_VBAT_MIN_CELL_VOLTAGE_DEFAULT,
+ .cellWarning = SETTING_VBAT_WARNING_CELL_VOLTAGE_DEFAULT
},
+#endif
.capacity = {
- .value = 0,
- .warning = 0,
- .critical = 0,
- .unit = BAT_CAPACITY_UNIT_MAH,
+ .value = SETTING_BATTERY_CAPACITY_DEFAULT,
+ .warning = SETTING_BATTERY_CAPACITY_WARNING_DEFAULT,
+ .critical = SETTING_BATTERY_CAPACITY_CRITICAL_DEFAULT,
+ .unit = SETTING_BATTERY_CAPACITY_UNIT_DEFAULT,
}
);
}
@@ -120,24 +123,26 @@ PG_REGISTER_WITH_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig, PG_B
PG_RESET_TEMPLATE(batteryMetersConfig_t, batteryMetersConfig,
+#ifdef USE_ADC
.voltage = {
- .type = VOLTAGE_SENSOR_ADC,
+ .type = SETTING_VBAT_METER_TYPE_DEFAULT,
.scale = VBAT_SCALE_DEFAULT,
},
+#endif
.current = {
- .type = CURRENT_SENSOR_ADC,
+ .type = SETTING_CURRENT_METER_TYPE_DEFAULT,
.scale = CURRENT_METER_SCALE,
.offset = CURRENT_METER_OFFSET
},
- .voltageSource = BAT_VOLTAGE_RAW,
+ .voltageSource = SETTING_BAT_VOLTAGE_SRC_DEFAULT,
- .cruise_power = 0,
- .idle_power = 0,
- .rth_energy_margin = 5,
+ .cruise_power = SETTING_CRUISE_POWER_DEFAULT,
+ .idle_power = SETTING_IDLE_POWER_DEFAULT,
+ .rth_energy_margin = SETTING_RTH_ENERGY_MARGIN_DEFAULT,
- .throttle_compensation_weight = 1.0f
+ .throttle_compensation_weight = SETTING_THR_COMP_WEIGHT_DEFAULT
);
@@ -150,6 +155,7 @@ void batteryInit(void)
batteryCriticalVoltage = 0;
}
+#ifdef USE_ADC
// profileDetect() profile sorting compare function
static int profile_compare(profile_comp_t *a, profile_comp_t *b) {
if (a->max_voltage < b->max_voltage)
@@ -182,6 +188,7 @@ static int8_t profileDetect(void) {
// No matching profile found
return -1;
}
+#endif
void setBatteryProfile(uint8_t profileIndex)
{
@@ -202,6 +209,7 @@ void activateBatteryProfile(void)
}
}
+#ifdef USE_ADC
static void updateBatteryVoltage(timeUs_t timeDelta, bool justConnected)
{
static pt1Filter_t vbatFilterState;
@@ -342,6 +350,7 @@ void batteryUpdate(timeUs_t timeDelta)
}
}
}
+#endif
batteryState_e getBatteryState(void)
{
diff --git a/src/main/sensors/battery.h b/src/main/sensors/battery.h
index 353f537d01..94201fb28c 100644
--- a/src/main/sensors/battery.h
+++ b/src/main/sensors/battery.h
@@ -69,10 +69,12 @@ typedef enum {
typedef struct batteryMetersConfig_s {
+#ifdef USE_ADC
struct {
uint16_t scale;
voltageSensor_e type;
} voltage;
+#endif
struct {
int16_t scale; // scale the current sensor output voltage to milliamps. Value in 1/10th mV/A
@@ -92,6 +94,7 @@ typedef struct batteryMetersConfig_s {
typedef struct batteryProfile_s {
+#ifdef USE_ADC
uint8_t cells;
struct {
@@ -100,6 +103,7 @@ typedef struct batteryProfile_s {
uint16_t cellMin; // minimum voltage per cell, this triggers battery critical alarm, in 0.01V units, default is 330 (3.3V)
uint16_t cellWarning; // warning voltage per cell, this triggers battery warning alarm, in 0.01V units, default is 350 (3.5V)
} voltage;
+#endif
struct {
uint32_t value; // mAh or mWh (see capacity.unit)
@@ -151,10 +155,13 @@ int32_t getPower(void);
int32_t getMAhDrawn(void);
int32_t getMWhDrawn(void);
+#ifdef USE_ADC
void batteryUpdate(timeUs_t timeDelta);
-void currentMeterUpdate(timeUs_t timeDelta);
void sagCompensatedVBatUpdate(timeUs_t currentTime, timeUs_t timeDelta);
void powerMeterUpdate(timeUs_t timeDelta);
+#endif
+
+void currentMeterUpdate(timeUs_t timeDelta);
uint8_t calculateBatteryPercentage(void);
float calculateThrottleCompensationFactor(void);
diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c
index 287d3d1da4..8e1da170b9 100644
--- a/src/main/sensors/compass.c
+++ b/src/main/sensors/compass.c
@@ -48,6 +48,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "io/gps.h"
#include "io/beeper.h"
@@ -59,27 +60,24 @@
mag_t mag; // mag access functions
+#ifdef USE_MAG
+
PG_REGISTER_WITH_RESET_TEMPLATE(compassConfig_t, compassConfig, PG_COMPASS_CONFIG, 4);
-#ifdef USE_MAG
-#define MAG_HARDWARE_DEFAULT MAG_AUTODETECT
-#else
-#define MAG_HARDWARE_DEFAULT MAG_NONE
-#endif
PG_RESET_TEMPLATE(compassConfig_t, compassConfig,
- .mag_align = ALIGN_DEFAULT,
- .mag_hardware = MAG_HARDWARE_DEFAULT,
- .mag_declination = 0,
- .mag_to_use = 0,
- .magCalibrationTimeLimit = 30,
- .rollDeciDegrees = 0,
- .pitchDeciDegrees = 0,
- .yawDeciDegrees = 0,
- .magGain = {1024, 1024, 1024},
+ .mag_align = SETTING_ALIGN_MAG_DEFAULT,
+ .mag_hardware = SETTING_MAG_HARDWARE_DEFAULT,
+ .mag_declination = SETTING_MAG_DECLINATION_DEFAULT,
+#ifdef USE_DUAL_MAG
+ .mag_to_use = SETTING_MAG_TO_USE_DEFAULT,
+#endif
+ .magCalibrationTimeLimit = SETTING_MAG_CALIBRATION_TIME_DEFAULT,
+ .rollDeciDegrees = SETTING_ALIGN_MAG_ROLL_DEFAULT,
+ .pitchDeciDegrees = SETTING_ALIGN_MAG_PITCH_DEFAULT,
+ .yawDeciDegrees = SETTING_ALIGN_MAG_YAW_DEFAULT,
+ .magGain = {SETTING_MAGGAIN_X_DEFAULT, SETTING_MAGGAIN_Y_DEFAULT, SETTING_MAGGAIN_Z_DEFAULT},
);
-#ifdef USE_MAG
-
static uint8_t magUpdatedAtLeastOnce = 0;
bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse)
diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h
index 1695311bd2..baba7bf6a1 100644
--- a/src/main/sensors/compass.h
+++ b/src/main/sensors/compass.h
@@ -26,7 +26,6 @@
#include "sensors/sensors.h"
-
// Type of magnetometer used/detected
typedef enum {
MAG_NONE = 0,
@@ -54,6 +53,8 @@ typedef struct mag_s {
extern mag_t mag;
+#ifdef USE_MAG
+
typedef struct compassConfig_s {
int16_t mag_declination; // Get your magnetic declination from here : http://magnetic-declination.com/
// For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
@@ -61,7 +62,9 @@ typedef struct compassConfig_s {
uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
flightDynamicsTrims_t magZero;
int16_t magGain[XYZ_AXIS_COUNT];
+#ifdef USE_DUAL_MAG
uint8_t mag_to_use;
+#endif
uint8_t magCalibrationTimeLimit; // Time for compass calibration (seconds)
int16_t rollDeciDegrees; // Alignment for external mag on the roll (X) axis (0.1deg)
int16_t pitchDeciDegrees; // Alignment for external mag on the pitch (Y) axis (0.1deg)
@@ -75,3 +78,5 @@ bool compassInit(void);
void compassUpdate(timeUs_t currentTimeUs);
bool compassIsReady(void);
bool compassIsHealthy(void);
+
+#endif
diff --git a/src/main/sensors/esc_sensor.c b/src/main/sensors/esc_sensor.c
index bd6e9886ec..672428b615 100644
--- a/src/main/sensors/esc_sensor.c
+++ b/src/main/sensors/esc_sensor.c
@@ -46,6 +46,7 @@
#include "io/serial.h"
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#if defined(USE_ESC_SENSOR)
@@ -80,7 +81,7 @@ static bool escSensorDataNeedsUpdate;
PG_REGISTER_WITH_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig, PG_ESC_SENSOR_CONFIG, 1);
PG_RESET_TEMPLATE(escSensorConfig_t, escSensorConfig,
.currentOffset = 0, // UNUSED
- .listenOnly = 0,
+ .listenOnly = SETTING_ESC_SENSOR_LISTEN_ONLY_DEFAULT,
);
static int getTelemetryMotorCount(void)
diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c
index 0f72aa9f7b..6a8710bff2 100644
--- a/src/main/sensors/gyro.c
+++ b/src/main/sensors/gyro.c
@@ -61,6 +61,7 @@ FILE_COMPILE_FOR_SPEED
#include "fc/config.h"
#include "fc/runtime_config.h"
#include "fc/rc_controls.h"
+#include "fc/settings.h"
#include "io/beeper.h"
#include "io/statusindicator.h"
@@ -106,26 +107,30 @@ EXTENDED_FASTRAM dynamicGyroNotchState_t dynamicGyroNotchState;
PG_REGISTER_WITH_RESET_TEMPLATE(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 11);
PG_RESET_TEMPLATE(gyroConfig_t, gyroConfig,
- .gyro_lpf = GYRO_LPF_256HZ,
- .gyro_soft_lpf_hz = 60,
- .gyro_soft_lpf_type = FILTER_BIQUAD,
- .gyro_align = ALIGN_DEFAULT,
- .gyroMovementCalibrationThreshold = 32,
- .looptime = 1000,
- .gyroSync = 1,
- .gyro_to_use = 0,
- .gyro_notch_hz = 0,
- .gyro_notch_cutoff = 1,
- .gyro_stage2_lowpass_hz = 0,
- .gyro_stage2_lowpass_type = FILTER_BIQUAD,
- .useDynamicLpf = 0,
- .gyroDynamicLpfMinHz = 200,
- .gyroDynamicLpfMaxHz = 500,
- .gyroDynamicLpfCurveExpo = 5,
- .dynamicGyroNotchRange = DYN_NOTCH_RANGE_MEDIUM,
- .dynamicGyroNotchQ = 120,
- .dynamicGyroNotchMinHz = 150,
- .dynamicGyroNotchEnabled = 0,
+ .gyro_lpf = SETTING_GYRO_HARDWARE_LPF_DEFAULT,
+ .gyro_soft_lpf_hz = SETTING_GYRO_LPF_HZ_DEFAULT,
+ .gyro_soft_lpf_type = SETTING_GYRO_LPF_TYPE_DEFAULT,
+ .gyro_align = SETTING_ALIGN_GYRO_DEFAULT,
+ .gyroMovementCalibrationThreshold = SETTING_MORON_THRESHOLD_DEFAULT,
+ .looptime = SETTING_LOOPTIME_DEFAULT,
+ .gyroSync = SETTING_GYRO_SYNC_DEFAULT,
+#ifdef USE_DUAL_GYRO
+ .gyro_to_use = SETTING_GYRO_TO_USE_DEFAULT,
+#endif
+ .gyro_notch_hz = SETTING_GYRO_NOTCH_HZ_DEFAULT,
+ .gyro_notch_cutoff = SETTING_GYRO_NOTCH_CUTOFF_DEFAULT,
+ .gyro_stage2_lowpass_hz = SETTING_GYRO_STAGE2_LOWPASS_HZ_DEFAULT,
+ .gyro_stage2_lowpass_type = SETTING_GYRO_STAGE2_LOWPASS_TYPE_DEFAULT,
+ .useDynamicLpf = SETTING_GYRO_USE_DYN_LPF_DEFAULT,
+ .gyroDynamicLpfMinHz = SETTING_GYRO_DYN_LPF_MIN_HZ_DEFAULT,
+ .gyroDynamicLpfMaxHz = SETTING_GYRO_DYN_LPF_MAX_HZ_DEFAULT,
+ .gyroDynamicLpfCurveExpo = SETTING_GYRO_DYN_LPF_CURVE_EXPO_DEFAULT,
+#ifdef USE_DYNAMIC_FILTERS
+ .dynamicGyroNotchRange = SETTING_DYNAMIC_GYRO_NOTCH_RANGE_DEFAULT,
+ .dynamicGyroNotchQ = SETTING_DYNAMIC_GYRO_NOTCH_Q_DEFAULT,
+ .dynamicGyroNotchMinHz = SETTING_DYNAMIC_GYRO_NOTCH_MIN_HZ_DEFAULT,
+ .dynamicGyroNotchEnabled = SETTING_DYNAMIC_GYRO_NOTCH_ENABLED_DEFAULT,
+#endif
);
STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev, gyroSensor_e gyroHardware)
@@ -536,4 +541,4 @@ void gyroUpdateDynamicLpf(float cutoffFreq) {
biquadFilterUpdate(&gyroLpfState[axis].biquad, cutoffFreq, getLooptime(), BIQUAD_Q, FILTER_LPF);
}
}
-}
\ No newline at end of file
+}
diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h
index 95174bb055..6aa3c11414 100644
--- a/src/main/sensors/gyro.h
+++ b/src/main/sensors/gyro.h
@@ -61,12 +61,14 @@ extern gyro_t gyro;
typedef struct gyroConfig_s {
sensor_align_e gyro_align; // gyro alignment
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.
- uint8_t gyroSync; // Enable interrupt based loop
+ bool gyroSync; // Enable interrupt based loop
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_soft_lpf_hz;
uint8_t gyro_soft_lpf_type;
+#ifdef USE_DUAL_GYRO
uint8_t gyro_to_use;
+#endif
uint16_t gyro_notch_hz;
uint16_t gyro_notch_cutoff;
uint16_t gyro_stage2_lowpass_hz;
@@ -75,10 +77,12 @@ typedef struct gyroConfig_s {
uint16_t gyroDynamicLpfMinHz;
uint16_t gyroDynamicLpfMaxHz;
uint8_t gyroDynamicLpfCurveExpo;
+#ifdef USE_DYNAMIC_FILTERS
uint8_t dynamicGyroNotchRange;
uint16_t dynamicGyroNotchQ;
uint16_t dynamicGyroNotchMinHz;
uint8_t dynamicGyroNotchEnabled;
+#endif
} gyroConfig_t;
PG_DECLARE(gyroConfig_t, gyroConfig);
diff --git a/src/main/sensors/opflow.c b/src/main/sensors/opflow.c
index f0f47b556f..9c1b6f265e 100755
--- a/src/main/sensors/opflow.c
+++ b/src/main/sensors/opflow.c
@@ -50,6 +50,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "sensors/boardalignment.h"
#include "sensors/gyro.h"
@@ -78,9 +79,9 @@ static float opflowCalibrationFlowAcc;
PG_REGISTER_WITH_RESET_TEMPLATE(opticalFlowConfig_t, opticalFlowConfig, PG_OPFLOW_CONFIG, 2);
PG_RESET_TEMPLATE(opticalFlowConfig_t, opticalFlowConfig,
- .opflow_hardware = OPFLOW_NONE,
- .opflow_align = CW0_DEG_FLIP,
- .opflow_scale = 10.5f,
+ .opflow_hardware = SETTING_OPFLOW_HARDWARE_DEFAULT,
+ .opflow_align = SETTING_ALIGN_OPFLOW_DEFAULT,
+ .opflow_scale = SETTING_OPFLOW_SCALE_DEFAULT,
);
static bool opflowDetect(opflowDev_t * dev, uint8_t opflowHardwareToUse)
diff --git a/src/main/sensors/pitotmeter.c b/src/main/sensors/pitotmeter.c
index 60fbaed019..a330be79bb 100644
--- a/src/main/sensors/pitotmeter.c
+++ b/src/main/sensors/pitotmeter.c
@@ -38,6 +38,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "scheduler/protothreads.h"
@@ -58,9 +59,9 @@ PG_REGISTER_WITH_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig, PG_PITOTME
#define PITOT_HARDWARE_DEFAULT PITOT_NONE
#endif
PG_RESET_TEMPLATE(pitotmeterConfig_t, pitotmeterConfig,
- .pitot_hardware = PITOT_HARDWARE_DEFAULT,
- .pitot_lpf_milli_hz = 350,
- .pitot_scale = 1.00f
+ .pitot_hardware = SETTING_PITOT_HARDWARE_DEFAULT,
+ .pitot_lpf_milli_hz = SETTING_PITOT_LPF_MILLI_HZ_DEFAULT,
+ .pitot_scale = SETTING_PITOT_SCALE_DEFAULT
);
bool pitotDetect(pitotDev_t *dev, uint8_t pitotHardwareToUse)
diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c
index 5c7f10c353..0129cdfb3b 100644
--- a/src/main/sensors/rangefinder.c
+++ b/src/main/sensors/rangefinder.c
@@ -45,6 +45,7 @@
#include "fc/config.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "sensors/sensors.h"
#include "sensors/rangefinder.h"
@@ -65,8 +66,8 @@ rangefinder_t rangefinder;
PG_REGISTER_WITH_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig, PG_RANGEFINDER_CONFIG, 1);
PG_RESET_TEMPLATE(rangefinderConfig_t, rangefinderConfig,
- .rangefinder_hardware = RANGEFINDER_NONE,
- .use_median_filtering = 0,
+ .rangefinder_hardware = SETTING_RANGEFINDER_HARDWARE_DEFAULT,
+ .use_median_filtering = SETTING_RANGEFINDER_MEDIAN_FILTER_DEFAULT,
);
const rangefinderHardwarePins_t * rangefinderGetHardwarePins(void)
@@ -287,4 +288,3 @@ bool rangefinderIsHealthy(void)
return (millis() - rangefinder.lastValidResponseTimeMs) < RANGEFINDER_HARDWARE_TIMEOUT_MS;
}
#endif
-
diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c
index cc1e81203f..ad553d6aad 100644
--- a/src/main/target/ALIENFLIGHTF3/config.c
+++ b/src/main/target/ALIENFLIGHTF3/config.c
@@ -63,9 +63,6 @@ void targetConfiguration(void)
pidProfileMutable()->bank_mc.pid[PITCH].P = 36;
failsafeConfigMutable()->failsafe_delay = 2;
failsafeConfigMutable()->failsafe_off_delay = 0;
- controlRateProfilesMutable(0)->stabilized.rates[FD_PITCH] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
- controlRateProfilesMutable(0)->stabilized.rates[FD_ROLL] = CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_DEFAULT;
- controlRateProfilesMutable(0)->stabilized.rates[FD_YAW] = CONTROL_RATE_CONFIG_YAW_RATE_DEFAULT;
parseRcChannels("TAER1234");
*primaryMotorMixerMutable(0) = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h
index 2f50dc866e..1c4cc3fe68 100755
--- a/src/main/target/BETAFLIGHTF3/target.h
+++ b/src/main/target/BETAFLIGHTF3/target.h
@@ -110,8 +110,8 @@
//#define SBUS_TELEMETRY_UART SERIAL_PORT_USART1 // XXX
#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_CURRENT_METER | FEATURE_TELEMETRY ) // XXX
-#define USE_SPEKTRUM_BIND
-#define BIND_PIN UART2_RX_PIN
+//#define USE_SPEKTRUM_BIND
+//#define BIND_PIN UART2_RX_PIN
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h
index ad03b71bcb..eae3c8ebdd 100644
--- a/src/main/target/CHEBUZZF3/target.h
+++ b/src/main/target/CHEBUZZF3/target.h
@@ -39,6 +39,7 @@
#define L3GD20_CS_PIN PE3
#define IMU_L3GD20_ALIGN CW270_DEG
+#define IMU_LSM303DLHC_ALIGN CW0_DEG
#define IMU_MPU6050_ALIGN CW0_DEG
#define USE_BARO
diff --git a/src/main/target/KFC32F3_INAV/CMakeLists.txt b/src/main/target/KFC32F3_INAV/CMakeLists.txt
deleted file mode 100644
index 1af4cecc06..0000000000
--- a/src/main/target/KFC32F3_INAV/CMakeLists.txt
+++ /dev/null
@@ -1 +0,0 @@
-target_stm32f303xc(KFC32F3_INAV SKIP_RELEASES)
diff --git a/src/main/target/KFC32F3_INAV/hardware_setup.c b/src/main/target/KFC32F3_INAV/hardware_setup.c
deleted file mode 100755
index c12e7dfde1..0000000000
--- a/src/main/target/KFC32F3_INAV/hardware_setup.c
+++ /dev/null
@@ -1,53 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#include
-#include
-#include
-
-#include "platform.h"
-
-#include "build/build_config.h"
-
-#include "drivers/time.h"
-#include "drivers/bus_spi.h"
-#include "drivers/io.h"
-#include "drivers/io_impl.h"
-
-void initialisePreBootHardware(void)
-{
- // setup CS pins
- IOInit(DEFIO_IO(PB5), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
- IOConfigGPIO(DEFIO_IO(PB5), IOCFG_OUT_PP);
- IOHi(DEFIO_IO(PB5));
-
- IOInit(DEFIO_IO(PC15), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
- IOConfigGPIO(DEFIO_IO(PC15), IOCFG_OUT_PP);
- IOHi(DEFIO_IO(PC15));
-
- IOInit(DEFIO_IO(PB12), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
- IOConfigGPIO(DEFIO_IO(PB12), IOCFG_OUT_PP);
- IOHi(DEFIO_IO(PB12));
-
- IOInit(DEFIO_IO(PB2), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
- IOConfigGPIO(DEFIO_IO(PB2), IOCFG_OUT_PP);
- IOHi(DEFIO_IO(PB2));
-
- IOInit(DEFIO_IO(PA7), OWNER_SYSTEM, RESOURCE_OUTPUT, 0);
- IOConfigGPIO(DEFIO_IO(PA7), IOCFG_OUT_PP);
- IOHi(DEFIO_IO(PA7));
-}
\ No newline at end of file
diff --git a/src/main/target/KFC32F3_INAV/target.c b/src/main/target/KFC32F3_INAV/target.c
deleted file mode 100755
index a32e395332..0000000000
--- a/src/main/target/KFC32F3_INAV/target.c
+++ /dev/null
@@ -1,42 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#include
-
-#include
-#include "drivers/io.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/timer.h"
-
-const timerHardware_t timerHardware[] =
-{
- DEF_TIM(TIM2, CH1, PA0, TIM_USE_PPM, 0), // PPM
-
- DEF_TIM(TIM8, CH3, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM2
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3
- DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5
- DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6
- DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM7
- DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM8
-
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // S1_out
- DEF_TIM(TIM2, CH2, PA1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // S2_out
-};
-
-const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/KFC32F3_INAV/target.h b/src/main/target/KFC32F3_INAV/target.h
deleted file mode 100755
index 5d3dacf3ba..0000000000
--- a/src/main/target/KFC32F3_INAV/target.h
+++ /dev/null
@@ -1,146 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "KFCi"
-#define USE_HARDWARE_PREBOOT_SETUP
-
-#define USE_DJI_HD_OSD
-
-#define LED0 PC13
-#define LED0_INVERTED
-
-#define LED1 PC14
-#define LED1_INVERTED
-
-#define BEEPER PA13
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define GYRO_INT_EXTI PC5
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define BUS_SPI_SPEED_MAX BUS_SPEED_SLOW
-
-#define USE_IMU_MPU6000
-#define IMU_MPU6000_ALIGN CW90_DEG
-#define MPU6000_CS_PIN PB5
-#define MPU6000_SPI_BUS BUS_SPI2
-
-
-#define USE_MAG
-#define MAG_I2C_BUS BUS_I2C1
-#define USE_MAG_HMC5883
-#define USE_MAG_QMC5883
-#define USE_MAG_IST8310
-#define USE_MAG_IST8308
-#define USE_MAG_MAG3110
-#define USE_MAG_LIS3MDL
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
-
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PB14
-#define SPI2_MOSI_PIN PB15
-
-#define USE_FLASHFS
-
-#define USE_FLASH_M25P16
-#define M25P16_CS_PIN PB12
-#define M25P16_SPI_BUS BUS_SPI2
-#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
-
-#define USE_BARO
-#define USE_BARO_MS5611
-#define MS5611_SPI_BUS BUS_SPI2
-#define MS5611_CS_PIN PB2
-
-#define USE_OSD
-#define USE_MAX7456
-#define MAX7456_SPI_BUS BUS_SPI2
-#define MAX7456_CS_PIN PA7
-
-//#define RFM_SPI SPI2
-//#define RFM_SPI_CS_PIN PC15
-//#define RFM_IRQ_PIN PB3
-//#define RFM_SPI_CLK (SPI_CLOCK_STANDARD*2)
-//#define RFM_RESTORE_CLK (SPI_CLOCK_FAST)
-
-#define USE_RX_SPI
-#define USE_RX_ELERES
-#define RX_NSS_PIN PC15
-#define RX_NSS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOC
-#define RX_SCK_PIN PB13
-#define RX_MOSI_PIN PB15
-#define RX_MISO_PIN PB14
-#define RX_SPI_INSTANCE SPI2
-#define RX_IRQ_PIN PB3
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define SERIAL_PORT_COUNT 3
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA2
-#define UART2_RX_PIN PA3
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-
-#define I2C1_SCL PA15
-#define I2C1_SDA PA14
-
-#define USE_PITOT_MS4525
-#define PITOT_I2C_BUS BUS_I2C1
-
-#define BOARD_HAS_VOLTAGE_DIVIDER
-#define USE_ADC
-#define ADC_INSTANCE ADC2
-#define ADC_CHANNEL_1_PIN PA4
-#define ADC_CHANNEL_2_PIN PA6
-#define ADC_CHANNEL_3_PIN PA5
-#define VBAT_ADC_CHANNEL ADC_CHN_1
-#define RSSI_ADC_CHANNEL ADC_CHN_2
-#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
-
-//#define USE_LED_STRIP
-//#define WS2811_PIN PA8
-//#define WS2811_DMA_STREAM DMA1_Channel2
-//#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER
-
-#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_BLACKBOX | FEATURE_OSD | FEATURE_VBAT)
-#define DEFAULT_RX_TYPE RX_TYPE_PPM
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-// Number of available PWM outputs
-#define MAX_PWM_OUTPUT_PORTS 10
-#define TARGET_MOTOR_COUNT 10
-
-// IO - stm32f303cc in 48pin package
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
-#define TARGET_IO_PORTF (BIT(4))
diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h
index 3a222d8acc..3338db998e 100644
--- a/src/main/target/OMNIBUS/target.h
+++ b/src/main/target/OMNIBUS/target.h
@@ -119,8 +119,8 @@
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
-#define USE_LED_STRIP
-#define WS2811_PIN PA8
+//#define USE_LED_STRIP
+//#define WS2811_PIN PA8
//#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h
index c60d00116b..9a68d246b1 100644
--- a/src/main/target/PIKOBLX/target.h
+++ b/src/main/target/PIKOBLX/target.h
@@ -72,8 +72,8 @@
#define VBAT_ADC_CHANNEL ADC_CHN_2
#define RSSI_ADC_CHANNEL ADC_CHN_3
-#define USE_LED_STRIP
-#define WS2811_PIN PB8 // TIM16_CH1
+//#define USE_LED_STRIP
+//#define WS2811_PIN PB8 // TIM16_CH1
// #define USE_TRANSPONDER
// #define TRANSPONDER_PIN PA8
diff --git a/src/main/target/RMDO/CMakeLists.txt b/src/main/target/RMDO/CMakeLists.txt
deleted file mode 100644
index ed40102c52..0000000000
--- a/src/main/target/RMDO/CMakeLists.txt
+++ /dev/null
@@ -1 +0,0 @@
-target_stm32f303xc(RMDO COMPILE_DEFINITIONS "SPRACINGF3" SKIP_RELEASES)
diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c
deleted file mode 100644
index 59769ba505..0000000000
--- a/src/main/target/RMDO/target.c
+++ /dev/null
@@ -1,48 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#include
-
-#include
-#include "drivers/io.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/timer.h"
-
-const timerHardware_t timerHardware[] = {
- DEF_TIM(TIM16, CH1, PA6, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
- DEF_TIM(TIM17, CH1, PA7, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
- DEF_TIM(TIM4, CH1, PA11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM3 - PA11
- DEF_TIM(TIM4, CH2, PA12, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM4 - PA12
- DEF_TIM(TIM4, CH3, PB8, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM5 - PB8
- DEF_TIM(TIM4, CH4, PB9, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // PWM6 - PB9
- DEF_TIM(TIM15, CH1, PA2, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM7 - PA2
- DEF_TIM(TIM15, CH2, PA3, TIM_USE_MC_MOTOR | TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0), // PWM8 - PA3
-
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0), // GPIO_TIMER / LED_STRIP
-
- DEF_TIM(TIM2, CH1, PA0, TIM_USE_PWM | TIM_USE_PPM, 0), // RC_CH1 - PA0 - *TIM2_CH1
- DEF_TIM(TIM2, CH2, PA1, TIM_USE_PWM, 0), // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
- DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0), // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7)
- DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0), // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7)
- DEF_TIM(TIM3, CH1, PB4, TIM_USE_PWM, 0), // RC_CH5 - PB4 - *TIM3_CH1
- DEF_TIM(TIM3, CH2, PB5, TIM_USE_PWM, 0), // RC_CH6 - PB5 - *TIM3_CH2
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, 0), // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, 0), // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
-};
-
-
-const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h
deleted file mode 100644
index fe467f8296..0000000000
--- a/src/main/target/RMDO/target.h
+++ /dev/null
@@ -1,125 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "RMDO" // Ready Made RC DoDo
-
-#define LED0 PB3
-
-#define BEEPER PC15
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define USE_IMU_MPU6050
-#define IMU_MPU6050_ALIGN CW270_DEG
-#define MPU6050_I2C_BUS BUS_I2C1
-
-
-#define USE_BARO
-#define BARO_I2C_BUS BUS_I2C1
-#define USE_BARO_BMP280
-
-#define USE_MAG
-#define MAG_I2C_BUS BUS_I2C1
-#define USE_MAG_AK8975
-#define USE_MAG_HMC5883
-#define USE_MAG_QMC5883
-#define USE_MAG_IST8310
-#define USE_MAG_IST8308
-#define USE_MAG_MAG3110
-#define USE_MAG_LIS3MDL
-
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
-
-#define USE_RANGEFINDER
-#define USE_RANGEFINDER_HCSR04
-#define RANGEFINDER_HCSR04_TRIGGER_PIN PB0 // RC_CH7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
-#define RANGEFINDER_HCSR04_ECHO_PIN PB1 // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
-
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_SOFTSERIAL1
-#define USE_SOFTSERIAL2
-#define SERIAL_PORT_COUNT 5
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA14 // PA14 / SWCLK
-#define UART2_RX_PIN PA15 // PA15
-
-#define UART3_TX_PIN PB10 // PB10 (AF7)
-#define UART3_RX_PIN PB11 // PB11 (AF7)
-
-#define SOFTSERIAL_1_RX_PIN PB4
-#define SOFTSERIAL_1_TX_PIN PB5
-#define SOFTSERIAL_2_RX_PIN PB0
-#define SOFTSERIAL_2_TX_PIN PB1
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
-
-#define M25P16_CS_GPIO GPIOB
-#define M25P16_CS_PIN PB12
-#define M25P16_SPI_BUS BUS_SPI2
-
-#define BOARD_HAS_VOLTAGE_DIVIDER
-#define USE_ADC
-#define ADC_INSTANCE ADC2
-#define ADC_CHANNEL_1_PIN PA4
-#define ADC_CHANNEL_2_PIN PA5
-#define ADC_CHANNEL_3_PIN PB2
-#define VBAT_ADC_CHANNEL ADC_CHN_1
-#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
-#define RSSI_ADC_CHANNEL ADC_CHN_3
-
-#define USE_LED_STRIP
-
-#define USE_LED_STRIP_ON_DMA1_CHANNEL2
-#define WS2811_PIN PA8
-
-#undef NAV_MAX_WAYPOINTS
-#define NAV_MAX_WAYPOINTS 30
-
-#define USE_SPEKTRUM_BIND
-// USART3,
-#define BIND_PIN PB11
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-#undef USE_GPS_PROTO_NAZA
-#undef USE_TELEMETRY_HOTT
-#undef USE_TELEMETRY_SMARTPORT
-#undef USE_TELEMETRY_IBUS
-
-// Number of available PWM outputs
-#define MAX_PWM_OUTPUT_PORTS 12
-
-// IO - stm32f303cc in 48pin package
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
diff --git a/src/main/target/SPRACINGF3NEO/CMakeLists.txt b/src/main/target/SPRACINGF3NEO/CMakeLists.txt
deleted file mode 100644
index d93726a632..0000000000
--- a/src/main/target/SPRACINGF3NEO/CMakeLists.txt
+++ /dev/null
@@ -1 +0,0 @@
-target_stm32f303xc(SPRACINGF3NEO SKIP_RELEASES)
diff --git a/src/main/target/SPRACINGF3NEO/config.c b/src/main/target/SPRACINGF3NEO/config.c
deleted file mode 100644
index 922e391a27..0000000000
--- a/src/main/target/SPRACINGF3NEO/config.c
+++ /dev/null
@@ -1,39 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#include
-#include
-
-#include "platform.h"
-
-#include "io/serial.h"
-
-#include "sensors/sensors.h"
-#include "sensors/compass.h"
-#include "sensors/barometer.h"
-
-#include "telemetry/telemetry.h"
-
-void targetConfiguration(void)
-{
- barometerConfigMutable()->baro_hardware = BARO_AUTODETECT;
- compassConfigMutable()->mag_hardware = MAG_AUTODETECT;
- serialConfigMutable()->portConfigs[1].functionMask = FUNCTION_MSP; // So Bluetooth users don't have to change anything.
- serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(TELEMETRY_UART)].functionMask = FUNCTION_TELEMETRY_SMARTPORT;
- serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(GPS_UART)].functionMask = FUNCTION_GPS;
- //telemetryConfigMutable()->halfDuplex = 1;
-}
diff --git a/src/main/target/SPRACINGF3NEO/target.c b/src/main/target/SPRACINGF3NEO/target.c
deleted file mode 100755
index 6a932ead1b..0000000000
--- a/src/main/target/SPRACINGF3NEO/target.c
+++ /dev/null
@@ -1,46 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#include
-
-#include
-
-#include "drivers/io.h"
-#include "drivers/pwm_mapping.h"
-#include "drivers/timer.h"
-
-const timerHardware_t timerHardware[] = {
- DEF_TIM(TIM15, CH2, PA3, TIM_USE_PWM | TIM_USE_PPM, 0), // PWM1 / PPM / UART2 RX
- DEF_TIM(TIM15, CH1, PA2, TIM_USE_PWM, 0), // PWM2
-
- DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // ESC1
- DEF_TIM(TIM3, CH2, PC7, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // ESC2
- DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // ESC3
- DEF_TIM(TIM3, CH1, PC6, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0), // ESC4
-
- DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // ESC5 (FW motor)
- DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0), // ESC6 (FW motor)
-
-
- DEF_TIM(TIM2, CH3, PB10, TIM_USE_PWM, 0), // PWM3 - PB10 - *TIM2_CH3, UART3_TX (AF7)
- DEF_TIM(TIM2, CH4, PB11, TIM_USE_PWM, 0), // PWM4 - PB11 - *TIM2_CH4, UART3_RX (AF7)
-
- DEF_TIM(TIM16, CH1, PB8, TIM_USE_ANY, 0),
- DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0),
-};
-
-const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
diff --git a/src/main/target/SPRACINGF3NEO/target.h b/src/main/target/SPRACINGF3NEO/target.h
deleted file mode 100755
index 9bec2fda3c..0000000000
--- a/src/main/target/SPRACINGF3NEO/target.h
+++ /dev/null
@@ -1,163 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it 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.
- *
- * Cleanflight 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 Cleanflight. If not, see .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "SP3N"
-
-#define LED0 PB9
-#define LED1 PB2
-
-#define BEEPER PC15
-#define BEEPER_INVERTED
-
-#define USE_EXTI
-#define GYRO_INT_EXTI PC13
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-
-#define USE_IMU_MPU6500
-#define IMU_MPU6500_ALIGN CW0_DEG
-
-#define USE_IMU_MPU9250
-#define IMU_MPU9250_ALIGN CW0_DEG
-
-#define MPU6500_CS_PIN SPI1_NSS_PIN
-#define MPU6500_SPI_BUS BUS_SPI1
-
-#define MPU9250_CS_PIN SPI1_NSS_PIN
-#define MPU9250_SPI_BUS BUS_SPI1
-
-#define USE_BARO
-#define BARO_I2C_BUS BUS_I2C1
-#define USE_BARO_BMP280
-#define USE_BARO_MS5611
-
-#define USE_MAG
-#define MAG_I2C_BUS BUS_I2C1
-#define USE_MAG_MPU9250
-#define USE_MAG_HMC5883
-#define USE_MAG_QMC5883
-#define USE_MAG_IST8310
-#define USE_MAG_IST8308
-#define USE_MAG_MAG3110
-#define USE_MAG_LIS3MDL
-
-#define USE_VCP
-#define USE_UART1
-#define USE_UART2
-#define USE_UART3
-#define USE_UART4
-#define USE_UART5
-//#define USE_SOFTSERIAL1
-//#define USE_SOFTSERIAL2
-//#define SERIAL_PORT_COUNT 8
-#define SERIAL_PORT_COUNT 6
-
-#define UART1_TX_PIN PA9
-#define UART1_RX_PIN PA10
-
-#define UART2_TX_PIN PA2
-#define UART2_RX_PIN PA3
-
-#define UART3_TX_PIN PB10
-#define UART3_RX_PIN PB11
-
-#define USE_I2C
-#define USE_I2C_DEVICE_1
-
-#define USE_SPI
-#define USE_SPI_DEVICE_1 // MPU
-#define USE_SPI_DEVICE_2 // SDCard
-#define USE_SPI_DEVICE_3 // External (MAX7456 & RTC6705)
-
-#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 SPI3_NSS_PIN PA15
-#define SPI3_SCK_PIN PB3
-#define SPI3_MISO_PIN PB4
-#define SPI3_MOSI_PIN PB5
-
-#undef USE_VTX_FFPV
-#undef USE_VTX_SMARTAUDIO // Disabled due to flash size
-#undef USE_VTX_TRAMP // Disabled due to flash size
-
-#undef USE_PITOT // Disabled due to RAM size
-#undef USE_PITOT_ADC // Disabled due to RAM size
-
-#define USE_MAX7456
-#define MAX7456_SPI_BUS BUS_SPI3
-#define MAX7456_CS_PIN PA15
-
-#define USE_SDCARD
-#define USE_SDCARD_SPI
-#define SDCARD_DETECT_INVERTED
-#define SDCARD_DETECT_PIN PC14
-#define SDCARD_SPI_BUS BUS_SPI2
-#define SDCARD_CS_PIN SPI2_NSS_PIN
-
-#define USE_ADC
-#define ADC_INSTANCE ADC1
-#define ADC_CHANNEL_1_PIN PC1
-#define ADC_CHANNEL_2_PIN PC2
-#define ADC_CHANNEL_3_PIN PC0
-#define VBAT_ADC_CHANNEL ADC_CHN_1
-#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
-#define RSSI_ADC_CHANNEL ADC_CHN_3
-
-#define USE_LED_STRIP
-#define WS2811_PIN PA8
-
-#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
-
-#define USE_OSD
-
-#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
-#define DEFAULT_FEATURES (FEATURE_TX_PROF_SEL | FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP)
-#define SERIALRX_UART SERIAL_PORT_USART2
-#define GPS_UART SERIAL_PORT_USART3
-#define TELEMETRY_UART SERIAL_PORT_USART5
-#define SERIALRX_PROVIDER SERIALRX_SBUS
-
-#define BUTTONS
-#define BUTTON_A_PIN PD2
-
-#define SPEKTRUM_BIND_PIN UART2_RX_PIN
-
-#define BINDPLUG_PIN PD2
-
-#define USE_SERIAL_4WAY_BLHELI_INTERFACE
-
-// Number of available PWM outputs
-#define MAX_PWM_OUTPUT_PORTS 10
-
-// IO - assuming 303 in 64pin package, TODO
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
-
-#undef USE_TELEMETRY_FRSKY
diff --git a/src/main/target/common.h b/src/main/target/common.h
index abe10db98a..34c1ca9110 100755
--- a/src/main/target/common.h
+++ b/src/main/target/common.h
@@ -124,7 +124,6 @@
#define USE_PWM_DRIVER_PCA9685
-#define USE_TELEMETRY_SIM
#define USE_FRSKYOSD
#define USE_DJI_HD_OSD
#define USE_SMARTPORT_MASTER
@@ -138,7 +137,19 @@
#define USE_I2C_IO_EXPANDER
+#define USE_GPS_PROTO_NMEA
+#define USE_GPS_PROTO_MTK
+
+#define USE_TELEMETRY_SIM
+#define USE_TELEMETRY_HOTT
+#define USE_TELEMETRY_MAVLINK
+#define USE_MSP_OVER_TELEMETRY
+
#define USE_SERIALRX_SRXL2 // Spektrum SRXL2 protocol
+#define USE_SERIALRX_SUMD
+#define USE_SERIALRX_SUMH
+#define USE_SERIALRX_XBUS
+#define USE_SERIALRX_JETIEXBUS
#define USE_TELEMETRY_SRXL
#define USE_SPEKTRUM_CMS_TELEMETRY
//#define USE_SPEKTRUM_VTX_CONTROL //Some functions from betaflight still not implemented
@@ -164,23 +175,14 @@
#define USE_STATS
#define USE_CMS
#define CMS_MENU_OSD
-#define USE_GPS_PROTO_NMEA
-#define USE_GPS_PROTO_MTK
#define NAV_GPS_GLITCH_DETECTION
#define NAV_NON_VOLATILE_WAYPOINT_STORAGE
-#define USE_TELEMETRY_HOTT
#define USE_TELEMETRY_IBUS
-#define USE_TELEMETRY_MAVLINK
#define USE_TELEMETRY_SMARTPORT
#define USE_TELEMETRY_CRSF
-#define USE_MSP_OVER_TELEMETRY
// These are rather exotic serial protocols
#define USE_RX_MSP
//#define USE_MSP_RC_OVERRIDE
-#define USE_SERIALRX_SUMD
-#define USE_SERIALRX_SUMH
-#define USE_SERIALRX_XBUS
-#define USE_SERIALRX_JETIEXBUS
#define USE_SERIALRX_CRSF
#define USE_PWM_SERVO_DRIVER
#define USE_SERIAL_PASSTHROUGH
diff --git a/src/main/telemetry/sim.c b/src/main/telemetry/sim.c
index 8fe6b7c53c..1d4ef3fdd9 100644
--- a/src/main/telemetry/sim.c
+++ b/src/main/telemetry/sim.c
@@ -63,15 +63,6 @@
#define SIM_RESPONSE_CODE_CMT ('C' << 24 | 'M' << 16 | 'T' << 8 | ':')
-typedef enum {
- SIM_TX_FLAG = (1 << 0),
- SIM_TX_FLAG_FAILSAFE = (1 << 1),
- SIM_TX_FLAG_GPS = (1 << 2),
- SIM_TX_FLAG_ACC = (1 << 3),
- SIM_TX_FLAG_LOW_ALT = (1 << 4),
- SIM_TX_FLAG_RESPONSE = (1 << 5)
-} simTxFlags_e;
-
typedef enum {
SIM_MODULE_NOT_DETECTED = 0,
SIM_MODULE_NOT_REGISTERED,
@@ -124,7 +115,6 @@ static uint8_t simResponse[SIM_RESPONSE_BUFFER_SIZE + 1];
static int atCommandStatus = SIM_AT_OK;
static bool simWaitAfterResponse = false;
static uint8_t readState = SIM_READSTATE_RESPONSE;
-static uint8_t transmitFlags = 0;
static timeMs_t t_lastMessageSent = 0;
static uint8_t lastMessageTriggeredBy = 0;
static uint8_t simModuleState = SIM_MODULE_NOT_DETECTED;
@@ -146,7 +136,7 @@ static bool isGroundStationNumberDefined(void) {
static bool checkGroundStationNumber(uint8_t* rv)
{
int i;
- const uint8_t* gsn = telemetryConfig()->simGroundStationNumber;
+ const char* gsn = telemetryConfig()->simGroundStationNumber;
int digitsToCheck = strlen((char*)gsn);
if (gsn[0] == '+') {
@@ -177,7 +167,7 @@ static bool checkGroundStationNumber(uint8_t* rv)
static void readOriginatingNumber(uint8_t* rv)
{
int i;
- uint8_t* gsn = telemetryConfigMutable()->simGroundStationNumber;
+ char* gsn = telemetryConfigMutable()->simGroundStationNumber;
if (gsn[0] != '\0')
return;
for (i = 0; i < 15 && rv[i] != '\"'; i++)
@@ -189,7 +179,7 @@ static void readTransmitFlags(const uint8_t* fs)
{
int i;
- transmitFlags = 0;
+ uint8_t transmitFlags = 0;
for (i = 0; i < SIM_N_TX_FLAGS && fs[i] != '\0'; i++) {
switch (fs[i]) {
case 'T': case 't':
@@ -209,6 +199,8 @@ static void readTransmitFlags(const uint8_t* fs)
break;
}
}
+
+ telemetryConfigMutable()->simTransmitFlags = transmitFlags;
}
static void requestSendSMS(uint8_t trigger)
@@ -337,7 +329,7 @@ static void transmit(void)
if (gpsSol.fixType != GPS_NO_FIX && FLIGHT_MODE(SIM_LOW_ALT_WARNING_MODES) && getAltitudeMeters() < telemetryConfig()->simLowAltitude)
triggers |= SIM_TX_FLAG_LOW_ALT;
- triggers &= transmitFlags;
+ triggers &= telemetryConfig()->simTransmitFlags;
if (!triggers)
return;
@@ -508,7 +500,6 @@ static void configureSimTelemetryPort(void)
sim_t_stateChange = millis() + SIM_STARTUP_DELAY_MS;
simTelemetryState = SIM_STATE_INIT;
readState = SIM_READSTATE_RESPONSE;
- readTransmitFlags(telemetryConfig()->simTransmitFlags);
simEnabled = true;
}
diff --git a/src/main/telemetry/sim.h b/src/main/telemetry/sim.h
index 081f74e036..299981e623 100644
--- a/src/main/telemetry/sim.h
+++ b/src/main/telemetry/sim.h
@@ -23,6 +23,15 @@
#define SIM_DEFAULT_TX_FLAGS "f"
#define SIM_PIN "0000"
+typedef enum {
+ SIM_TX_FLAG = (1 << 0),
+ SIM_TX_FLAG_FAILSAFE = (1 << 1),
+ SIM_TX_FLAG_GPS = (1 << 2),
+ SIM_TX_FLAG_ACC = (1 << 3),
+ SIM_TX_FLAG_LOW_ALT = (1 << 4),
+ SIM_TX_FLAG_RESPONSE = (1 << 5)
+} simTxFlags_e;
+
void handleSimTelemetry(void);
void initSimTelemetry(void);
diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c
index 98531e65e3..6246c3f47f 100644
--- a/src/main/telemetry/telemetry.c
+++ b/src/main/telemetry/telemetry.c
@@ -34,6 +34,7 @@
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
+#include "fc/settings.h"
#include "io/serial.h"
@@ -53,38 +54,43 @@
#include "telemetry/ghst.h"
-PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 4);
+PG_REGISTER_WITH_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 5);
PG_RESET_TEMPLATE(telemetryConfig_t, telemetryConfig,
- .gpsNoFixLatitude = 0,
- .gpsNoFixLongitude = 0,
- .telemetry_switch = 0,
- .telemetry_inverted = 0,
- .frsky_coordinate_format = FRSKY_FORMAT_DMS,
- .frsky_unit = FRSKY_UNIT_METRICS,
- .frsky_vfas_precision = 0,
- .frsky_pitch_roll = 0,
- .report_cell_voltage = 0,
- .hottAlarmSoundInterval = 5,
- .halfDuplex = 1,
- .smartportFuelUnit = SMARTPORT_FUEL_UNIT_MAH,
- .ibusTelemetryType = 0,
- .ltmUpdateRate = LTM_RATE_NORMAL,
- .simTransmitInterval = SIM_DEFAULT_TRANSMIT_INTERVAL,
- .simTransmitFlags = SIM_DEFAULT_TX_FLAGS,
- .simLowAltitude = INT16_MIN,
- .simPin = SIM_PIN,
- .accEventThresholdHigh = 0,
- .accEventThresholdLow = 0,
- .accEventThresholdNegX = 0,
+ .gpsNoFixLatitude = SETTING_FRSKY_DEFAULT_LATITUDE_DEFAULT,
+ .gpsNoFixLongitude = SETTING_FRSKY_DEFAULT_LONGITUDE_DEFAULT,
+ .telemetry_switch = SETTING_TELEMETRY_SWITCH_DEFAULT,
+ .telemetry_inverted = SETTING_TELEMETRY_INVERTED_DEFAULT,
+ .frsky_coordinate_format = SETTING_FRSKY_COORDINATES_FORMAT_DEFAULT,
+ .frsky_unit = SETTING_FRSKY_UNIT_DEFAULT,
+ .frsky_vfas_precision = SETTING_FRSKY_VFAS_PRECISION_DEFAULT,
+ .frsky_pitch_roll = SETTING_FRSKY_PITCH_ROLL_DEFAULT,
+ .report_cell_voltage = SETTING_REPORT_CELL_VOLTAGE_DEFAULT,
+ .hottAlarmSoundInterval = SETTING_HOTT_ALARM_SOUND_INTERVAL_DEFAULT,
+ .halfDuplex = SETTING_TELEMETRY_HALFDUPLEX_DEFAULT,
+ .smartportFuelUnit = SETTING_SMARTPORT_FUEL_UNIT_DEFAULT,
+ .ibusTelemetryType = SETTING_IBUS_TELEMETRY_TYPE_DEFAULT,
+ .ltmUpdateRate = SETTING_LTM_UPDATE_RATE_DEFAULT,
+
+#ifdef USE_TELEMETRY_SIM
+ .simTransmitInterval = SETTING_SIM_TRANSMIT_INTERVAL_DEFAULT,
+ .simTransmitFlags = SETTING_SIM_TRANSMIT_FLAGS_DEFAULT,
+ .simLowAltitude = SETTING_SIM_LOW_ALTITUDE_DEFAULT,
+ .simPin = SETTING_SIM_PIN_DEFAULT,
+ .simGroundStationNumber = SETTING_SIM_GROUND_STATION_NUMBER_DEFAULT,
+
+ .accEventThresholdHigh = SETTING_ACC_EVENT_THRESHOLD_HIGH_DEFAULT,
+ .accEventThresholdLow = SETTING_ACC_EVENT_THRESHOLD_LOW_DEFAULT,
+ .accEventThresholdNegX = SETTING_ACC_EVENT_THRESHOLD_NEG_X_DEFAULT,
+#endif
.mavlink = {
- .extended_status_rate = 2,
- .rc_channels_rate = 5,
- .position_rate = 2,
- .extra1_rate = 10,
- .extra2_rate = 2,
- .extra3_rate = 1
+ .extended_status_rate = SETTING_MAVLINK_EXT_STATUS_RATE_DEFAULT,
+ .rc_channels_rate = SETTING_MAVLINK_RC_CHAN_RATE_DEFAULT,
+ .position_rate = SETTING_MAVLINK_POS_RATE_DEFAULT,
+ .extra1_rate = SETTING_MAVLINK_EXTRA1_RATE_DEFAULT,
+ .extra2_rate = SETTING_MAVLINK_EXTRA2_RATE_DEFAULT,
+ .extra3_rate = SETTING_MAVLINK_EXTRA3_RATE_DEFAULT
}
);
diff --git a/src/main/telemetry/telemetry.h b/src/main/telemetry/telemetry.h
index 717e9fec03..242f5cc83e 100644
--- a/src/main/telemetry/telemetry.h
+++ b/src/main/telemetry/telemetry.h
@@ -68,14 +68,18 @@ typedef struct telemetryConfig_s {
smartportFuelUnit_e smartportFuelUnit;
uint8_t ibusTelemetryType;
uint8_t ltmUpdateRate;
+
+#ifdef USE_TELEMETRY_SIM
+ int16_t simLowAltitude;
+ char simGroundStationNumber[16];
+ char simPin[8];
uint16_t simTransmitInterval;
- uint8_t simTransmitFlags[4];
+ uint8_t simTransmitFlags;
+
uint16_t accEventThresholdHigh;
uint16_t accEventThresholdLow;
uint16_t accEventThresholdNegX;
- int16_t simLowAltitude;
- uint8_t simGroundStationNumber[16];
- uint8_t simPin[8];
+#endif
struct {
uint8_t extended_status_rate;
uint8_t rc_channels_rate;
@@ -98,4 +102,3 @@ void telemetryCheckState(void);
void telemetryProcess(timeUs_t currentTimeUs);
bool telemetryDetermineEnabledState(portSharing_e portSharing);
-
diff --git a/src/test/unit/CMakeLists.txt b/src/test/unit/CMakeLists.txt
index d1aebcd5e0..1f6e7dcd00 100644
--- a/src/test/unit/CMakeLists.txt
+++ b/src/test/unit/CMakeLists.txt
@@ -43,9 +43,13 @@ function(unit_test src)
endif()
list(TRANSFORM deps PREPEND "${MAIN_DIR}/")
add_executable(${name} ${src} ${deps})
- target_include_directories(${name} PRIVATE . ${MAIN_DIR})
+ set(gen_name ${name}_gen)
+ get_generated_files_dir(gen ${gen_name})
+ target_include_directories(${name} PRIVATE . ${MAIN_DIR} ${gen})
target_compile_definitions(${name} PRIVATE ${test_definitions})
- set_target_properties(${name} PROPERTIES COMPILE_FLAGS "-pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0")
+ target_compile_options(${name} PRIVATE -pthread -Wall -Wextra -Wno-extern-c-compat -ggdb3 -O0)
+ enable_settings(${name} ${gen_name} OUTPUTS setting_files SETTINGS_CXX g++)
+ target_sources(${name} PRIVATE ${setting_files})
target_link_libraries(${name} gtest_main)
gtest_discover_tests(${name})
add_custom_target("run-${name}" "${name}" DEPENDS ${name})
diff --git a/src/utils/compiler.rb b/src/utils/compiler.rb
index 39f7d57184..dc44611426 100644
--- a/src/utils/compiler.rb
+++ b/src/utils/compiler.rb
@@ -36,7 +36,10 @@ class Compiler
# on Windows if PATH contains spaces.
#dirs = ((ENV["CPP_PATH"] || "") + File::PATH_SEPARATOR + (ENV["PATH"] || "")).split(File::PATH_SEPARATOR)
dirs = ((ENV["CPP_PATH"] || "") + File::PATH_SEPARATOR + (ENV["PATH"] || "")).split(File::PATH_SEPARATOR)
- bin = "arm-none-eabi-g++"
+ bin = ENV["SETTINGS_CXX"]
+ if bin.empty?
+ bin = "arm-none-eabi-g++"
+ end
dirs.each do |dir|
p = File.join(dir, bin)
['', '.exe'].each do |suffix|
diff --git a/src/utils/settings.rb b/src/utils/settings.rb
old mode 100644
new mode 100755
index 10deeab1c7..acae823773
--- a/src/utils/settings.rb
+++ b/src/utils/settings.rb
@@ -299,9 +299,11 @@ class Generator
load_data
+ check_member_default_values_presence
sanitize_fields
initialize_name_encoder
initialize_value_encoder
+ validate_default_values
write_header_file(header_file)
write_impl_file(impl_file)
@@ -417,8 +419,33 @@ class Generator
ii = 0
foreach_enabled_member do |group, member|
name = member["name"]
+ type = member["type"]
+ default_value = member["default_value"]
+
+ case
+ when %i[ zero target ].include?(default_value)
+ default_value = nil
+
+ when member.has_key?("table")
+ table_name = member["table"]
+ table_values = @tables[table_name]["values"]
+ if table_name == 'off_on' and [false, true].include? default_value
+ default_value = { false => '0', true => '1' }[default_value]
+ else
+ default_value = table_values.index default_value
+ end
+
+ when type == "string"
+ default_value = "{ #{[*default_value.bytes, 0] * ', '} }"
+
+ when default_value.is_a?(Float)
+ default_value = default_value.to_s + ?f
+
+ end
+
min, max = resolve_range(member)
setting_name = "SETTING_#{name.upcase}"
+ buf << "#define #{setting_name}_DEFAULT #{default_value}\n" unless default_value.nil?
buf << "#define #{setting_name} #{ii}\n"
buf << "#define #{setting_name}_MIN #{min}\n"
buf << "#define #{setting_name}_MAX #{max}\n"
@@ -444,6 +471,12 @@ class Generator
end
end
+ # When this file is compiled in unit tests, some of the tables
+ # are not used and generate warnings, causing the test to fail
+ # with -Werror. Silence them
+
+ buf << "#pragma GCC diagnostic ignored \"-Wunused-const-variable\"\n"
+
# Write PGN arrays
pgn_steps = []
pgns = []
@@ -629,44 +662,47 @@ class Generator
return !cond || @true_conditions.include?(cond)
end
- def foreach_enabled_member
- @data["groups"].each do |group|
- if is_condition_enabled(group["condition"])
- group["members"].each do |member|
- if is_condition_enabled(member["condition"])
- yield group, member
+ def foreach_enabled_member &block
+ enum = Enumerator.new do |yielder|
+ groups.each do |group|
+ if is_condition_enabled(group["condition"])
+ group["members"].each do |member|
+ if is_condition_enabled(member["condition"])
+ yielder.yield group, member
+ end
end
end
end
end
+ block_given? ? enum.each(&block) : enum
end
- def foreach_enabled_group
- last = nil
- foreach_enabled_member do |group, member|
- if last != group
- last = group
- yield group
+ def foreach_enabled_group &block
+ enum = Enumerator.new do |yielder|
+ last = nil
+ foreach_enabled_member do |group, member|
+ if last != group
+ last = group
+ yielder.yield group
+ end
end
end
+ block_given? ? enum.each(&block) : enum
end
- def foreach_member
- @data["groups"].each do |group|
- group["members"].each do |member|
- yield group, member
+ def foreach_member &block
+ enum = Enumerator.new do |yielder|
+ @data["groups"].each do |group|
+ group["members"].each do |member|
+ yielder.yield group, member
+ end
end
end
+ block_given? ? enum.each(&block) : enum
end
- def foreach_group
- last = nil
- foreach_member do |group, member|
- if last != group
- last = group
- yield group
- end
- end
+ def groups
+ @data["groups"]
end
def initialize_tables
@@ -795,25 +831,27 @@ class Generator
if !group["name"]
raise "Missing group name"
end
+
if !member["name"]
raise "Missing member name in group #{group["name"]}"
end
+
table = member["table"]
if table
if !@tables[table]
raise "Member #{member["name"]} references non-existing table #{table}"
end
+
@used_tables << table
end
+
if !member["field"]
member["field"] = member["name"]
end
+
typ = member["type"]
- if !typ
- pending_types[member] = group
- elsif typ == "bool"
+ if typ == "bool"
has_booleans = true
- member["type"] = "uint8_t"
member["table"] = OFF_ON_TABLE["name"]
end
end
@@ -825,7 +863,7 @@ class Generator
@used_tables << OFF_ON_TABLE["name"]
end
- resolve_types pending_types unless !pending_types
+ resolve_all_types
foreach_enabled_member do |group, member|
@count += 1
@max_name_length = [@max_name_length, member["name"].length].max
@@ -835,9 +873,82 @@ class Generator
end
end
+ def validate_default_values
+ foreach_enabled_member do |_, member|
+ name = member["name"]
+ type = member["type"]
+ default_value = member["default_value"]
+
+ next if %i[ zero target ].include? default_value
+
+ case
+ when type == "bool"
+ raise "Member #{name} has an invalid default value" unless [ false, true ].include? default_value
+
+ when member.has_key?("table")
+ table_name = member["table"]
+ table_values = @tables[table_name]["values"]
+ raise "Member #{name} has an invalid default value" unless table_values.include? default_value
+
+ when type =~ /\A(?u?)int(?8|16|32|64)_t\Z/
+ unsigned = !$~[:unsigned].empty?
+ bitsize = $~[:bitsize].to_i
+ type_range = unsigned ? 0..(2**bitsize-1) : (-2**(bitsize-1)+1)..(2**(bitsize-1)-1)
+ raise "Numeric member #{name} doesn't have maximum value defined" unless member.has_key? 'max'
+ 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
+
+ when type == "float"
+ raise "Numeric member #{name} doesn't have maximum value defined" unless member.has_key? 'max'
+ raise "Member #{name} default value has an invalid type, numeric or symbol expected" unless default_value.is_a? Numeric or default_value.is_a? Symbol
+
+ when type == "string"
+ max = member["max"].to_i
+ raise "Member #{name} default value has an invalid type, string expected" unless default_value.is_a? String
+ raise "Member #{name} default value is too long (max #{max} chars)" if default_value.bytesize > max
+
+ else
+ raise "Unexpected type for member #{name}: #{type.inspect}"
+ end
+ end
+ end
+
+ def scan_types(stderr)
+ types = Hash.new
+ # gcc 6-9
+ stderr.scan(/var_(\d+).*?['’], which is of non-class type ['‘](.*)['’]/).each do |m|
+ member_idx = m[0].to_i
+ type = m[1]
+ types[member_idx] = type
+ end
+ # clang
+ stderr.scan(/member reference base type '(.*?)'.*?is not a structure or union.*? var_(\d+)/m).each do |m|
+ member_idx = m[1].to_i
+ type = m[0]
+ types[member_idx] = type
+ end
+ return types
+ end
+
+ def resolve_all_types()
+ loop do
+ pending = Hash.new
+ foreach_enabled_member do |group, member|
+ if !member["type"]
+ pending[member] = group
+ end
+ end
+
+ if pending.empty?
+ # All types resolved
+ break
+ end
+
+ resolve_types(pending)
+ end
+ end
+
def resolve_types(pending)
- # TODO: Loop to avoid reaching the maximum number
- # of errors printed by the compiler.
prog = StringIO.new
prog << "int main() {\n"
ii = 0
@@ -853,9 +964,13 @@ class Generator
prog << "return 0;\n"
prog << "};\n"
stderr = compile_test_file(prog)
- stderr.scan(/var_(\d+).*?', which is of non-class type '(.*)'/).each do |m|
- member = members[m[0].to_i]
- case m[1]
+ types = scan_types(stderr)
+ if types.empty?
+ raise "No types resolved from #{stderr}"
+ end
+ types.each do |idx, type|
+ member = members[idx]
+ case type
when /^int8_t/ # {aka signed char}"
typ = "int8_t"
when /^uint8_t/ # {aka unsigned char}"
@@ -878,12 +993,6 @@ class Generator
dputs "#{member["name"]} type is #{typ}"
member["type"] = typ
end
- # Make sure all types have been resolved
- foreach_enabled_member do |group, member|
- if !member["type"]
- raise "Could not resolve type for member #{member["name"]} in group #{group["name"]}"
- end
- end
end
def initialize_name_encoder
@@ -925,6 +1034,11 @@ class Generator
@value_encoder = ValueEncoder.new(values, constantValues)
end
+ def check_member_default_values_presence
+ missing_default_value_names = foreach_member.inject([]) { |names, (_, member)| member.has_key?("default_value") ? names : names << member["name"] }
+ raise "Missing default value for #{missing_default_value_names.count} member#{"s" unless missing_default_value_names.one?}: #{missing_default_value_names * ", "}" unless missing_default_value_names.empty?
+ end
+
def resolve_constants(constants)
return nil unless constants.length > 0
s = Set.new
@@ -936,7 +1050,9 @@ class Generator
# warnings to find these constants, the compiler
# might reach the maximum number of errors and stop
# compilation, so we might need multiple passes.
- re = /required from 'class expr_(.*?)<(.*)>'/
+ gcc_re = /required from ['‘]class expr_(.*?)<(.*?)>['’]/ # gcc 6-9
+ clang_re = / template class 'expr_(.*?)<(.*?)>'/ # clang
+ res = [gcc_re, clang_re]
values = Hash.new
while s.length > 0
buf = StringIO.new
@@ -956,7 +1072,12 @@ class Generator
ii += 1
end
stderr = compile_test_file(buf)
- matches = stderr.scan(re)
+ matches = []
+ res.each do |re|
+ if matches.length == 0
+ matches = stderr.scan(re)
+ end
+ end
if matches.length == 0
puts stderr
raise "No more matches looking for constants"