include ../MatekL431/hwdef.inc # enable GPS and compass define HAL_PERIPH_ENABLE_GPS define GPS_MAX_RATE_MS 200 define GPS_MAX_RECEIVERS 1 define GPS_MAX_INSTANCES 1 define HAL_PERIPH_GPS_PORT_DEFAULT 2 # allow for F9P GPS modules with moving baseline define GPS_MOVING_BASELINE 1 define HAL_PERIPH_ENABLE_MAG define HAL_PROBE_EXTERNAL_I2C_COMPASSES define HAL_COMPASS_MAX_SENSORS 1 SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 # QMC5883L for different board varients COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 # disable USART1 undef PB6 undef PB7 # enable GPS port with DMA undef PB10 undef PB11 PB10 USART3_TX USART3 SPEED_HIGH PB11 USART3_RX USART3 SPEED_HIGH # no ADC pins define HAL_USE_ADC FALSE # disable unnecessary threads define HAL_NO_MONITOR_THREAD define HAL_NO_RCOUT_THREAD define HAL_NO_TIMER_THREAD undef HAL_RCIN_THREAD_ENABLED define HAL_RCIN_THREAD_ENABLED 0 # maintain GPS port number compatibility with MatekL431-Periph SERIAL_ORDER EMPTY USART2 USART3 # larger CAN pool for RTCM data undef HAL_CAN_POOL_SIZE define HAL_CAN_POOL_SIZE 12000 # -------------------- MSP -------------------------------- define HAL_PERIPH_ENABLE_MSP define HAL_MSP_ENABLED 1 define AP_PERIPH_MSP_PORT_DEFAULT 1 undef PB10 undef PB11 PB10 USART3_TX USART3 SPEED_HIGH PB11 USART3_RX USART3 SPEED_HIGH