mirror of https://github.com/ArduPilot/ardupilot
72 lines
1.3 KiB
Plaintext
72 lines
1.3 KiB
Plaintext
|
# hw definition file for processing by chibios_pins.py
|
||
|
|
||
|
# MCU class and specific type
|
||
|
MCU STM32F4xx STM32F405xx
|
||
|
|
||
|
FLASH_RESERVE_START_KB 0
|
||
|
FLASH_BOOTLOADER_LOAD_KB 60
|
||
|
|
||
|
# reserve some space for params
|
||
|
APP_START_OFFSET_KB 4
|
||
|
|
||
|
# board ID for firmware load
|
||
|
APJ_BOARD_ID 1064
|
||
|
|
||
|
# setup build for a peripheral firmware
|
||
|
env AP_PERIPH 1
|
||
|
|
||
|
# crystal frequency set to 0 to use internal clock
|
||
|
OSCILLATOR_HZ 0
|
||
|
|
||
|
# assume 1024K flash part
|
||
|
FLASH_SIZE_KB 1024
|
||
|
|
||
|
STDOUT_SERIAL SD2
|
||
|
STDOUT_BAUDRATE 57600
|
||
|
|
||
|
# order of UARTs
|
||
|
SERIAL_ORDER OTG1 USART2
|
||
|
|
||
|
# a fault LED
|
||
|
PA15 LED_BOOTLOADER OUTPUT HIGH # blue
|
||
|
define HAL_LED_ON 0
|
||
|
|
||
|
# USART1
|
||
|
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
||
|
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||
|
|
||
|
# USB
|
||
|
PA11 OTG_FS_DM OTG1
|
||
|
PA12 OTG_FS_DP OTG1
|
||
|
|
||
|
define HAL_USE_SERIAL TRUE
|
||
|
|
||
|
define STM32_SERIAL_USE_USART2 TRUE
|
||
|
|
||
|
define HAL_NO_GPIO_IRQ
|
||
|
|
||
|
define SERIAL_BUFFERS_SIZE 32
|
||
|
define HAL_USE_EMPTY_IO TRUE
|
||
|
define PORT_INT_REQUIRED_STACK 64
|
||
|
|
||
|
define DMA_RESERVE_SIZE 0
|
||
|
|
||
|
MAIN_STACK 0x800
|
||
|
PROCESS_STACK 0x800
|
||
|
|
||
|
define HAL_DISABLE_LOOP_DELAY
|
||
|
|
||
|
# enable CAN support
|
||
|
PB8 CAN1_RX CAN1
|
||
|
PB9 CAN1_TX CAN1
|
||
|
|
||
|
# debugger support
|
||
|
PA13 JTMS-SWDIO SWD
|
||
|
PA14 JTCK-SWCLK SWD
|
||
|
|
||
|
# make bl baudrate match debug baudrate for easier debugging
|
||
|
define BOOTLOADER_BAUDRATE 57600
|
||
|
|
||
|
# use a small bootloader timeout
|
||
|
define HAL_BOOTLOADER_TIMEOUT 1000
|