mirror of https://github.com/ArduPilot/ardupilot
114 lines
2.0 KiB
Plaintext
114 lines
2.0 KiB
Plaintext
# hw definition file for processing by chibios_pins.py
|
|
|
|
AUTOBUILD_TARGETS None
|
|
|
|
# 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 1047
|
|
|
|
# setup build for a peripheral firmware
|
|
env AP_PERIPH 1
|
|
|
|
# enable watchdog
|
|
|
|
# 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 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
|
|
|
|
# enable CAN support
|
|
PD0 CAN1_RX CAN1
|
|
PD1 CAN1_TX CAN1
|
|
|
|
CAN_ORDER 1
|
|
|
|
define HAL_USE_ADC TRUE
|
|
define STM32_ADC_USE_ADC1 TRUE
|
|
PA4 VSENSE ADC1 SCALE(2)
|
|
|
|
define AP_PARAM_MAX_EMBEDDED_PARAM 512
|
|
|
|
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
|
|
|
|
# bootloader embedding / bootloader flashing not available
|
|
define AP_BOOTLOADER_FLASHING_ENABLED 0
|
|
|
|
define HAL_RCIN_THREAD_ENABLED 1
|