ardupilot/libraries/AP_HAL_ChibiOS/hwdef/CarbonixL496/hwdef.dat

149 lines
2.8 KiB
Plaintext

# 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 set to 0 to use internal clock
OSCILLATOR_HZ 0
# 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, ESC telem
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
PA15 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
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 AP_STATS_ENABLED 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
# enable ESC control
define HAL_SUPPORT_RCOUT_SERIAL 1
define HAL_WITH_ESC_TELEM 1
# enable GPS
define HAL_PERIPH_ENABLE_GPS
define HAL_PERIPH_GPS_PORT_DEFAULT 2
#define HAL_PERIPH_ENABLE_NOTIFY
#define HAL_PERIPH_ENABLE_NCP5623_LED_WITHOUT_NOTIFY
# default ADSB off by setting 0 baudrate
define HAL_PERIPH_ENABLE_ADSB
define HAL_PERIPH_ADSB_PORT_DEFAULT 3
define HAL_PERIPH_ADSB_BAUD_DEFAULT 57600
BARO MS56XX I2C:0:0x76
COMPASS MMC5XX3 I2C:0:0x30 false ROTATION_NONE