ardupilot/libraries/AP_HAL_ChibiOS/hwdef/mRoCANPWM-M10126/hwdef-bl.dat

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

83 lines
1.9 KiB
Plaintext
Raw Normal View History

###########################################################################################################################################################
# mRo CAN PWM breakout
# 12x PWM / IO 3V3 logic level
# Connector options: 90deg 0.1", straight or no headers.
# External power supply for servos in solder pads.
# 1x UART port exposed in solder pads.
# Blue LEd status indicator.
# Uncased Weight and Dimensions:
# Weight: ()
# Width: 33mm (.79in)
# Length: 31.3mm (1.34in)
# Screw hole pattern: 19x25mm
# M10126A - Initial release March 2023
###########################################################################################################################################################
MCU STM32G4xx STM32G474xx
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 32
# reserve some space for params
APP_START_OFFSET_KB 8
FLASH_SIZE_KB 512
# board ID for firmware load
APJ_BOARD_ID 1098
# setup build for a peripheral firmware
env AP_PERIPH 1
# debug on USART2
STDOUT_SERIAL SD1
STDOUT_BAUDRATE 57600
# crystal frequency
OSCILLATOR_HZ 8000000
#define CH_CFG_ST_FREQUENCY 1000000
# order of UARTs
SERIAL_ORDER USART1
# blue LED
PB10 LED_BOOTLOADER OUTPUT LOW
define HAL_LED_ON 1
# USART1
PB6 USART1_TX USART1
PB7 USART1_RX USART1
# 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 FALSE
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 DMA_RESERVE_SIZE 0
define HAL_DISABLE_LOOP_DELAY
# enable CAN support
PA11 CAN1_RX CAN1
PA12 CAN1_TX CAN1
#PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
# make bl baudrate match debug baudrate for easier debugging
define BOOTLOADER_BAUDRATE 57600
# use a smaller bootloader timeout
define HAL_BOOTLOADER_TIMEOUT 2500