ardupilot/libraries/AP_HAL_ChibiOS/hwdef/f303-MatekGPS/hwdef-bl.dat
Andy Piper f9c5f9be00 AP_HAL_ChibiOS: make dshot DMA unlock event driven in order to allow unlocking from rcout thread
refactor rcout into separate thread and process all dshot requests there
move uart DMA completion to event model
process dshot locks in strick reverse order when unlocking
convert Shared_DMA to use mutexes
move UART transmit to a thread-per-uart
do blocking UART DMA transactions
do blocking dshot DMA transactions
trim stack sizes
cancel dma transactions on dshot when timeout occurs
support contention stats on blocking locking
move thread supression into chibios_hwdef.py
invalidate DMA bounce buffer correctly
separate UART initialisation into two halves
cleanup UART transaction timeouts
add @SYS/uarts.txt
move half-duplex handling to TX thread
correct thread statistics after use of ExpandingString
set unbuffered TX thread priority owner + 1
correctly unlock serial_led_send()
don't share IMU RX on KakuteF7Mini
observe dshot pulse time more accurately.
set TRBUFF bit for UART DMA transfers
deal with UART DMA timeouts correctly
don't deadlock on reverse ordered DMA locks
change PORT_INT_REQUIRED_STACK to 128
2021-02-20 14:37:11 +11:00

101 lines
2.1 KiB
Plaintext

# hw definition file f303 Matek CAN GPS
# MCU class and specific type
MCU STM32F303 STM32F303xC
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 26
# board ID for firmware load
APJ_BOARD_ID 1004
# setup build for a peripheral firmware
env AP_PERIPH 1
# crystal frequency
OSCILLATOR_HZ 8000000
define CH_CFG_ST_FREQUENCY 1000
# assume 256k flash part
FLASH_SIZE_KB 256
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# order of UARTs
SERIAL_ORDER
define HAL_USE_UART FALSE
PA4 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# USART1
PA9 USART1_TX USART1 SPEED_HIGH NODMA
PA10 USART1_RX USART1 SPEED_HIGH NODMA
# USART2
PA2 USART2_TX USART2 SPEED_HIGH NODMA
PA3 USART2_RX USART2 SPEED_HIGH NODMA
# USART3
PB10 USART3_TX USART3 SPEED_HIGH NODMA
PB11 USART3_RX USART3 SPEED_HIGH NODMA
define HAL_USE_SERIAL TRUE
define STM32_SERIAL_USE_USART1 TRUE
define STM32_SERIAL_USE_USART2 TRUE
define STM32_SERIAL_USE_USART3 FALSE
PA13 SWDIO-JTMS SWD
PA14 SWCLK-JTCK SWD
define HAL_NO_GPIO_IRQ
define CH_CFG_ST_TIMEDELTA 0
#define CH_CFG_USE_DYNAMIC FALSE
define SERIAL_BUFFERS_SIZE 32
define HAL_USE_EMPTY_IO TRUE
define PORT_INT_REQUIRED_STACK 64
define HAL_USE_RTC FALSE
define DISABLE_SERIAL_ESC_COMM TRUE
define NO_DATAFLASH TRUE
define DMA_RESERVE_SIZE 0
define PERIPH_FW TRUE
MAIN_STACK 0x800
PROCESS_STACK 0x800
define HAL_DISABLE_LOOP_DELAY
define HAL_USE_EMPTY_STORAGE 1
define HAL_STORAGE_SIZE 16384
# enable CAN support
PA11 CAN_RX CAN
PA12 CAN_TX CAN
define HAL_USE_CAN TRUE
define STM32_CAN_USE_CAN1 TRUE
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a small bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 1000
# use PB6 (normally I2C1_SCL) as "hold in bootloader" pin
# this has a hw pullup, so if we set it as input floating
# and look for it low then we know user has pulled it down and
# want to stay in the bootloader
PB6 STAY_IN_BOOTLOADER INPUT FLOATING
# reserve 256 bytes for comms between app and bootloader
RAM_RESERVE_START 256
# use DNA
define HAL_CAN_DEFAULT_NODE_ID 0
define CAN_APP_NODE_NAME "org.ardupilot.f303_MatekGPS"