ardupilot/libraries/AP_HAL_ChibiOS/hwdef/Nucleo-L476/hwdef.dat
Andrew Tridgell 822e657a70 HAL_ChibiOS: increase PROCESS_STACK on several boards
use min of 0xA00 for AP_Periph. A larger stack is needed for parameter
fetching
2021-10-20 19:06:35 +11:00

124 lines
2.4 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32L476 STM32L476xx
# 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 1051
# 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 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
# status LED
PA5 LED OUTPUT LOW GPIO(1)
define HAL_LED_ON 1
# spi bus for IMU
PB13 SPI2_SCK SPI2
PB14 SPI2_MISO SPI2
PB15 SPI2_MOSI SPI2
# one I2C bus. Pullups added to avoid having to add pullup resistors.
# on production boards correct pullups are needed (between 1k and 2k Ohm)
# and the pullup keyword omitted to use open drain
PB10 I2C2_SCL I2C2 PULLUP
PB11 I2C2_SDA I2C2 PULLUP
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 0xA00
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 0
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-L476"
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_GPS_PORT_DEFAULT 0
define HAL_PERIPH_ENABLE_MAG
define HAL_PROBE_EXTERNAL_I2C_COMPASSES
define HAL_I2C_INTERNAL_MASK 0
define HAL_PERIPH_ENABLE_BARO
define HAL_PERIPH_ENABLE_AIRSPEED