# hw definition file for Zubax GNSS # MCU class and specific type MCU STM32F105 STM32F105xC define STM32F107_MCUCONF define HAL_BOARD_AP_PERIPH_ZUBAXGNSS # bootloader starts firmware at 34k FLASH_RESERVE_START_KB 34 # store parameters in last 2 pages STORAGE_FLASH_PAGE 126 define HAL_STORAGE_SIZE 800 # board ID for firmware load APJ_BOARD_ID 1005 # setup build for a peripheral firmware env AP_PERIPH 1 # crystal frequency OSCILLATOR_HZ 16000000 define CH_CFG_ST_FREQUENCY 1000 FLASH_SIZE_KB 256 # USART3 for debug STDOUT_SERIAL SD3 STDOUT_BAUDRATE 115200 # enable pin for GPS PB7 GPS_ENABLE OUTPUT HIGH PA15 BARO_CS CS PD2 MAG_CS CS PB6 MAG_DRDY INPUT PC1 HWID_BIT0 INPUT PC2 HWID_BIT1_INV INPUT PC3 HWID_BIT2 INPUT PB3 LED OUTPUT PB5 LED_CAN1 OUTPUT PB4 LED_CAN2 OUTPUT # USART2 for GPS PA2 USART2_TX USART2 SPEED_HIGH NODMA PA3 USART2_RX USART2 SPEED_HIGH NODMA # USART3 for debug PB10 USART3_TX USART3 SPEED_HIGH NODMA PB11 USART3_RX USART3 SPEED_HIGH NODMA # PA13 XPA13 OUTPUT HIGH # PA1 XPA1 INPUT FLOATING # don't enable DMA in UART driver define HAL_UART_NODMA # enable watchdog # enable CAN support PA11 CAN_RX CAN PB9 CAN_TX CAN # no I2C buses # I2C_ORDER # spi bus for baro/mag PC10 SPI3_SCK SPI3 SPEED_HIGH PC11 SPI3_MISO SPI3 SPEED_HIGH PC12 SPI3_MOSI SPI3 SPEED_HIGH ######################### # order of UARTs SERIAL_ORDER USART3 EMPTY EMPTY USART2 SPIDEV ms5611 SPI3 DEVID1 BARO_CS MODE3 8*MHZ 8*MHZ SPIDEV lis3mdl SPI3 DEVID2 MAG_CS MODE3 500*KHZ 500*KHZ 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 PORT_INT_REQUIRED_STACK 64 #defined to turn off undef warnings define __FPU_PRESENT 0 define HAL_USE_RTC FALSE define DMA_RESERVE_SIZE 0 MAIN_STACK 0x200 PROCESS_STACK 0xA00 define HAL_USE_I2C TRUE define STM32_I2C_USE_I2C1 TRUE 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_I2C_CLEAR_ON_TIMEOUT 0 define HAL_DEVICE_THREAD_STACK 768 define AP_PARAM_MAX_EMBEDDED_PARAM 0 define HAL_I2C_INTERNAL_MASK 0 # LIS3MDL compass COMPASS LIS3MDL SPI:lis3mdl false ROTATION_YAW_270 # MS5611 baro BARO MS56XX SPI:ms5611 define HAL_BARO_ALLOW_INIT_NO_BARO define HAL_PERIPH_ENABLE_GPS define HAL_PERIPH_ENABLE_MAG define HAL_PERIPH_ENABLE_BARO # reduce the number of CAN RX Buffer define HAL_CAN_RX_QUEUE_SIZE 32