-
Notifications
You must be signed in to change notification settings - Fork 17.8k
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 MatekG474-Periph hwdef
- Loading branch information
Showing
8 changed files
with
310 additions
and
0 deletions.
There are no files selected for viewing
22 changes: 22 additions & 0 deletions
22
libraries/AP_HAL_ChibiOS/hwdef/MatekG474-DShot/defaults.parm
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,22 @@ | ||
# up to 11 motors/servos | ||
|
||
OUT1_FUNCTION 33 | ||
OUT2_FUNCTION 34 | ||
OUT3_FUNCTION 35 | ||
OUT4_FUNCTION 36 | ||
OUT5_FUNCTION 51 | ||
OUT6_FUNCTION 52 | ||
OUT7_FUNCTION 53 | ||
OUT8_FUNCTION 54 | ||
OUT9_FUNCTION 55 | ||
OUT10_FUNCTION 56 | ||
OUT11_FUNCTION 57 | ||
|
||
# DShot 600 | ||
ESC_PWM_TYPE 7 | ||
OUT_BLH_OTYPE 6 | ||
|
||
OUT_BLH_MASK 15 | ||
|
||
# DShot telem on RX3 | ||
ESC_TELEM_PORT 3 |
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 @@ | ||
include ../MatekG474/hwdef-bl.inc |
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,22 @@ | ||
include ../MatekG474/hwdef.inc | ||
|
||
# --------------------- PWM ----------------------- | ||
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(50) | ||
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(51) | ||
PA2 TIM2_CH3 TIM2 PWM(3) GPIO(52) | ||
PA3 TIM2_CH4 TIM2 PWM(4) GPIO(53) | ||
PA6 TIM3_CH1 TIM3 PWM(5) GPIO(54) | ||
PA7 TIM3_CH2 TIM3 PWM(6) GPIO(55) | ||
PB0 TIM3_CH3 TIM3 PWM(7) GPIO(56) | ||
PB1 TIM3_CH4 TIM3 PWM(8) GPIO(57) | ||
PC6 TIM8_CH1 TIM8 PWM(9) GPIO(58) | ||
PB9 TIM8_CH3 TIM8 PWM(10) GPIO(59) | ||
PB2 TIM5_CH1 TIM5 PWM(11) GPIO(60) | ||
|
||
define HAL_PERIPH_ENABLE_RC_OUT | ||
define HAL_PERIPH_ENABLE_NOTIFY | ||
|
||
# enable ESC control | ||
define HAL_SUPPORT_RCOUT_SERIAL 1 | ||
define HAL_WITH_ESC_TELEM 1 | ||
|
24 changes: 24 additions & 0 deletions
24
libraries/AP_HAL_ChibiOS/hwdef/MatekG474-Periph/defaults.parm
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,24 @@ | ||
# ----setup for PORT defaults | ||
#| EMPTY | USART1 | USART2 | USART3 | UART4 | | ||
GPS_PORT 2 | ||
MSP_PORT 3 | ||
RNGFND_PORT 4 | ||
ADSB_PORT -1 | ||
RC_PORT 1 | ||
EFI_PORT -1 | ||
PRX_PORT -1 | ||
ESC_TELEM_PORT -1 | ||
|
||
# ----I2C AirSpeed sensor, disabled by default | ||
ARSPD_BUS 0 # I2C1 | ||
ARSPD_TYPE 0 | ||
|
||
# ----I2C External Baro | ||
BARO_EXT_BUS -1 | ||
BARO_PROBE_EXT 4095 | ||
|
||
# ----I2C BATT_MONITOR INA2xx | ||
BATT_I2C_BUS 0 | ||
BATT_I2C_ADDR 0 | ||
BATT_SHUNT 0.0002 | ||
|
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 @@ | ||
include ../MatekG474/hwdef-bl.inc |
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,68 @@ | ||
include ../MatekG474/hwdef.inc | ||
|
||
# ----------- GPS | ||
define HAL_PERIPH_ENABLE_GPS | ||
define GPS_MAX_RATE_MS 200 | ||
|
||
define GPS_MAX_RECEIVERS 1 | ||
define GPS_MAX_INSTANCES 1 | ||
|
||
# allow for F9P GPS modules with moving baseline | ||
define GPS_MOVING_BASELINE 1 | ||
|
||
|
||
# ----------- COMPASS | ||
define HAL_PERIPH_ENABLE_MAG | ||
|
||
SPIDEV rm3100 SPI2 DEVID1 MAG_CS MODE0 1*MHZ 1*MHZ | ||
COMPASS RM3100 SPI:rm3100 false ROTATION_PITCH_180 | ||
|
||
define HAL_COMPASS_MAX_SENSORS 1 | ||
|
||
define HAL_PROBE_EXTERNAL_I2C_COMPASSES | ||
|
||
|
||
# ----------- I2C airspeed | ||
define HAL_PERIPH_ENABLE_AIRSPEED | ||
define AIRSPEED_MAX_SENSORS 1 | ||
|
||
|
||
# ----------- I2C Barometer | ||
define HAL_PERIPH_ENABLE_BARO | ||
define HAL_BARO_ALLOW_INIT_NO_BARO | ||
|
||
# BARO SPL06 I2C:0:0x76 | ||
|
||
# ----------- I2C BATT_MONITOR INA2xx | ||
|
||
define HAL_PERIPH_ENABLE_BATTERY | ||
define AP_BATTERY_INA2XX_ENABLED 1 | ||
define HAL_BATT_MONITOR_DEFAULT 21 | ||
|
||
|
||
# ----------- MSP | ||
define HAL_PERIPH_ENABLE_MSP | ||
define HAL_MSP_ENABLED 1 | ||
|
||
|
||
# ----------- ADSB | ||
define HAL_PERIPH_ENABLE_ADSB | ||
|
||
|
||
# ----------- RC INPUT | ||
define HAL_PERIPH_ENABLE_RCIN 1 | ||
|
||
|
||
# ----------- EFI | ||
define HAL_PERIPH_ENABLE_EFI | ||
define HAL_EFI_ENABLED 1 | ||
|
||
|
||
# ----------- proximity | ||
define HAL_PERIPH_ENABLE_PROXIMITY | ||
define HAL_PROXIMITY_ENABLED 1 | ||
|
||
|
||
# ----------- rangefinder | ||
define HAL_PERIPH_ENABLE_RANGEFINDER | ||
|
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,57 @@ | ||
# hw definition file Matek G474 CAN node | ||
|
||
# MCU class and specific type | ||
MCU STM32G474 STM32G474xx | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID AP_HW_MatekG474 | ||
|
||
# setup build for a peripheral firmware | ||
env AP_PERIPH 1 | ||
|
||
FLASH_RESERVE_START_KB 0 | ||
FLASH_BOOTLOADER_LOAD_KB 32 | ||
FLASH_SIZE_KB 512 | ||
|
||
# reserve some space for params | ||
APP_START_OFFSET_KB 4 | ||
|
||
# --------------------------------------------- | ||
PC13 LED_BOOTLOADER OUTPUT LOW # blue | ||
define HAL_LED_ON 0 | ||
|
||
# SWD debugging | ||
PA13 JTMS-SWDIO SWD | ||
PA14 JTCK-SWCLK SWD | ||
|
||
# enable CAN support | ||
PA11 CAN1_RX CAN1 | ||
PA12 CAN1_TX CAN1 | ||
|
||
PB5 CAN2_RX CAN2 | ||
PB6 CAN2_TX CAN2 | ||
|
||
|
||
# --------------------------------------------- | ||
|
||
# make bl baudrate match debug baudrate for easier debugging | ||
define BOOTLOADER_BAUDRATE 57600 | ||
|
||
# use a small bootloader timeout | ||
define HAL_BOOTLOADER_TIMEOUT 2500 | ||
|
||
define HAL_NO_GPIO_IRQ | ||
define HAL_USE_EMPTY_IO TRUE | ||
define DMA_RESERVE_SIZE 0 | ||
define HAL_DISABLE_LOOP_DELAY | ||
define HAL_NO_TIMER_THREAD | ||
define HAL_NO_RCIN_THREAD | ||
|
||
define HAL_USE_SERIAL FALSE | ||
|
||
# Add CS pins to ensure they are high in bootloader | ||
PB12 MAG_CS CS | ||
PC14 SPARE_CS CS |
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,115 @@ | ||
# hw definition file for Matek G474 CAN node | ||
|
||
# MCU class and specific type | ||
MCU STM32G474 STM32G474xx | ||
|
||
# bootloader starts firmware at 32k + 4k (STORAGE_FLASH) | ||
FLASH_RESERVE_START_KB 36 | ||
FLASH_SIZE_KB 512 | ||
|
||
# store parameters in pages | ||
STORAGE_FLASH_PAGE 16 | ||
define HAL_STORAGE_SIZE 1800 | ||
|
||
# ChibiOS system timer | ||
STM32_ST_USE_TIMER 15 | ||
define CH_CFG_ST_RESOLUTION 16 | ||
|
||
# board ID for firmware load | ||
APJ_BOARD_ID AP_HW_MatekG474 | ||
|
||
# crystal frequency | ||
OSCILLATOR_HZ 8000000 | ||
|
||
|
||
env AP_PERIPH 1 | ||
|
||
define SERIAL_BUFFERS_SIZE 512 | ||
# stack for fast interrupts | ||
define PORT_INT_REQUIRED_STACK 64 | ||
|
||
define HAL_NO_GPIO_IRQ | ||
define HAL_NO_MONITOR_THREAD | ||
define HAL_USE_RTC FALSE | ||
define HAL_DISABLE_LOOP_DELAY | ||
define HAL_NO_GCS | ||
define HAL_NO_LOGGING | ||
|
||
|
||
define DMA_RESERVE_SIZE 2048 | ||
|
||
# don't share any DMA channels (there are enough for everyone) | ||
DMA_NOSHARE * | ||
|
||
|
||
# keep ROMFS uncompressed as we don't have enough RAM | ||
# to uncompress the bootloader at runtime | ||
env ROMFS_UNCOMPRESSED True | ||
|
||
define AP_PARAM_MAX_EMBEDDED_PARAM 512 | ||
|
||
# allow for reboot command for faster development | ||
# define HAL_PERIPH_LISTEN_FOR_SERIAL_UART_REBOOT_CMD_PORT 0 | ||
|
||
|
||
# blue LED0 marked as ACT | ||
PC13 LED OUTPUT HIGH | ||
define HAL_LED_ON 1 | ||
|
||
# --------------------- SPI1 RM3100 ----------------------- | ||
PB13 SPI2_SCK SPI2 | ||
PB14 SPI2_MISO SPI2 | ||
PB15 SPI2_MOSI SPI2 | ||
PB12 MAG_CS CS | ||
PC14 SPARE_CS CS | ||
|
||
# ---------------------- I2C bus ------------------------ | ||
I2C_ORDER I2C1 I2C2 | ||
|
||
# SWD debugging, disabled for I2C1 | ||
# PA13 JTMS-SWDIO SWD | ||
# PA14 JTCK-SWCLK SWD | ||
|
||
PA13 I2C1_SCL I2C1 | ||
PA14 I2C1_SDA I2C1 | ||
|
||
PC4 I2C2_SCL I2C2 | ||
PA8 I2C2_SDA I2C2 | ||
|
||
define HAL_I2C_CLEAR_ON_TIMEOUT 0 | ||
define HAL_I2C_INTERNAL_MASK 0 | ||
|
||
define HAL_USE_I2C TRUE | ||
|
||
# ---------------------- CAN bus ------------------------- | ||
PA11 CAN1_RX CAN1 | ||
PA12 CAN1_TX CAN1 | ||
PB5 CAN2_RX CAN2 | ||
PB6 CAN2_TX CAN2 | ||
|
||
define HAL_CAN_POOL_SIZE 6000 | ||
|
||
# ---------------------- UARTs --------------------------- | ||
# make the UARTn numbers in parameters match the silkscreen | ||
# | sr0 | sr1 | sr2 | sr3 | sr4 | | ||
SERIAL_ORDER EMPTY USART1 USART2 USART3 UART4 | ||
|
||
PA9 USART1_TX USART1 SPEED_HIGH | ||
PA10 USART1_RX USART1 SPEED_HIGH | ||
|
||
PB3 USART2_TX USART2 SPEED_HIGH | ||
PB4 USART2_RX USART2 SPEED_HIGH | ||
|
||
PB10 USART3_TX USART3 SPEED_HIGH NODMA | ||
PB11 USART3_RX USART3 SPEED_HIGH NODMA | ||
|
||
PC10 UART4_TX UART4 SPEED_HIGH | ||
PC11 UART4_RX UART4 SPEED_HIGH | ||
|
||
STDOUT_SERIAL SD1 | ||
STDOUT_BAUDRATE 57600 | ||
|
||
# ----------- ADC | ||
define HAL_USE_ADC FALSE | ||
define STM32_ADC_USE_ADC1 FALSE | ||
define HAL_DISABLE_ADC_DRIVER TRUE |