diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat new file mode 100644 index 0000000000000..04f1494a272ab --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef-bl.dat @@ -0,0 +1,2 @@ +include ../TBS-L431/hwdef-bl.inc + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat new file mode 100644 index 0000000000000..4f184a84c002d --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431-Airspeed/hwdef.dat @@ -0,0 +1,24 @@ +include ../TBS-L431/hwdef.inc + +USE_BOOTLOADER_FROM_BOARD TBS-L431-Periph + +define HAL_USE_ADC FALSE +define STM32_ADC_USE_ADC1 FALSE +define HAL_DISABLE_ADC_DRIVER TRUE + +# ---------------------- I2C bus ------------------------ +I2C_ORDER I2C1 + +PA9 I2C1_SCL I2C1 +PA10 I2C1_SDA I2C1 + +define HAL_I2C_CLEAR_ON_TIMEOUT 0 +define HAL_I2C_INTERNAL_MASK 1 + +# ------------------ I2C airspeed ------------------------- +define HAL_PERIPH_ENABLE_AIRSPEED + +# 10" DLVR sensor by default +define HAL_AIRSPEED_TYPE_DEFAULT 9 +define AIRSPEED_MAX_SENSORS 1 + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc new file mode 100644 index 0000000000000..84c91b4054935 --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef-bl.inc @@ -0,0 +1,61 @@ +# hw definition file Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# crystal frequency +OSCILLATOR_HZ 0 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_L431_PERIPH + +# setup build for a peripheral firmware +env AP_PERIPH 1 + +FLASH_RESERVE_START_KB 0 +FLASH_BOOTLOADER_LOAD_KB 36 +FLASH_SIZE_KB 256 + +# reserve some space for params +APP_START_OFFSET_KB 4 + +# --------------------------------------------- +PB3 LED_BOOTLOADER OUTPUT LOW # blue +define HAL_LED_ON 0 + +# enable CAN support +#PB8 CAN1_RX CAN1 +#PB9 CAN1_TX CAN1 +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +CAN_ORDER 1 + +# --------------------------------------------- + +# make bl baudrate match debug baudrate for easier debugging +define BOOTLOADER_BAUDRATE 57600 + +# use a small bootloader timeout +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 + +# Add CS pins to ensure they are high in bootloader +PA4 MAG_CS CS +PB2 SPARE_CS CS + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + diff --git a/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc new file mode 100644 index 0000000000000..1016f0eece5be --- /dev/null +++ b/libraries/AP_HAL_ChibiOS/hwdef/TBS-L431/hwdef.inc @@ -0,0 +1,77 @@ +# hw definition file for Matek L431 CAN node + +# MCU class and specific type +MCU STM32L431 STM32L431xx + +# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) +FLASH_RESERVE_START_KB 40 +FLASH_SIZE_KB 256 + +# store parameters in pages 18 and 19 +STORAGE_FLASH_PAGE 18 +define HAL_STORAGE_SIZE 800 + +# ChibiOS system timer +STM32_ST_USE_TIMER 15 +define CH_CFG_ST_RESOLUTION 16 + +# board ID for firmware load +APJ_BOARD_ID AP_HW_TBS_L431_PERIPH + +# crystal frequency +#OSCILLATOR_HZ 8000000 +OSCILLATOR_HZ 0 + +env AP_PERIPH 1 + +STDOUT_SERIAL SD1 +STDOUT_BAUDRATE 57600 + +define HAL_NO_GPIO_IRQ +define SERIAL_BUFFERS_SIZE 512 +define PORT_INT_REQUIRED_STACK 64 + +define DMA_RESERVE_SIZE 0 + +# MAIN_STACK is stack for ISR handlers +MAIN_STACK 0x300 + +# PROCESS_STACK controls stack for main thread +PROCESS_STACK 0xA00 + +# we setup a small defaults.parm +define AP_PARAM_MAX_EMBEDDED_PARAM 512 + +# blue LED0 marked as ACT +PB3 LED OUTPUT HIGH +define HAL_LED_ON 1 + +# debugger support +PA13 JTMS-SWDIO SWD +PA14 JTCK-SWCLK SWD + +# ---------------------- CAN bus ------------------------- +CAN_ORDER 1 + +PA11 CAN1_RX CAN1 +PA12 CAN1_TX CAN1 +# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW + +define HAL_CAN_POOL_SIZE 6000 + +# ---------------------- UARTs --------------------------- +# | sr0 | MSP | GPS | +SERIAL_ORDER USART1 + +# USART1 for debug +PB6 USART1_TX USART1 SPEED_HIGH +PB7 USART1_RX USART1 SPEED_HIGH + +# allow for reboot command for faster development +define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 + +# keep ROMFS uncompressed as we don't have enough RAM +# to uncompress the bootloader at runtime +env ROMFS_UNCOMPRESSED True + +define HAL_RCIN_THREAD_ENABLED 1