forked from ArduPilot/ardupilot
-
Notifications
You must be signed in to change notification settings - Fork 0
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
AP_HAL_ChibiOS: add MatekL431 AP_Periph hwdef
- Loading branch information
1 parent
994e1e0
commit 35ed87a
Showing
6 changed files
with
292 additions
and
0 deletions.
There are no files selected for viewing
3 changes: 3 additions & 0 deletions
3
libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef-bl.dat
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
include ../MatekL431/hwdef-bl.inc | ||
|
||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" |
15 changes: 15 additions & 0 deletions
15
libraries/AP_HAL_ChibiOS/hwdef/MatekL431-Airspeed/hwdef.dat
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,15 @@ | ||
include ../MatekL431/hwdef.inc | ||
|
||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Airspeed" | ||
|
||
define HAL_USE_ADC FALSE | ||
define STM32_ADC_USE_ADC1 FALSE | ||
define HAL_DISABLE_ADC_DRIVER TRUE | ||
|
||
# ------------------ I2C airspeed ------------------------- | ||
define HAL_PERIPH_ENABLE_AIRSPEED | ||
|
||
# 10" DLVR sensor by default | ||
define HAL_AIRSPEED_TYPE_DEFAULT 9 | ||
define AIRSPEED_MAX_SENSORS 1 | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,3 @@ | ||
include ../MatekL431/hwdef-bl.inc | ||
|
||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,85 @@ | ||
include ../MatekL431/hwdef.inc | ||
|
||
define CAN_APP_NODE_NAME "org.ardupilot.MatekL431-Periph" | ||
|
||
|
||
# --------------------- PWM ----------------------- | ||
PA8 TIM1_CH1 TIM1 PWM(1) GPIO(50) | ||
PA9 TIM1_CH2 TIM1 PWM(2) GPIO(51) | ||
PA10 TIM1_CH3 TIM1 PWM(3) GPIO(52) | ||
PA11 TIM1_CH4 TIM1 PWM(4) GPIO(53) | ||
PA15 TIM2_CH1 TIM2 PWM(5) GPIO(54) | ||
|
||
# Beeper | ||
PA6 TIM16_CH1 TIM16 GPIO(32) ALARM | ||
|
||
# ----------------------- GPS ---------------------------- | ||
define HAL_PERIPH_ENABLE_GPS | ||
define GPS_MAX_RATE_MS 200 | ||
|
||
define GPS_MAX_RECEIVERS 1 | ||
define GPS_MAX_INSTANCES 1 | ||
|
||
define HAL_PERIPH_GPS_PORT_DEFAULT 2 | ||
|
||
|
||
# ---------------------- COMPASS --------------------------- | ||
define HAL_PERIPH_ENABLE_MAG | ||
|
||
SPIDEV rm3100 SPI1 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ | ||
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 | ||
|
||
define HAL_COMPASS_MAX_SENSORS 1 | ||
|
||
# added QMC5883L for different board varients | ||
COMPASS QMC5883L I2C:0:0xd false ROTATION_PITCH_180_YAW_90 | ||
|
||
|
||
# --------------------- Barometer --------------------------- | ||
define HAL_PERIPH_ENABLE_BARO | ||
define HAL_BARO_ALLOW_INIT_NO_BARO | ||
|
||
BARO SPL06 I2C:0:0x76 | ||
|
||
# ------------------ I2C airspeed ------------------------- | ||
define HAL_PERIPH_ENABLE_AIRSPEED | ||
|
||
# MS4525 sensor by default | ||
define HAL_AIRSPEED_TYPE_DEFAULT 1 | ||
define AIRSPEED_MAX_SENSORS 1 | ||
|
||
# -------------------- MSP -------------------------------- | ||
define HAL_PERIPH_ENABLE_MSP | ||
define HAL_MSP_ENABLED 1 | ||
define AP_PERIPH_MSP_PORT_DEFAULT 1 | ||
|
||
# ------------------ BATTERY Monitor ----------------------- | ||
define HAL_PERIPH_ENABLE_BATTERY | ||
|
||
define HAL_USE_ADC TRUE | ||
define STM32_ADC_USE_ADC1 TRUE | ||
|
||
PA0 BATT_VOLTAGE_SENS ADC1 SCALE(1) | ||
PA1 BATT_CURRENT_SENS ADC1 SCALE(1) | ||
|
||
define HAL_BATT_MONITOR_DEFAULT 0 | ||
define HAL_BATT_VOLT_PIN 5 | ||
define HAL_BATT_VOLT_SCALE 21.0 | ||
define HAL_BATT_CURR_PIN 6 | ||
define HAL_BATT_CURR_SCALE 40.0 | ||
|
||
|
||
PB0 BATT2_VOLTAGE_SENS ADC1 SCALE(1) | ||
PB1 BATT2_CURRENT_SENS ADC1 SCALE(1) | ||
|
||
define HAL_BATT2_MONITOR_DEFAULT 0 | ||
define HAL_BATT2_VOLT_PIN 15 | ||
define HAL_BATT2_VOLT_SCALE 21.0 | ||
define HAL_BATT2_CURR_PIN 16 | ||
define HAL_BATT2_CURR_SCALE 40.0 | ||
|
||
|
||
# -------------------- Buzzer+NeoPixels --------------d------ | ||
define HAL_PERIPH_ENABLE_RC_OUT | ||
define HAL_PERIPH_ENABLE_NOTIFY | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,83 @@ | ||
# hw definition file Matek L431 CAN node | ||
|
||
# MCU class and specific type | ||
MCU STM32L431 STM32L431xx | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 1062 | ||
|
||
# setup build for a peripheral firmware | ||
env AP_PERIPH 1 | ||
|
||
FLASH_RESERVE_START_KB 0 | ||
FLASH_BOOTLOADER_LOAD_KB 36 | ||
FLASH_SIZE_KB 256 | ||
|
||
# reserve some space for params | ||
APP_START_OFFSET_KB 4 | ||
|
||
STDOUT_SERIAL SD1 | ||
STDOUT_BAUDRATE 57600 | ||
|
||
# --------------------------------------------- | ||
PB3 LED_BOOTLOADER OUTPUT LOW # blue | ||
define HAL_LED_ON 0 | ||
|
||
# order of UARTs | ||
SERIAL_ORDER USART1 USART2 USART3 | ||
|
||
PB6 USART1_TX USART1 NODMA | ||
PB7 USART1_RX USART1 NODMA | ||
|
||
PA2 USART2_TX USART2 NODMA | ||
PA3 USART2_RX USART2 NODMA | ||
|
||
PB10 USART3_TX USART3 NODMA | ||
PB11 USART3_RX USART3 NODMA | ||
|
||
define HAL_USE_SERIAL TRUE | ||
define STM32_SERIAL_USE_USART1 TRUE | ||
define STM32_SERIAL_USE_USART2 TRUE | ||
define STM32_SERIAL_USE_USART3 TRUE | ||
|
||
# enable CAN support | ||
PB8 CAN1_RX CAN1 | ||
PB9 CAN1_TX CAN1 | ||
# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW | ||
|
||
CAN_ORDER 1 | ||
|
||
# --------------------------------------------- | ||
|
||
# make bl baudrate match debug baudrate for easier debugging | ||
define BOOTLOADER_BAUDRATE 57600 | ||
|
||
# use a small bootloader timeout | ||
define HAL_BOOTLOADER_TIMEOUT 1000 | ||
|
||
define HAL_USE_SERIAL TRUE | ||
define STM32_SERIAL_USE_USART1 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 | ||
|
||
# Add CS pins to ensure they are high in bootloader | ||
PA4 MAG_CS CS | ||
PB2 SPARE_CS CS | ||
|
||
# debugger support | ||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,103 @@ | ||
# hw definition file for Matek L431 CAN node | ||
|
||
# MCU class and specific type | ||
MCU STM32L431 STM32L431xx | ||
|
||
# bootloader starts firmware at 36k + 4k (STORAGE_FLASH) | ||
FLASH_RESERVE_START_KB 40 | ||
FLASH_SIZE_KB 256 | ||
|
||
# store parameters in pages 18 and 19 | ||
STORAGE_FLASH_PAGE 18 | ||
define HAL_STORAGE_SIZE 800 | ||
|
||
# ChibiOS system timer | ||
STM32_ST_USE_TIMER 15 | ||
define CH_CFG_ST_RESOLUTION 16 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID 1062 | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
env AP_PERIPH 1 | ||
|
||
STDOUT_SERIAL SD1 | ||
STDOUT_BAUDRATE 57600 | ||
|
||
define HAL_NO_GPIO_IRQ | ||
define SERIAL_BUFFERS_SIZE 512 | ||
define PORT_INT_REQUIRED_STACK 64 | ||
|
||
define DMA_RESERVE_SIZE 0 | ||
|
||
# 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 | ||
|
||
define HAL_GCS_ENABLED 0 | ||
define HAL_NO_MONITOR_THREAD | ||
define HAL_NO_LOGGING | ||
define HAL_MINIMIZE_FEATURES 0 | ||
|
||
# we setup a small defaults.parm | ||
define AP_PARAM_MAX_EMBEDDED_PARAM 512 | ||
|
||
# blue LED0 marked as ACT | ||
PB3 LED OUTPUT HIGH | ||
define HAL_LED_ON 1 | ||
|
||
# debugger support | ||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# --------------------- SPI1 RM3100 ----------------------- | ||
PA5 SPI1_SCK SPI1 | ||
PB4 SPI1_MISO SPI1 | ||
PA7 SPI1_MOSI SPI1 | ||
PA4 MAG_CS CS | ||
PB2 SPARE_CS CS | ||
|
||
|
||
# ---------------------- I2C bus ------------------------ | ||
I2C_ORDER I2C2 | ||
|
||
PB13 I2C2_SCL I2C2 | ||
PB14 I2C2_SDA I2C2 | ||
|
||
define HAL_I2C_CLEAR_ON_TIMEOUT 0 | ||
define HAL_I2C_INTERNAL_MASK 1 | ||
|
||
|
||
# ---------------------- CAN bus ------------------------- | ||
CAN_ORDER 1 | ||
|
||
PB8 CAN1_RX CAN1 | ||
PB9 CAN1_TX CAN1 | ||
# PC13 GPIO_CAN1_SILENT OUTPUT PUSHPULL SPEED_LOW LOW | ||
|
||
define HAL_CAN_POOL_SIZE 6000 | ||
|
||
# ---------------------- UARTs --------------------------- | ||
# | sr0 | MSP | GPS | | ||
SERIAL_ORDER USART1 USART2 USART3 | ||
|
||
# USART1 for debug | ||
PB6 USART1_TX USART1 SPEED_HIGH | ||
PB7 USART1_RX USART1 SPEED_HIGH | ||
|
||
# USART2 for MSP | ||
PA2 USART2_TX USART2 SPEED_HIGH | ||
PA3 USART2_RX USART2 SPEED_HIGH | ||
|
||
# USART3 for GPS | ||
PB10 USART3_TX USART3 SPEED_HIGH NODMA | ||
PB11 USART3_RX USART3 SPEED_HIGH NODMA | ||
|
||
# allow for reboot command for faster development | ||
define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 |