2019-10-19 06:43:37 -03:00
|
|
|
# hw definition file for Zubax GNSS
|
|
|
|
|
|
|
|
# MCU class and specific type
|
|
|
|
MCU STM32F105 STM32F105xC
|
|
|
|
|
|
|
|
define STM32F107_MCUCONF
|
|
|
|
|
|
|
|
FLASH_RESERVE_START_KB 0
|
|
|
|
FLASH_BOOTLOADER_LOAD_KB 34
|
|
|
|
|
|
|
|
# board ID for firmware load
|
2020-01-14 22:56:00 -04:00
|
|
|
APJ_BOARD_ID 1005
|
2019-10-19 06:43:37 -03:00
|
|
|
|
|
|
|
# setup build for a peripheral firmware
|
|
|
|
env AP_PERIPH 1
|
|
|
|
|
|
|
|
define HAL_BOARD_AP_PERIPH_ZUBAXGNSS
|
|
|
|
|
|
|
|
# crystal frequency
|
|
|
|
OSCILLATOR_HZ 16000000
|
|
|
|
|
|
|
|
define CH_CFG_ST_FREQUENCY 1000
|
|
|
|
|
|
|
|
FLASH_SIZE_KB 256
|
|
|
|
|
2022-01-12 04:14:38 -04:00
|
|
|
# store parameters in last 2 pages
|
|
|
|
define HAL_STORAGE_SIZE 800
|
2019-10-21 00:48:39 -03:00
|
|
|
|
2019-10-19 06:43:37 -03:00
|
|
|
# USART3 for debug
|
2019-10-19 17:04:56 -03:00
|
|
|
#STDOUT_SERIAL SD3
|
|
|
|
#STDOUT_BAUDRATE 115200
|
2019-10-19 06:43:37 -03:00
|
|
|
|
|
|
|
# USART3 for debug
|
|
|
|
PB10 USART3_TX USART3 SPEED_HIGH NODMA
|
|
|
|
PB11 USART3_RX USART3 SPEED_HIGH NODMA
|
|
|
|
|
|
|
|
|
|
|
|
PB7 PERIPH_RESET OUTPUT HIGH
|
|
|
|
|
|
|
|
#PC1 HWID_BIT0 INPUT
|
|
|
|
#PC2 HWID_BIT1_INV INPUT
|
|
|
|
#PC3 HWID_BIT2 INPUT
|
|
|
|
|
|
|
|
PB3 LED_BOOTLOADER OUTPUT
|
|
|
|
PB5 LED_CAN1 OUTPUT
|
|
|
|
PB4 LED_CAN2 OUTPUT
|
|
|
|
define HAL_LED_ON 1
|
|
|
|
|
|
|
|
# don't enable DMA in UART driver
|
|
|
|
define HAL_UART_NODMA
|
|
|
|
|
|
|
|
# enable CAN support
|
|
|
|
PA11 CAN_RX CAN
|
|
|
|
PB9 CAN_TX CAN
|
2020-08-27 12:00:22 -03:00
|
|
|
|
|
|
|
|
2019-10-19 06:43:37 -03:00
|
|
|
|
|
|
|
# no I2C buses
|
|
|
|
# I2C_ORDER
|
|
|
|
|
|
|
|
define HAL_USE_ADC FALSE
|
|
|
|
define STM32_ADC_USE_ADC1 FALSE
|
|
|
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
|
|
|
|
|
|
|
define HAL_NO_GPIO_IRQ
|
|
|
|
|
|
|
|
define CH_CFG_ST_TIMEDELTA 0
|
|
|
|
define SERIAL_BUFFERS_SIZE 512
|
|
|
|
define HAL_USE_EMPTY_IO TRUE
|
|
|
|
define PORT_INT_REQUIRED_STACK 64
|
|
|
|
|
|
|
|
# avoid timer and RCIN threads to save memory
|
|
|
|
define HAL_NO_TIMER_THREAD
|
|
|
|
|
|
|
|
#defined to turn off undef warnings
|
|
|
|
define __FPU_PRESENT 0
|
|
|
|
|
|
|
|
|
|
|
|
define DMA_RESERVE_SIZE 0
|
|
|
|
|
|
|
|
MAIN_STACK 0x100
|
|
|
|
PROCESS_STACK 0x600
|
|
|
|
|
|
|
|
define HAL_UART_MIN_TX_SIZE 256
|
|
|
|
define HAL_UART_MIN_RX_SIZE 128
|
|
|
|
|
|
|
|
define HAL_UART_STACK_SIZE 256
|
|
|
|
define STORAGE_THD_WA_SIZE 512
|
|
|
|
|
|
|
|
define HAL_NO_MONITOR_THREAD
|
|
|
|
|
|
|
|
define HAL_DEVICE_THREAD_STACK 768
|
|
|
|
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 0
|
|
|
|
|
|
|
|
# USART2 for GPS
|
2019-10-19 17:04:56 -03:00
|
|
|
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
2019-10-19 06:43:37 -03:00
|
|
|
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
|
|
|
|
2020-04-24 08:10:08 -03:00
|
|
|
SERIAL_ORDER
|
2019-10-19 06:43:37 -03:00
|
|
|
|
2020-03-09 19:54:59 -03:00
|
|
|
# Add CS pins to ensure they are high in bootloader
|
|
|
|
PA15 BARO_CS CS
|
|
|
|
PD2 MAG_CS CS
|
2020-08-27 12:00:22 -03:00
|
|
|
|
|
|
|
# reduce the number of CAN RX Buffer
|
|
|
|
define HAL_CAN_RX_QUEUE_SIZE 32
|