ardupilot/libraries/AP_HAL_ChibiOS/hwdef/AeroFox-PMU/hwdef-bl.inc

38 lines
688 B
PHP
Raw Normal View History

2022-09-27 00:16:51 -03:00
MCU STM32L431 STM32L431xx
APJ_BOARD_ID 1080
OSCILLATOR_HZ 8000000
env AP_PERIPH 1
FLASH_RESERVE_START_KB 0
FLASH_BOOTLOADER_LOAD_KB 36
FLASH_SIZE_KB 256
APP_START_OFFSET_KB 4
PB3 LED_BOOTLOADER OUTPUT LOW # blue
define HAL_LED_ON 0
PB8 CAN1_RX CAN1
PB9 CAN1_TX CAN1
# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW
CAN_ORDER 1
define BOOTLOADER_BAUDRATE 57600
define HAL_BOOTLOADER_TIMEOUT 1000
define HAL_USE_SERIAL FALSE
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
PA13 JTMS-SWDIO SWD
PA14 JTCK-SWCLK SWD