# hw definition file for processing by chibios_pins.py # MCU class and specific type MCU STM32F4xx STM32F412Rx FLASH_RESERVE_START_KB 0 # two sectors for bootloader, two for storage FLASH_BOOTLOADER_LOAD_KB 64 # board ID for firmware load APJ_BOARD_ID 1001 # setup build for a peripheral firmware env AP_PERIPH 1 # crystal frequency OSCILLATOR_HZ 16000000 define CH_CFG_ST_FREQUENCY 1000000 # assume 512k flash part FLASH_SIZE_KB 512 STDOUT_SERIAL SD1 STDOUT_BAUDRATE 57600 # order of UARTs SERIAL_ORDER # use safety button to stay in bootloader PB3 STAY_IN_BOOTLOADER INPUT PULLDOWN define HAL_STAY_IN_BOOTLOADER_VALUE 1 PB12 LED_BOOTLOADER OUTPUT LOW define HAL_LED_ON 1 # USART1 PB6 USART1_TX USART1 PB7 USART1_RX USART1 # USART2 PA2 USART2_TX USART2 PA3 USART2_RX USART2 # SWD debugging PA13 JTMS-SWDIO SWD PA14 JTCK-SWCLK SWD define HAL_USE_SERIAL TRUE define STM32_SERIAL_USE_USART1 TRUE define STM32_SERIAL_USE_USART2 TRUE define STM32_SERIAL_USE_USART3 FALSE define HAL_NO_GPIO_IRQ define HAL_USE_EMPTY_IO TRUE # avoid timer and RCIN threads to save memory define HAL_NO_TIMER_THREAD define HAL_NO_RCIN_THREAD define HAL_USE_RTC FALSE define DISABLE_SERIAL_ESC_COMM TRUE define NO_DATAFLASH TRUE define DMA_RESERVE_SIZE 0 define PERIPH_FW TRUE define HAL_DISABLE_LOOP_DELAY define HAL_USE_EMPTY_STORAGE 1 define HAL_STORAGE_SIZE 16384 # enable CAN support PB8 CAN1_RX CAN1 PB9 CAN1_TX CAN1 PB5 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW define HAL_USE_CAN TRUE define STM32_CAN_USE_CAN1 TRUE define CAN_APP_NODE_NAME "org.ardupilot.cuav_gps" # use DNA define HAL_CAN_DEFAULT_NODE_ID 0 # make bl baudrate match debug baudrate for easier debugging define BOOTLOADER_BAUDRATE 57600 # use a small bootloader timeout define HAL_BOOTLOADER_TIMEOUT 1000 # reserve 256 bytes for comms between app and bootloader RAM_RESERVE_START 256 # Add CS pins to ensure they are high in bootloader PA4 MAG_CS CS PA10 MS5611_CS CS