mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 01:18:29 -04:00
hwdef: added CarbonixL496 AP_Periph node
This commit is contained in:
parent
62b03bd1f1
commit
67649fe17d
74
libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat
Normal file
74
libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef-bl.dat
Normal file
@ -0,0 +1,74 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32L496 STM32L496xx
|
||||
|
||||
FLASH_RESERVE_START_KB 0
|
||||
FLASH_BOOTLOADER_LOAD_KB 36
|
||||
|
||||
# reserve some space for params
|
||||
APP_START_OFFSET_KB 4
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1053
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 12000000
|
||||
|
||||
# assume 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
STDOUT_SERIAL SD2
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER OTG1 USART2
|
||||
|
||||
# a fault LED
|
||||
PA13 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, disabled as PA13 used for LED
|
||||
# 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
|
||||
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496"
|
131
libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat
Normal file
131
libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat
Normal file
@ -0,0 +1,131 @@
|
||||
# hw definition file for processing by chibios_pins.py
|
||||
|
||||
# MCU class and specific type
|
||||
MCU STM32L496 STM32L496xx
|
||||
|
||||
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH)
|
||||
FLASH_RESERVE_START_KB 40
|
||||
|
||||
# store parameters in pages 18 and 19
|
||||
STORAGE_FLASH_PAGE 18
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1053
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# enable watchdog
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 12000000
|
||||
|
||||
# assume the 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER OTG1 USART2 USART3 UART4
|
||||
|
||||
define HAL_CAN_POOL_SIZE 6000
|
||||
|
||||
#STDOUT_SERIAL SD1
|
||||
#STDOUT_BAUDRATE 57600
|
||||
|
||||
|
||||
# PWM outputs
|
||||
PA9 TIM1_CH2 TIM1 PWM(1) GPIO(50)
|
||||
PA8 TIM1_CH1 TIM1 PWM(2) GPIO(51)
|
||||
PC6 TIM3_CH1 TIM3 PWM(3) GPIO(52) # LED
|
||||
|
||||
# USART2
|
||||
PA2 USART2_TX USART2 SPEED_HIGH NODMA
|
||||
PA3 USART2_RX USART2 SPEED_HIGH NODMA
|
||||
|
||||
# USART3
|
||||
PC4 USART3_TX USART3 SPEED_HIGH NODMA
|
||||
PC5 USART3_RX USART3 SPEED_HIGH NODMA
|
||||
|
||||
# UART4
|
||||
PA0 UART4_TX UART4 SPEED_HIGH NODMA
|
||||
PA1 UART4_RX UART4 SPEED_HIGH NODMA
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# LED, active low
|
||||
PA13 LED OUTPUT HIGH GPIO(1)
|
||||
|
||||
# spi2
|
||||
PB10 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
# CS pins
|
||||
PC8 BMI088_A_CS CS
|
||||
PC9 BMI088_G_CS CS
|
||||
|
||||
SPIDEV bmi088_g SPI2 DEVID1 BMI088_G_CS MODE3 10*MHZ 10*MHZ
|
||||
SPIDEV bmi088_a SPI2 DEVID2 BMI088_A_CS MODE3 10*MHZ 10*MHZ
|
||||
|
||||
# one I2C bus
|
||||
PB6 I2C4_SCL I2C4
|
||||
PB7 I2C4_SDA I2C4
|
||||
|
||||
I2C_ORDER I2C4
|
||||
|
||||
# allow for reboot command for faster development
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
# debugger support (disabled as conflicts with LED)
|
||||
#PA13 JTMS-SWDIO SWD
|
||||
#PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
|
||||
define DMA_RESERVE_SIZE 2048
|
||||
|
||||
# stack for fast interrupts
|
||||
define PORT_INT_REQUIRED_STACK 64
|
||||
|
||||
# MAIN_STACK is stack for ISR handlers
|
||||
MAIN_STACK 0x300
|
||||
|
||||
# PROCESS_STACK controls stack for main thread
|
||||
PROCESS_STACK 0xA00
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
# ADC inputs
|
||||
define HAL_USE_ADC TRUE
|
||||
define STM32_ADC_USE_ADC1 TRUE
|
||||
|
||||
PA4 VSENSE1 ADC1 SCALE(1)
|
||||
PA5 VSENSE2 ADC1 SCALE(1)
|
||||
PA6 VSENSE3 ADC1 SCALE(1)
|
||||
PB1 VSENSE4 ADC1 SCALE(1)
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
define CAN_APP_NODE_NAME "org.ardupilot.CarbonixL496"
|
||||
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_ENABLE_RC_OUT
|
||||
|
||||
BARO MS56XX I2C:0:0x76
|
||||
COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE
|
||||
|
||||
|
||||
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user