# hw definition file for MatekF405 hardware
# tested on the MatekF405-OSD board
# with thanks to betaflight for pinout
# MCU class and specific type
MCU STM32F4xx STM32F405xx
# board ID. See Tools/AP_Bootloader/board_types.txt
APJ_BOARD_ID 199
# crystal frequency
OSCILLATOR_HZ 8000000
define STM32_ST_USE_TIMER 4
define CH_CFG_ST_RESOLUTION 16
FLASH_SIZE_KB 1024
# only one I2C bus
I2C_ORDER I2C1
# order of UARTs (and USB)
SERIAL_ORDER OTG1 USART1 USART3 USART2 UART4 UART5 USART6
# LEDs
define AP_NOTIFY_GPIO_LED_2_ENABLED 1
PC15 LED_BLUE OUTPUT LOW GPIO(0)
PC14 LED_GREEN OUTPUT LOW GPIO(1)
PB3 GP_GPIO OUTPUT LOW GPIO(70)
define HAL_GPIO_A_LED_PIN 0
define HAL_GPIO_B_LED_PIN 1
# buzzer
PC13 BUZZER OUTPUT GPIO(80) LOW
define HAL_BUZZER_PIN 80
# GPIO
PC2 PINIO1 OUTPUT GPIO(81) HIGH
PC5 PINIO2 OUTPUT GPIO(82) HIGH
# spi1 bus for IMU
PA5 SPI1_SCK SPI1
PA6 SPI1_MISO SPI1
PA7 SPI1_MOSI SPI1
# spi2 for OSD
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
PB12 MAX7456_CS CS
# spi3 for sdcard and onboard flash
PC10 SPI3_SCK SPI3
PC11 SPI3_MISO SPI3
PB5 SPI3_MOSI SPI3
PA15 FLASH1_CS CS
# PC0 M25P16_CS CS
PA4 GYRO1_CS CS
# only one I2C bus in normal config
PB8 I2C1_SCL I2C1
PB9 I2C1_SDA I2C1
# analog pins
PC1 BATT_VOLTAGE_SENS ADC1 SCALE(1)
PC3 BATT_CURRENT_SENS ADC1 SCALE(1)
# PC1 RSSI_ADC_PIN ADC1 SCALE(1)
# define default battery setup
# PC5 - ADC12_CH15
define HAL_BATT_VOLT_PIN 11
# PC4 - ADC12_CH14
define HAL_BATT_CURR_PIN 13
define HAL_BATT_VOLT_SCALE 11
define HAL_BATT_CURR_SCALE 103.8
#analog rssi pin (also could be used as analog airspeed input)
# PB1 - ADC12_CH9
define BOARD_RSSI_ANA_PIN 9
# USART1
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# RC input using timer
PA3 TIM9_CH2 TIM9 RCININT PULLDOWN
# alternative RC input using UART 10K下拉电阻 永远下拉 傻逼HAKRC ONLY FOR SBUS
PA2 USART2_TX USART2 NODMA
PA3 USART2_RX USART2 NODMA ALT(1)
# USART3
PB10 USART3_TX USART3
PB11 USART3_RX USART3
# UART4
PA0 UART4_TX UART4
PA1 UART4_RX UART4
# UART5
PD2 UART5_RX UART5
PC12 UART5_TX UART5
# USART6
PC6 USART6_TX USART6
PC7 USART6_RX USART6
# PA10 IO-debug-console
PA11 OTG_FS_DM OTG1
PA12 OTG_FS_DP OTG1
# USB detection
# VBUS INPUT OPENDRAIN
# debug (disabled out to allow for both LEDs)
#PA13 JTMS-SWDIO SWD
#PA14 JTCK-SWCLK SWD
# PWM out pins. Note that channel order follows the ArduPilot motor
# order conventions
# Motor Outputs
PC8 TIM8_CH3 TIM8 PWM(1) GPIO(50)
PC9 TIM8_CH4 TIM8 PWM(2) GPIO(51)
PA8 TIM1_CH1 TIM1 PWM(3) GPIO(52)
PA9 TIM1_CH2 TIM1 PWM(4) GPIO(53)
PA10 TIM1_CH3 TIM1 PWM(5) GPIO(54)
PB4 TIM3_CH1 TIM3 PWM(6) GPIO(55)
PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56)
PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57)
define HAL_STORAGE_SIZE 15360
STORAGE_FLASH_PAGE 2
# reserve 32k for bootloader and 32k for flash storage
FLASH_RESERVE_START_KB 64
# ------------------- IMU ICM42605 ---------------------
SPIDEV icm42688 SPI1 DEVID0 GYRO1_CS MODE3 1*MHZ 16*MHZ
IMU Invensensev3 SPI:icm42688 ROTATION_ROLL_180_YAW_90
# filesystem setup on sdcard
# define HAL_OS_FATFS_IO 1
SPIDEV dataflash SPI3 DEVID1 FLASH1_CS MODE3 32*MHZ 32*MHZ
# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1
# BARO
# probe for I2C DPS310, but allow init on board variants without onboard baro too
BARO DPS310 I2C:0:0x76
# define HAL_BARO_ALLOW_INIT_NO_BARO
# define AP_BARO_BACKEND_DEFAULT_ENABLED 0
define AP_BARO_DPS310_ENABLED 1
# no built-in compass, but probe the i2c bus for all possible
# external compass types
define ALLOW_ARM_NO_COMPASS
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_COMPASS_AUTO_ROT_DEFAULT 2
# setup for OSD
SPIDEV osd SPI2 DEVID2 MAX7456_CS MODE0 10*MHZ 10*MHZ
define OSD_ENABLED 1
define HAL_OSD_TYPE_DEFAULT 1
ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
# disable parachute to save flash
define HAL_PARACHUTE_ENABLED 0
# save some flash
include ../include/minimize_fpv_osd.inc
the param
ACRO_BAL_PITCH,1
ACRO_BAL_ROLL,1
ACRO_OPTIONS,1
ACRO_RP_EXPO,0.67
ACRO_RP_RATE,720
ACRO_RP_RATE_TC,0
ACRO_THR_MID,0
ACRO_TRAINER,0
ACRO_Y_EXPO,0.67
ACRO_Y_RATE,600
ACRO_Y_RATE_TC,0
AHRS_COMP_BETA,0.1
AHRS_EKF_TYPE,3
AHRS_GPS_GAIN,1
AHRS_GPS_MINSATS,6
AHRS_GPS_USE,1
AHRS_OPTIONS,0
AHRS_ORIENTATION,4
AHRS_RP_P,0.2
AHRS_TRIM_X,0.0006457
AHRS_TRIM_Y,-0.0146321
AHRS_TRIM_Z,0
AHRS_WIND_MAX,0
AHRS_YAW_P,0.2
ANGLE_MAX,3000
ARMING_ACCTHRESH,0.75
ARMING_CHECK,12336
ARMING_MAGTHRESH,100
ARMING_MIS_ITEMS,0
ARMING_NEED_LOC,0
ARMING_OPTIONS,0
ARMING_RUDDER,0
ATC_ACCEL_P_MAX,110000
ATC_ACCEL_R_MAX,110000
ATC_ACCEL_Y_MAX,27000
ATC_ANG_LIM_TC,1
ATC_ANG_PIT_P,6
ATC_ANG_RLL_P,6
ATC_ANG_YAW_P,6
ATC_ANGLE_BOOST,1
ATC_INPUT_TC,0.15
ATC_LAND_P_MULT,1
ATC_LAND_R_MULT,1
ATC_LAND_Y_MULT,1
ATC_RAT_PIT_D,0.00012
ATC_RAT_PIT_D_FF,0
ATC_RAT_PIT_FF,0
ATC_RAT_PIT_FLTD,37.5
ATC_RAT_PIT_FLTE,0
ATC_RAT_PIT_FLTT,37.5
ATC_RAT_PIT_I,0.09
ATC_RAT_PIT_IMAX,0.5
ATC_RAT_PIT_P,0.04
ATC_RAT_PIT_PDMX,0
ATC_RAT_PIT_SMAX,0
ATC_RAT_RLL_D,0.00012
ATC_RAT_RLL_D_FF,0
ATC_RAT_RLL_FF,0
ATC_RAT_RLL_FLTD,37.5
ATC_RAT_RLL_FLTE,0
ATC_RAT_RLL_FLTT,37.5
ATC_RAT_RLL_I,0.09
ATC_RAT_RLL_IMAX,0.5
ATC_RAT_RLL_P,0.04
ATC_RAT_RLL_PDMX,0
ATC_RAT_RLL_SMAX,0
ATC_RAT_YAW_D,0.00012
ATC_RAT_YAW_D_FF,0
ATC_RAT_YAW_FF,0
ATC_RAT_YAW_FLTD,0
ATC_RAT_YAW_FLTE,2
ATC_RAT_YAW_FLTT,37.5
ATC_RAT_YAW_I,0.04
ATC_RAT_YAW_IMAX,0.5
ATC_RAT_YAW_P,0.11
ATC_RAT_YAW_PDMX,0
ATC_RAT_YAW_SMAX,0
ATC_RATE_FF_ENAB,1
ATC_RATE_P_MAX,0
ATC_RATE_R_MAX,0
ATC_RATE_Y_MAX,0
ATC_SLEW_YAW,6000
ATC_THR_G_BOOST,0
ATC_THR_MIX_MAN,0.1
ATC_THR_MIX_MAX,0.5
ATC_THR_MIX_MIN,0.1
AUTO_OPTIONS,0
AUTOTUNE_AGGR,0.075
AUTOTUNE_AXES,7
AUTOTUNE_MIN_D,0.0005
AVOID_ACCEL_MAX,3
AVOID_ALT_MIN,0
AVOID_ANGLE_MAX,1000
AVOID_BACKUP_DZ,0.1
AVOID_BACKUP_SPD,0.75
AVOID_BACKZ_SPD,0.75
AVOID_BEHAVE,0
AVOID_DIST_MAX,5
AVOID_ENABLE,3
AVOID_MARGIN,2
BARO_ALT_OFFSET,0
BARO_ALTERR_MAX,2000
BARO_EXT_BUS,-1
BARO_FIELD_ELV,0
BARO_FLTR_RNG,0
BARO_GND_TEMP,0
BARO_OPTIONS,0
BARO_PRIMARY,0
BARO_PROBE_EXT,0
BARO1_DEVID,423425
BARO1_GND_PRESS,100006.9
BARO2_DEVID,0
BARO2_GND_PRESS,0
BARO3_DEVID,0
BARO3_GND_PRESS,0
BATT_AMP_OFFSET,0
BATT_AMP_PERVLT,103.8
BATT_ARM_MAH,0
BATT_ARM_VOLT,14.7
BATT_CAPACITY,3300
BATT_CRT_MAH,0
BATT_CRT_VOLT,14
BATT_CURR_PIN,13
BATT_FS_CRT_ACT,1
BATT_FS_LOW_ACT,2
BATT_FS_VOLTSRC,0
BATT_LOW_MAH,0
BATT_LOW_TIMER,10
BATT_LOW_VOLT,14.4
BATT_MONITOR,4
BATT_OPTIONS,0
BATT_SERIAL_NUM,-1
BATT_VLT_OFFSET,0
BATT_VOLT_MULT,11
BATT_VOLT_PIN,11
BATT2_MONITOR,0
BATT3_MONITOR,0
BATT4_MONITOR,0
BATT5_MONITOR,0
BATT6_MONITOR,0
BATT7_MONITOR,0
BATT8_MONITOR,0
BATT9_MONITOR,0
BRD_ALT_CONFIG,0
BRD_BOOT_DELAY,0
BRD_OPTIONS,1
BRD_RTC_TYPES,1
BRD_RTC_TZ_MIN,0
BRD_SAFETY_DEFLT,0
BRD_SAFETY_MASK,16368
BRD_SAFETYOPTION,3
BRD_SD_SLOWDOWN,0
BRD_SERIAL_NUM,0
BTN_ENABLE,0
CAM_AUTO_ONLY,0
CAM_MAX_ROLL,0
CAM1_TYPE,0
CAM2_TYPE,0
CIRCLE_OPTIONS,1
CIRCLE_RADIUS,1000
CIRCLE_RATE,20
COMPASS_AUTO_ROT,2
COMPASS_AUTODEC,1
COMPASS_CAL_FIT,16
COMPASS_DEC,-0.1178207
COMPASS_DEV_ID,855297
COMPASS_DEV_ID2,0
COMPASS_DEV_ID3,0
COMPASS_DEV_ID4,0
COMPASS_DEV_ID5,0
COMPASS_DEV_ID6,0
COMPASS_DEV_ID7,0
COMPASS_DEV_ID8,0
COMPASS_DIA_X,0.9717223
COMPASS_DIA_Y,1.000764
COMPASS_DIA_Z,1.039477
COMPASS_DIA2_X,1
COMPASS_DIA2_Y,1
COMPASS_DIA2_Z,1
COMPASS_DIA3_X,1
COMPASS_DIA3_Y,1
COMPASS_DIA3_Z,1
COMPASS_DISBLMSK,0
COMPASS_ENABLE,1
COMPASS_EXTERN2,0
COMPASS_EXTERN3,0
COMPASS_EXTERNAL,1
COMPASS_FLTR_RNG,0
COMPASS_LEARN,0
COMPASS_MOT_X,0
COMPASS_MOT_Y,0
COMPASS_MOT_Z,0
COMPASS_MOT2_X,0
COMPASS_MOT2_Y,0
COMPASS_MOT2_Z,0
COMPASS_MOT3_X,0
COMPASS_MOT3_Y,0
COMPASS_MOT3_Z,0
COMPASS_MOTCT,0
COMPASS_ODI_X,0.0222533
COMPASS_ODI_Y,0.0040149
COMPASS_ODI_Z,-0.0108504
COMPASS_ODI2_X,0
COMPASS_ODI2_Y,0
COMPASS_ODI2_Z,0
COMPASS_ODI3_X,0
COMPASS_ODI3_Y,0
COMPASS_ODI3_Z,0
COMPASS_OFFS_MAX,1800
COMPASS_OFS_X,-237.3822
COMPASS_OFS_Y,-65.63731
COMPASS_OFS_Z,-7.371342
COMPASS_OFS2_X,0
COMPASS_OFS2_Y,0
COMPASS_OFS2_Z,0
COMPASS_OFS3_X,0
COMPASS_OFS3_Y,0
COMPASS_OFS3_Z,0
COMPASS_OPTIONS,0
COMPASS_ORIENT,0
COMPASS_ORIENT2,0
COMPASS_ORIENT3,0
COMPASS_PMOT_EN,0
COMPASS_PRIO1_ID,855297
COMPASS_PRIO2_ID,0
COMPASS_PRIO3_ID,0
COMPASS_SCALE,0
COMPASS_SCALE2,0
COMPASS_SCALE3,0
COMPASS_USE,1
COMPASS_USE2,0
COMPASS_USE3,0
CUST_ROT_ENABLE,0
DEV_OPTIONS,0
DISARM_DELAY,0
EK3_ABIAS_P_NSE,0.02
EK3_ACC_BIAS_LIM,1
EK3_ACC_P_NSE,0.35
EK3_AFFINITY,0
EK3_ALT_M_NSE,2
EK3_BCN_DELAY,50
EK3_BCN_I_GTE,500
EK3_BCN_M_NSE,1
EK3_BETA_MASK,0
EK3_CHECK_SCALE,100
EK3_DRAG_BCOEF_X,0
EK3_DRAG_BCOEF_Y,0
EK3_DRAG_M_NSE,0.5
EK3_DRAG_MCOEF,0
EK3_EAS_I_GATE,400
EK3_EAS_M_NSE,1.4
EK3_ENABLE,1
EK3_ERR_THRESH,0.2
EK3_FLOW_DELAY,10
EK3_FLOW_I_GATE,300
EK3_FLOW_M_NSE,0.25
EK3_FLOW_USE,1
EK3_GBIAS_P_NSE,0.001
EK3_GLITCH_RAD,25
EK3_GND_EFF_DZ,4
EK3_GPS_CHECK,31
EK3_GPS_VACC_MAX,0
EK3_GSF_RST_MAX,2
EK3_GSF_RUN_MASK,3
EK3_GSF_USE_MASK,3
EK3_GYRO_P_NSE,0.015
EK3_HGT_DELAY,60
EK3_HGT_I_GATE,500
EK3_HRT_FILT,2
EK3_IMU_MASK,1
EK3_LOG_LEVEL,0
EK3_MAG_CAL,3
EK3_MAG_EF_LIM,50
EK3_MAG_I_GATE,300
EK3_MAG_M_NSE,0.05
EK3_MAG_MASK,0
EK3_MAGB_P_NSE,0.0001
EK3_MAGE_P_NSE,0.001
EK3_MAX_FLOW,2.5
EK3_NOAID_M_NSE,10
EK3_OGN_HGT_MASK,0
EK3_OGNM_TEST_SF,2
EK3_OPTIONS,0
EK3_POS_I_GATE,500
EK3_POSNE_M_NSE,0.5
EK3_PRIMARY,0
EK3_RNG_I_GATE,500
EK3_RNG_M_NSE,0.5
EK3_RNG_USE_HGT,-1
EK3_RNG_USE_SPD,2
EK3_SRC_OPTIONS,1
EK3_SRC1_POSXY,3
EK3_SRC1_POSZ,1
EK3_SRC1_VELXY,3
EK3_SRC1_VELZ,3
EK3_SRC1_YAW,1
EK3_SRC2_POSXY,0
EK3_SRC2_POSZ,1
EK3_SRC2_VELXY,0
EK3_SRC2_VELZ,0
EK3_SRC2_YAW,0
EK3_SRC3_POSXY,0
EK3_SRC3_POSZ,1
EK3_SRC3_VELXY,0
EK3_SRC3_VELZ,0
EK3_SRC3_YAW,0
EK3_TAU_OUTPUT,25
EK3_TERR_GRAD,0.1
EK3_VEL_I_GATE,500
EK3_VELD_M_NSE,0.5
EK3_VELNE_M_NSE,0.3
EK3_VIS_VERR_MAX,0.9
EK3_VIS_VERR_MIN,0.1
EK3_WENC_VERR,0.1
EK3_WIND_P_NSE,0.2
EK3_WIND_PSCALE,1
EK3_YAW_I_GATE,300
EK3_YAW_M_NSE,0.5
ESC_CALIBRATION,0
ESC_TLM_MAV_OFS,0
FENCE_ACTION,3
FENCE_ALT_MAX,120
FENCE_ALT_MIN,-10
FENCE_AUTOENABLE,0
FENCE_ENABLE,0
FENCE_MARGIN,2
FENCE_NTF_FREQ,1
FENCE_OPTIONS,0
FENCE_RADIUS,150
FENCE_TOTAL,0
FENCE_TYPE,7
FLIGHT_OPTIONS,0
FLTMODE_CH,6
FLTMODE_GCSBLOCK,0
FLTMODE1,0
FLTMODE2,15
FLTMODE3,1
FLTMODE4,6
FLTMODE5,0
FLTMODE6,0
FORMAT_VERSION,120
FRAME_CLASS,1
FRAME_TYPE,1
FRSKY_DNLINK_ID,27
FRSKY_DNLINK1_ID,20
FRSKY_DNLINK2_ID,7
FRSKY_OPTIONS,0
FRSKY_UPLINK_ID,13
FS_CRASH_CHECK,0
FS_DR_ENABLE,2
FS_DR_TIMEOUT,30
FS_EKF_ACTION,1
FS_EKF_FILT,5
FS_EKF_THRESH,1
FS_GCS_ENABLE,0
FS_GCS_TIMEOUT,5
FS_OPTIONS,16
FS_THR_ENABLE,1
FS_THR_VALUE,975
FS_VIBE_ENABLE,1
FSTRATE_DIV,1
FSTRATE_ENABLE,0
GCS_PID_MASK,0
GND_EFFECT_COMP,1
GPS_AUTO_CONFIG,1
GPS_AUTO_SWITCH,1
GPS_DRV_OPTIONS,0
GPS_HDOP_GOOD,140
GPS_INJECT_TO,127
GPS_MIN_ELEV,-100
GPS_NAVFILTER,8
GPS_PRIMARY,0
GPS_RAW_DATA,0
GPS_SAVE_CFG,2
GPS_SBAS_MODE,2
GPS1_DELAY_MS,0
GPS1_GNSS_MODE,0
GPS1_POS_X,0
GPS1_POS_Y,0
GPS1_POS_Z,0
GPS1_RATE_MS,200
GPS1_TYPE,1
GPS2_TYPE,0
GUID_OPTIONS,0
GUID_TIMEOUT,3
INITIAL_MODE,0
INS_ACC_BODYFIX,2
INS_ACC_ID,3407882
INS_ACCEL_FILTER,10
INS_ACCOFFS_X,-0.015833
INS_ACCOFFS_Y,-0.0007024
INS_ACCOFFS_Z,0.0088857
INS_ACCSCAL_X,0.999705
INS_ACCSCAL_Y,0.9995401
INS_ACCSCAL_Z,0.9980302
INS_ENABLE_MASK,127
INS_FAST_SAMPLE,1
INS_GYR_CAL,1
INS_GYR_ID,3407882
INS_GYRO_FILTER,100
INS_GYRO_RATE,1
INS_GYROFFS_X,-0.0106094
INS_GYROFFS_Y,0.0041728
INS_GYROFFS_Z,-0.0059273
INS_HNTC2_ENABLE,0
INS_HNTCH_ENABLE,0
INS_LOG_BAT_CNT,1024
INS_LOG_BAT_LGCT,32
INS_LOG_BAT_LGIN,20
INS_LOG_BAT_MASK,1
INS_LOG_BAT_OPT,5
INS_POS1_X,0
INS_POS1_Y,0
INS_POS1_Z,0
INS_RAW_LOG_OPT,9
INS_STILL_THRESH,2.5
INS_TRIM_OPTION,1
INS_USE,1
LAND_ALT_LOW,1000
LAND_REPOSITION,1
LAND_SPEED,50
LAND_SPEED_HIGH,0
LGR_ENABLE,0
LOG_BACKEND_TYPE,4
LOG_BITMASK,2504413
LOG_BLK_RATEMAX,5
LOG_DARM_RATEMAX,0
LOG_DISARMED,0
LOG_FILE_BUFSIZE,16
LOG_FILE_DSRMROT,1
LOG_FILE_MB_FREE,16
LOG_FILE_RATEMAX,0
LOG_FILE_TIMEOUT,5
LOG_MAV_BUFSIZE,8
LOG_MAV_RATEMAX,0
LOG_MAX_FILES,500
LOG_REPLAY,0
LOIT_ACC_MAX,500
LOIT_ANG_MAX,0
LOIT_BRK_ACCEL,250
LOIT_BRK_DELAY,0.5
LOIT_BRK_JERK,500
LOIT_SPEED,1250
MAV_GCS_SYSID,255
MAV_OPTIONS,0
MAV_SYSID,1
MAV_TELEM_DELAY,0
MAV1_ADSB,0
MAV1_EXT_STAT,2
MAV1_EXTRA1,4
MAV1_EXTRA2,4
MAV1_EXTRA3,2
MAV1_OPTIONS,0
MAV1_PARAMS,0
MAV1_POSITION,2
MAV1_RAW_CTRL,0
MAV1_RAW_SENS,2
MAV1_RC_CHAN,2
MAV2_ADSB,0
MAV2_EXT_STAT,0
MAV2_EXTRA1,0
MAV2_EXTRA2,0
MAV2_EXTRA3,0
MAV2_OPTIONS,0
MAV2_PARAMS,0
MAV2_POSITION,0
MAV2_RAW_CTRL,0
MAV2_RAW_SENS,0
MAV2_RC_CHAN,0
MAV3_ADSB,0
MAV3_EXT_STAT,0
MAV3_EXTRA1,0
MAV3_EXTRA2,0
MAV3_EXTRA3,0
MAV3_OPTIONS,0
MAV3_PARAMS,0
MAV3_POSITION,0
MAV3_RAW_CTRL,0
MAV3_RAW_SENS,0
MAV3_RC_CHAN,0
MIS_OPTIONS,0
MIS_RESTART,0
MIS_TOTAL,1
MOT_BAT_CURR_MAX,0
MOT_BAT_CURR_TC,5
MOT_BAT_IDX,0
MOT_BAT_VOLT_MAX,16.8
MOT_BAT_VOLT_MIN,13.2
MOT_BOOST_SCALE,0
MOT_HOVER_LEARN,2
MOT_OPTIONS,0
MOT_PWM_MAX,2000
MOT_PWM_MIN,1000
MOT_PWM_TYPE,6
MOT_SAFE_DISARM,0
MOT_SAFE_TIME,1
MOT_SLEW_DN_TIME,0
MOT_SLEW_UP_TIME,0
MOT_SPIN_ARM,0.03
MOT_SPIN_MAX,0.9
MOT_SPIN_MIN,0.03
MOT_SPOOL_TIM_DN,0
MOT_SPOOL_TIME,0.05
MOT_THST_EXPO,0.49
MOT_THST_HOVER,0.1928777
MOT_YAW_HEADROOM,200
MSP_OPTIONS,4
MSP_OSD_NCELLS,0
NTF_BUZZ_ON_LVL,1
NTF_BUZZ_PIN,80
NTF_BUZZ_TYPES,1
NTF_BUZZ_VOLUME,100
NTF_LED_BRIGHT,3
NTF_LED_LEN,1
NTF_LED_OVERRIDE,0
NTF_LED_TYPES,122887
OSD_ARM_SCR,0
OSD_BTN_DELAY,300
OSD_CELL_COUNT,-1
OSD_CHAN,0
OSD_DSARM_SCR,0
OSD_FONT,0
OSD_FS_SCR,0
OSD_H_OFFSET,32
OSD_MSG_TIME,10
OSD_OPTIONS,1
OSD_SB_H_OFS,0
OSD_SB_V_EXT,0
OSD_SW_METHOD,0
OSD_TYPE,5
OSD_TYPE2,0
OSD_UNITS,0
OSD_V_OFFSET,16
OSD_W_ACRVOLT,3.6
OSD_W_AVGCELLV,3.6
OSD_W_BATVOLT,10
OSD_W_NSAT,9
OSD_W_RESTVOLT,10
OSD_W_RSSI,30
OSD1_ACRVOLT_EN,0
OSD1_ACRVOLT_X,24
OSD1_ACRVOLT_Y,4
OSD1_ALTITUDE_EN,1
OSD1_ALTITUDE_X,35
OSD1_ALTITUDE_Y,7
OSD1_ARMING_EN,1
OSD1_ARMING_X,16
OSD1_ARMING_Y,2
OSD1_ASPD1_EN,0
OSD1_ASPD1_X,0
OSD1_ASPD1_Y,0
OSD1_ASPD2_EN,0
OSD1_ASPD2_X,0
OSD1_ASPD2_Y,0
OSD1_ASPEED_EN,0
OSD1_ASPEED_X,2
OSD1_ASPEED_Y,13
OSD1_ATEMP_EN,0
OSD1_ATEMP_X,0
OSD1_ATEMP_Y,0
OSD1_AVGCELLV_EN,0
OSD1_AVGCELLV_X,24
OSD1_AVGCELLV_Y,3
OSD1_BAT_VOLT_EN,1
OSD1_BAT_VOLT_X,37
OSD1_BAT_VOLT_Y,3
OSD1_BAT2_VLT_EN,0
OSD1_BAT2_VLT_X,0
OSD1_BAT2_VLT_Y,0
OSD1_BAT2USED_EN,0
OSD1_BAT2USED_X,0
OSD1_BAT2USED_Y,0
OSD1_BATTBAR_EN,1
OSD1_BATTBAR_X,16
OSD1_BATTBAR_Y,2
OSD1_BATUSED_EN,1
OSD1_BATUSED_X,36
OSD1_BATUSED_Y,5
OSD1_BTEMP_EN,0
OSD1_BTEMP_X,0
OSD1_BTEMP_Y,0
OSD1_CELLVOLT_EN,1
OSD1_CELLVOLT_X,16
OSD1_CELLVOLT_Y,2
OSD1_CHAN_MAX,2100
OSD1_CHAN_MIN,900
OSD1_CLIMBEFF_EN,0
OSD1_CLIMBEFF_X,0
OSD1_CLIMBEFF_Y,0
OSD1_CLK_EN,0
OSD1_CLK_X,0
OSD1_CLK_Y,0
OSD1_COMPASS_EN,1
OSD1_COMPASS_X,26
OSD1_COMPASS_Y,6
OSD1_CRSSHAIR_EN,0
OSD1_CRSSHAIR_X,0
OSD1_CRSSHAIR_Y,0
OSD1_CURRENT_EN,1
OSD1_CURRENT_X,37
OSD1_CURRENT_Y,4
OSD1_CURRENT2_EN,0
OSD1_CURRENT2_X,0
OSD1_CURRENT2_Y,0
OSD1_DIST_EN,0
OSD1_DIST_X,22
OSD1_DIST_Y,11
OSD1_EFF_EN,0
OSD1_EFF_X,22
OSD1_EFF_Y,10
OSD1_ENABLE,1
OSD1_ESC_IDX,0
OSD1_ESCAMPS_EN,0
OSD1_ESCAMPS_X,24
OSD1_ESCAMPS_Y,14
OSD1_ESCRPM_EN,0
OSD1_ESCRPM_X,22
OSD1_ESCRPM_Y,12
OSD1_ESCTEMP_EN,0
OSD1_ESCTEMP_X,24
OSD1_ESCTEMP_Y,13
OSD1_FENCE_EN,0
OSD1_FENCE_X,14
OSD1_FENCE_Y,9
OSD1_FLTIME_EN,0
OSD1_FLTIME_X,23
OSD1_FLTIME_Y,10
OSD1_FLTMODE_EN,1
OSD1_FLTMODE_X,12
OSD1_FLTMODE_Y,10
OSD1_FONT,0
OSD1_GPSLAT_EN,1
OSD1_GPSLAT_X,19
OSD1_GPSLAT_Y,15
OSD1_GPSLONG_EN,1
OSD1_GPSLONG_X,19
OSD1_GPSLONG_Y,16
OSD1_GSPEED_EN,1
OSD1_GSPEED_X,12
OSD1_GSPEED_Y,9
OSD1_HDOP_EN,0
OSD1_HDOP_X,0
OSD1_HDOP_Y,0
OSD1_HEADING_EN,1
OSD1_HEADING_X,29
OSD1_HEADING_Y,2
OSD1_HOME_EN,1
OSD1_HOME_X,23
OSD1_HOME_Y,5
OSD1_HOMEDIR_EN,1
OSD1_HOMEDIR_X,16
OSD1_HOMEDIR_Y,2
OSD1_HOMEDIST_EN,1
OSD1_HOMEDIST_X,16
OSD1_HOMEDIST_Y,2
OSD1_HORIZON_EN,1
OSD1_HORIZON_X,26
OSD1_HORIZON_Y,10
OSD1_LINK_Q_EN,0
OSD1_LINK_Q_X,1
OSD1_LINK_Q_Y,1
OSD1_MESSAGE_EN,1
OSD1_MESSAGE_X,23
OSD1_MESSAGE_Y,12
OSD1_PITCH_EN,0
OSD1_PITCH_X,0
OSD1_PITCH_Y,0
OSD1_POWER_EN,1
OSD1_POWER_X,16
OSD1_POWER_Y,2
OSD1_RESTVOLT_EN,0
OSD1_RESTVOLT_X,24
OSD1_RESTVOLT_Y,2
OSD1_RNGF_EN,0
OSD1_RNGF_X,0
OSD1_RNGF_Y,0
OSD1_ROLL_EN,0
OSD1_ROLL_X,0
OSD1_ROLL_Y,0
OSD1_RPM_EN,0
OSD1_RPM_X,2
OSD1_RPM_Y,2
OSD1_RSSI_EN,1
OSD1_RSSI_X,16
OSD1_RSSI_Y,2
OSD1_SATS_EN,1
OSD1_SATS_X,14
OSD1_SATS_Y,5
OSD1_SIDEBARS_EN,0
OSD1_SIDEBARS_X,4
OSD1_SIDEBARS_Y,5
OSD1_STATS_EN,0
OSD1_STATS_X,0
OSD1_STATS_Y,0
OSD1_TEMP_EN,0
OSD1_TEMP_X,0
OSD1_TEMP_Y,0
OSD1_THROTTLE_EN,1
OSD1_THROTTLE_X,41
OSD1_THROTTLE_Y,12
OSD1_TXT_RES,0
OSD1_VSPEED_EN,1
OSD1_VSPEED_X,37
OSD1_VSPEED_Y,9
OSD1_VTX_PWR_EN,0
OSD1_VTX_PWR_X,0
OSD1_VTX_PWR_Y,0
OSD1_WAYPOINT_EN,0
OSD1_WAYPOINT_X,0
OSD1_WAYPOINT_Y,0
OSD1_WIND_EN,0
OSD1_WIND_X,2
OSD1_WIND_Y,12
OSD1_XTRACK_EN,0
OSD1_XTRACK_X,0
OSD1_XTRACK_Y,0
OSD2_ENABLE,0
OSD2_ESC_IDX,0
OSD2_FONT,0
OSD2_LINK_Q_EN,0
OSD2_LINK_Q_X,1
OSD2_LINK_Q_Y,1
OSD2_TXT_RES,0
OSD3_ENABLE,0
OSD3_ESC_IDX,0
OSD3_FONT,0
OSD3_LINK_Q_EN,0
OSD3_LINK_Q_X,1
OSD3_LINK_Q_Y,1
OSD3_TXT_RES,0
OSD4_ENABLE,0
OSD4_ESC_IDX,0
OSD4_FONT,0
OSD4_LINK_Q_EN,0
OSD4_LINK_Q_X,1
OSD4_LINK_Q_Y,1
OSD4_TXT_RES,0
OSD5_ENABLE,0
OSD6_ENABLE,0
PHLD_BRAKE_ANGLE,3000
PHLD_BRAKE_RATE,8
PILOT_ACCEL_Z,250
PILOT_SPEED_DN,0
PILOT_SPEED_UP,250
PILOT_THR_BHV,0
PILOT_THR_FILT,0
PILOT_TKOFF_ALT,0
PILOT_Y_EXPO,0.67
PILOT_Y_RATE,600
PILOT_Y_RATE_TC,0
PLDP_DELAY,0
PLDP_RNG_MAX,0
PLDP_SPEED_DN,0
PLDP_THRESH,0.9
PSC_ACCZ_D,0.001
PSC_ACCZ_D_FF,0
PSC_ACCZ_FF,0
PSC_ACCZ_FLTD,0
PSC_ACCZ_FLTE,20
PSC_ACCZ_FLTT,0
PSC_ACCZ_I,0.5
PSC_ACCZ_IMAX,800
PSC_ACCZ_P,0.2
PSC_ACCZ_PDMX,0
PSC_ACCZ_SMAX,0
PSC_ANGLE_MAX,0
PSC_JERK_XY,5
PSC_JERK_Z,5
PSC_POSXY_P,1.2
PSC_POSZ_P,1
PSC_VELXY_D,0.25
PSC_VELXY_FF,0
PSC_VELXY_FLTD,5
PSC_VELXY_FLTE,5
PSC_VELXY_I,0.75
PSC_VELXY_IMAX,1000
PSC_VELXY_P,0.65
PSC_VELZ_D,0
PSC_VELZ_FF,0
PSC_VELZ_FLTD,5
PSC_VELZ_FLTE,5
PSC_VELZ_I,0
PSC_VELZ_IMAX,1000
PSC_VELZ_P,7
RALLY_INCL_HOME,1
RALLY_LIMIT_KM,0.3
RALLY_TOTAL,0
RC_FS_TIMEOUT,1
RC_OPTIONS,32
RC_OVERRIDE_TIME,3
RC_PROTOCOLS,1
RC_SPEED,490
RC1_DZ,20
RC1_MAX,2000
RC1_MIN,993
RC1_OPTION,0
RC1_REVERSED,0
RC1_TRIM,1500
RC10_DZ,0
RC10_MAX,2000
RC10_MIN,999
RC10_OPTION,0
RC10_REVERSED,0
RC10_TRIM,2000
RC11_DZ,0
RC11_MAX,1900
RC11_MIN,1100
RC11_OPTION,0
RC11_REVERSED,0
RC11_TRIM,1500
RC12_DZ,0
RC12_MAX,1900
RC12_MIN,1100
RC12_OPTION,0
RC12_REVERSED,0
RC12_TRIM,1500
RC13_DZ,0
RC13_MAX,1900
RC13_MIN,1100
RC13_OPTION,0
RC13_REVERSED,0
RC13_TRIM,1500
RC14_DZ,0
RC14_MAX,1900
RC14_MIN,1100
RC14_OPTION,0
RC14_REVERSED,0
RC14_TRIM,1500
RC15_DZ,0
RC15_MAX,1900
RC15_MIN,1100
RC15_OPTION,0
RC15_REVERSED,0
RC15_TRIM,1500
RC16_DZ,0
RC16_MAX,1900
RC16_MIN,1100
RC16_OPTION,0
RC16_REVERSED,0
RC16_TRIM,1500
RC2_DZ,20
RC2_MAX,2011
RC2_MIN,994
RC2_OPTION,0
RC2_REVERSED,1
RC2_TRIM,1500
RC3_DZ,30
RC3_MAX,2010
RC3_MIN,993
RC3_OPTION,0
RC3_REVERSED,0
RC3_TRIM,994
RC4_DZ,20
RC4_MAX,1993
RC4_MIN,993
RC4_OPTION,0
RC4_REVERSED,0
RC4_TRIM,1500
RC5_DZ,0
RC5_MAX,2000
RC5_MIN,999
RC5_OPTION,154
RC5_REVERSED,0
RC5_TRIM,999
RC6_DZ,0
RC6_MAX,2000
RC6_MIN,999
RC6_OPTION,0
RC6_REVERSED,0
RC6_TRIM,999
RC7_DZ,0
RC7_MAX,2000
RC7_MIN,999
RC7_OPTION,0
RC7_REVERSED,0
RC7_TRIM,999
RC8_DZ,0
RC8_MAX,2000
RC8_MIN,999
RC8_OPTION,28
RC8_REVERSED,0
RC8_TRIM,999
RC9_DZ,0
RC9_MAX,2000
RC9_MIN,999
RC9_OPTION,0
RC9_REVERSED,0
RC9_TRIM,999
RCMAP_PITCH,2
RCMAP_ROLL,1
RCMAP_THROTTLE,3
RCMAP_YAW,4
RELAY1_DEFAULT,0
RELAY1_FUNCTION,1
RELAY1_INVERTED,0
RELAY1_PIN,82
RELAY2_FUNCTION,0
RELAY3_FUNCTION,0
RELAY4_FUNCTION,0
RELAY5_FUNCTION,0
RELAY6_FUNCTION,0
RNGFND_FILT,0.5
RNGFND1_TYPE,0
RNGFND2_TYPE,0
RNGFND3_TYPE,0
RNGFND4_TYPE,0
RNGFND5_TYPE,0
RNGFND6_TYPE,0
RNGFND7_TYPE,0
RNGFND8_TYPE,0
RNGFND9_TYPE,0
RNGFNDA_TYPE,0
RPM1_TYPE,0
RPM2_TYPE,0
RSSI_ANA_PIN,9
RSSI_CHAN_HIGH,2000
RSSI_CHAN_LOW,1000
RSSI_CHANNEL,0
RSSI_PIN_HIGH,5
RSSI_PIN_LOW,0
RSSI_TYPE,3
RTL_ALT,1500
RTL_ALT_FINAL,0
RTL_ALT_TYPE,0
RTL_CLIMB_MIN,0
RTL_CONE_SLOPE,3
RTL_LOIT_TIME,5000
RTL_OPTIONS,0
RTL_SPEED,0
SCHED_DEBUG,0
SCHED_LOOP_RATE,400
SCHED_OPTIONS,0
SERIAL_PASS1,0
SERIAL_PASS2,-1
SERIAL_PASSTIMO,15
SERIAL0_BAUD,115
SERIAL0_PROTOCOL,2
SERIAL1_BAUD,460
SERIAL1_OPTIONS,0
SERIAL1_PROTOCOL,2
SERIAL2_BAUD,57
SERIAL2_OPTIONS,0
SERIAL2_PROTOCOL,-1
SERIAL3_BAUD,115
SERIAL3_OPTIONS,0
SERIAL3_PROTOCOL,42
SERIAL4_BAUD,57
SERIAL4_OPTIONS,0
SERIAL4_PROTOCOL,2
SERIAL5_BAUD,57
SERIAL5_OPTIONS,0
SERIAL5_PROTOCOL,-1
SERIAL6_BAUD,230
SERIAL6_OPTIONS,0
SERIAL6_PROTOCOL,5
SERVO_BLH_3DMASK,0
SERVO_BLH_AUTO,1
SERVO_BLH_DEBUG,0
SERVO_BLH_MASK,15
SERVO_BLH_OTYPE,5
SERVO_BLH_POLES,14
SERVO_BLH_PORT,0
SERVO_BLH_RVMASK,0
SERVO_BLH_TEST,0
SERVO_BLH_TMOUT,0
SERVO_BLH_TRATE,10
SERVO_DSHOT_ESC,2
SERVO_DSHOT_RATE,0
SERVO_GPIO_MASK,0
SERVO_RATE,50
SERVO_RC_FS_MSK,0
SERVO1_FUNCTION,35
SERVO1_MAX,2000
SERVO1_MIN,1000
SERVO1_REVERSED,0
SERVO1_TRIM,1000
SERVO10_FUNCTION,0
SERVO10_MAX,1900
SERVO10_MIN,1100
SERVO10_REVERSED,0
SERVO10_TRIM,1500
SERVO11_FUNCTION,0
SERVO11_MAX,1900
SERVO11_MIN,1100
SERVO11_REVERSED,0
SERVO11_TRIM,1500
SERVO12_FUNCTION,0
SERVO12_MAX,1900
SERVO12_MIN,1100
SERVO12_REVERSED,0
SERVO12_TRIM,1500
SERVO13_FUNCTION,0
SERVO13_MAX,1900
SERVO13_MIN,1100
SERVO13_REVERSED,0
SERVO13_TRIM,1500
SERVO14_FUNCTION,0
SERVO14_MAX,1900
SERVO14_MIN,1100
SERVO14_REVERSED,0
SERVO14_TRIM,1500
SERVO15_FUNCTION,0
SERVO15_MAX,1900
SERVO15_MIN,1100
SERVO15_REVERSED,0
SERVO15_TRIM,1500
SERVO16_FUNCTION,0
SERVO16_MAX,1900
SERVO16_MIN,1100
SERVO16_REVERSED,0
SERVO16_TRIM,1500
SERVO2_FUNCTION,34
SERVO2_MAX,2000
SERVO2_MIN,1000
SERVO2_REVERSED,0
SERVO2_TRIM,1000
SERVO3_FUNCTION,33
SERVO3_MAX,2000
SERVO3_MIN,1000
SERVO3_REVERSED,0
SERVO3_TRIM,1000
SERVO4_FUNCTION,36
SERVO4_MAX,2000
SERVO4_MIN,1000
SERVO4_REVERSED,0
SERVO4_TRIM,1000
SERVO5_FUNCTION,0
SERVO5_MAX,2000
SERVO5_MIN,1000
SERVO5_REVERSED,0
SERVO5_TRIM,1000
SERVO6_FUNCTION,0
SERVO6_MAX,1900
SERVO6_MIN,1100
SERVO6_REVERSED,0
SERVO6_TRIM,1500
SERVO7_FUNCTION,0
SERVO7_MAX,1900
SERVO7_MIN,1100
SERVO7_REVERSED,0
SERVO7_TRIM,1500
SERVO8_FUNCTION,0
SERVO8_MAX,1900
SERVO8_MIN,1100
SERVO8_REVERSED,0
SERVO8_TRIM,1500
SERVO9_FUNCTION,0
SERVO9_MAX,1900
SERVO9_MIN,1100
SERVO9_REVERSED,0
SERVO9_TRIM,1500
SIMPLE,0
SRTL_ACCURACY,2
SRTL_OPTIONS,0
SRTL_POINTS,300
STAT_BOOTCNT,29
STAT_FLTTIME,641
STAT_RESET,1
STAT_RUNTIME,12429
SUPER_SIMPLE,0
SURFTRAK_MODE,1
SURFTRAK_TC,1
TCAL_ENABLED,0
THR_DZ,100
THROW_ALT_ACSND,3
THROW_ALT_DCSND,1
THROW_ALT_MAX,0
THROW_ALT_MIN,0
THROW_MOT_START,0
THROW_NEXTMODE,18
THROW_TYPE,0
TKOFF_RPM_MAX,0
TKOFF_RPM_MIN,0
TKOFF_SLEW_TIME,2
TKOFF_THR_MAX,0.9
TUNE,0
TUNE_MAX,0
TUNE_MIN,0
VTX_ENABLE,0
WP_NAVALT_MIN,0
WP_YAW_BEHAVIOR,2
WPNAV_ACCEL,250
WPNAV_ACCEL_C,0
WPNAV_ACCEL_Z,100
WPNAV_JERK,1
WPNAV_RADIUS,200
WPNAV_RFND_USE,1
WPNAV_SPEED,1000
WPNAV_SPEED_DN,150
WPNAV_SPEED_UP,250
WPNAV_TER_MARGIN,10