HAL_ChibiOS: added Nucleo-L496 AP_Periph target
This commit is contained in:
parent
90bb0d6310
commit
6d093e56fb
92
libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat
Normal file
92
libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef-bl.dat
Normal file
@ -0,0 +1,92 @@
|
||||
# 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 1047
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# crystal frequency, no crystal for now
|
||||
OSCILLATOR_HZ 0
|
||||
|
||||
# assume 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
STDOUT_SERIAL SD1
|
||||
STDOUT_BAUDRATE 57600
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER OTG1 USART1
|
||||
|
||||
# a fault LED
|
||||
PB7 LED_BOOTLOADER OUTPUT LOW # blue
|
||||
define HAL_LED_ON 1
|
||||
|
||||
PB14 LED_RED OUTPUT LOW GPIO(1)
|
||||
|
||||
# USART1
|
||||
PA9 USART1_TX USART1 SPEED_HIGH NODMA
|
||||
PA10 USART1_RX USART1 SPEED_HIGH NODMA
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
define HAL_USE_SERIAL TRUE
|
||||
|
||||
define STM32_SERIAL_USE_USART1 TRUE
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
|
||||
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
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
# debugger support
|
||||
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
|
||||
|
||||
# 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.Nucleo-L496"
|
130
libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat
Normal file
130
libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L496/hwdef.dat
Normal file
@ -0,0 +1,130 @@
|
||||
# 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
|
||||
define STORAGE_FLASH_PAGE 18
|
||||
define HAL_STORAGE_SIZE 800
|
||||
|
||||
# board ID for firmware load
|
||||
APJ_BOARD_ID 1047
|
||||
|
||||
# setup build for a peripheral firmware
|
||||
env AP_PERIPH 1
|
||||
|
||||
# enable watchdog
|
||||
define HAL_WATCHDOG_ENABLED_DEFAULT true
|
||||
|
||||
# crystal frequency
|
||||
OSCILLATOR_HZ 0
|
||||
|
||||
# assume the 256k flash part
|
||||
FLASH_SIZE_KB 256
|
||||
|
||||
# order of UARTs
|
||||
SERIAL_ORDER OTG1 USART1
|
||||
|
||||
define HAL_CAN_POOL_SIZE 6000
|
||||
|
||||
#STDOUT_SERIAL SD1
|
||||
#STDOUT_BAUDRATE 57600
|
||||
|
||||
# USART1, telemetry
|
||||
PA9 USART1_TX USART1 SPEED_HIGH
|
||||
PA10 USART1_RX USART1 SPEED_HIGH
|
||||
|
||||
# USB
|
||||
PA11 OTG_FS_DM OTG1
|
||||
PA12 OTG_FS_DP OTG1
|
||||
|
||||
# LEDs
|
||||
PB7 LED OUTPUT LOW GPIO(1)
|
||||
|
||||
# a fault LED
|
||||
# PB14 LED_FAULT OUTPUT LOW # red
|
||||
|
||||
# spi bus for IMU
|
||||
PB13 SPI2_SCK SPI2
|
||||
PB14 SPI2_MISO SPI2
|
||||
PB15 SPI2_MOSI SPI2
|
||||
|
||||
PB12 IMU_CS CS
|
||||
|
||||
SPIDEV Invensensev2 SPI2 DEVID2 IMU_CS MODE3 2*MHZ 8*MHZ
|
||||
|
||||
# one I2C bus
|
||||
PB10 I2C2_SCL I2C2
|
||||
PB11 I2C2_SDA I2C2
|
||||
|
||||
I2C_ORDER I2C2
|
||||
|
||||
# allow for reboot command for faster development
|
||||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0
|
||||
|
||||
# debugger support
|
||||
PA13 JTMS-SWDIO SWD
|
||||
PA14 JTCK-SWCLK SWD
|
||||
|
||||
define HAL_NO_GPIO_IRQ
|
||||
define SERIAL_BUFFERS_SIZE 512
|
||||
|
||||
define NO_DATAFLASH TRUE
|
||||
|
||||
define DMA_RESERVE_SIZE 2048
|
||||
|
||||
define PERIPH_FW TRUE
|
||||
|
||||
# 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 0x800
|
||||
|
||||
define HAL_DISABLE_LOOP_DELAY
|
||||
|
||||
# enable CAN support
|
||||
PB8 CAN1_RX CAN1
|
||||
PB9 CAN1_TX CAN1
|
||||
|
||||
CAN_ORDER 1
|
||||
|
||||
define HAL_USE_ADC TRUE
|
||||
define STM32_ADC_USE_ADC1 TRUE
|
||||
PA4 VSENSE ADC1 SCALE(2)
|
||||
|
||||
define HAL_NO_GCS
|
||||
define HAL_NO_MONITOR_THREAD
|
||||
|
||||
define HAL_MINIMIZE_FEATURES 1
|
||||
|
||||
define HAL_BUILD_AP_PERIPH
|
||||
|
||||
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
||||
|
||||
# use the app descriptor needed by MissionPlanner for CAN upload
|
||||
env APP_DESCRIPTOR MissionPlanner
|
||||
|
||||
# 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.Nucleo-L496"
|
||||
|
||||
define HAL_PERIPH_ENABLE_GPS
|
||||
define HAL_PERIPH_ENABLE_MAG
|
||||
define HAL_PERIPH_ENABLE_BARO
|
||||
define HAL_PERIPH_ENABLE_AIRSPEED
|
||||
|
||||
BARO MS56XX SPI:ms5611
|
||||
BARO BMP388 I2C:0:0x76
|
||||
|
||||
# define HAL_SPI_CHECK_CLOCK_FREQ
|
Loading…
Reference in New Issue
Block a user