mirror of https://github.com/ArduPilot/ardupilot
96 lines
2.4 KiB
Plaintext
96 lines
2.4 KiB
Plaintext
|
###########################################################################################################################################################
|
||
|
# mRo CAN PWM breakout
|
||
|
# 12x PWM / IO 3V3 logic level
|
||
|
# Connector options: 90deg 0.1", straight or no headers.
|
||
|
# External power supply for servos in solder pads.
|
||
|
# 1x UART port exposed in solder pads.
|
||
|
# Blue LEd status indicator.
|
||
|
# Uncased Weight and Dimensions:
|
||
|
# Weight: g ()
|
||
|
# Width: 33mm (in)
|
||
|
# Length: 31.3mm (in)
|
||
|
# Screw hole pattern: 19x25mm
|
||
|
# M10126A - Initial release March 2023
|
||
|
###########################################################################################################################################################
|
||
|
|
||
|
MCU STM32G4xx STM32G474xx
|
||
|
|
||
|
FLASH_RESERVE_START_KB 40
|
||
|
FLASH_SIZE_KB 512
|
||
|
|
||
|
STORAGE_FLASH_PAGE 16
|
||
|
define HAL_STORAGE_SIZE 2000
|
||
|
|
||
|
# board ID for firmware load
|
||
|
APJ_BOARD_ID 1098
|
||
|
|
||
|
OSCILLATOR_HZ 8000000
|
||
|
|
||
|
# setup build for a peripheral firmware
|
||
|
env AP_PERIPH 1
|
||
|
|
||
|
# debug on USART1
|
||
|
STDOUT_SERIAL SD1
|
||
|
STDOUT_BAUDRATE 57600
|
||
|
|
||
|
# order of UARTs
|
||
|
SERIAL_ORDER USART1
|
||
|
|
||
|
# LEDs
|
||
|
PB10 LED OUTPUT HIGH # blue
|
||
|
|
||
|
# USART1
|
||
|
PB6 USART1_TX USART1 NODMA
|
||
|
PB7 USART1_RX USART1 NODMA
|
||
|
|
||
|
# SWD debugging
|
||
|
PA13 JTMS-SWDIO SWD
|
||
|
PA14 JTCK-SWCLK SWD
|
||
|
|
||
|
define HAL_USE_ADC FALSE
|
||
|
define STM32_ADC_USE_ADC1 FALSE
|
||
|
define HAL_DISABLE_ADC_DRIVER TRUE
|
||
|
|
||
|
define HAL_NO_GPIO_IRQ
|
||
|
|
||
|
# avoid RCIN thread to save memory
|
||
|
define HAL_NO_RCIN_THREAD
|
||
|
|
||
|
define HAL_USE_RTC FALSE
|
||
|
|
||
|
#define DMA_RESERVE_SIZE 2048
|
||
|
|
||
|
define HAL_DISABLE_LOOP_DELAY
|
||
|
|
||
|
# enable CAN support
|
||
|
PA11 CAN1_RX CAN1
|
||
|
PA12 CAN1_TX CAN1
|
||
|
|
||
|
# keep ROMFS uncompressed as we don't have enough RAM
|
||
|
# to uncompress the bootloader at runtime
|
||
|
env ROMFS_UNCOMPRESSED True
|
||
|
|
||
|
define CAN_APP_NODE_NAME "io.mrobotics.mRoCANPWM-M10126"
|
||
|
|
||
|
# PWM - BIDIR config pending
|
||
|
PA0 TIM5_CH1 TIM5 PWM(1) GPIO(50)
|
||
|
PA1 TIM5_CH2 TIM5 PWM(2) GPIO(51)
|
||
|
PA2 TIM5_CH3 TIM5 PWM(3) GPIO(52)
|
||
|
PA3 TIM5_CH4 TIM5 PWM(4) GPIO(53)
|
||
|
PB15 TIM15_CH2 TIM15 PWM(5) GPIO(54)
|
||
|
PA8 TIM1_CH1 TIM1 PWM(6) GPIO(55)
|
||
|
PA9 TIM1_CH2 TIM1 PWM(7) GPIO(56)
|
||
|
PA10 TIM1_CH3 TIM1 PWM(8) GPIO(57)
|
||
|
PA6 TIM3_CH1 TIM3 PWM(9) GPIO(58)
|
||
|
PA7 TIM3_CH2 TIM3 PWM(10) GPIO(59)
|
||
|
PB0 TIM3_CH3 TIM3 PWM(11) GPIO(60)
|
||
|
PB1 TIM3_CH4 TIM3 PWM(12) GPIO(61)
|
||
|
|
||
|
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
|
||
|
|