ardupilot/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.dat
bugobliterator 9a21297cd1 AP_HAL_ChibiOS: add support for DShot on IOMCU
set timer counter size to be a byte wide
use HAL_DSHOT_ENABLED instead of DISABLE_DSHOT
build iomcu-dshot from existing iomcu
correct defines for DMAR size on iomcu
allow iomcu dshot rate to be configured from FMU
correct DMA allocation for dshot on iomcu
allow debug builds on iofirmware
ensure dshot is enabled on iomcu dshot
support proper iomcu dshot output thread triggered by FMU
allow selective disablement of serial LEDs and passthrough
disable serial LEDs and passthrough on iomcu-dshot
propagate ESC telemetry to iomcu
dshot_send_groups() for iomcu
remove use of ICU on iomcu for dshot. only allocate possible DMA channels
rename serial passthrough and dshot defines
update dshot docs
resize dshot iomcu main stack to minimum
correct dshot prescaler usage and bit_width_mul calculation
use ChibiOS in tickless mode on iomcu-dshot so that virtual timers can be used
propagate dshot commands to iomcu
passthrough oneshot125 to iomcu
2023-08-15 06:53:48 +10:00

44 lines
1.4 KiB
Plaintext

# hw definition file for processing by chibios_pins.py
include ../iomcu/hwdef.dat
undef AP_FASTBOOT_ENABLED AP_BOOTLOADER_FLASHING_ENABLED
undef HAL_DSHOT_ENABLED
# PPM uses a DMA channel that is required for TIM2, and no remapping of PA8 is possible
undef PA8
undef STM32_ICU_USE_TIM1 RCIN_ICU_TIMER STM32_RCIN_DMA_STREAM HAL_USE_ICU
undef PORT_INT_REQUIRED_STACK MAIN_STACK
undef CH_CFG_ST_TIMEDELTA CH_CFG_ST_FREQUENCY
define HAL_NO_LED_THREAD 1
# TIM2_UP required for PWM1/2
define STM32_TIM_TIM2_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 2)
define STM32_TIM_TIM2_UP_DMA_CHAN 1
# TIM4_UP (PWM 3/4) cannot be used as channels used by high speed USART2 RX/TX
# It's possible that DMA sharing might make this workable
#define STM32_TIM_TIM4_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
#define STM32_TIM_TIM4_UP_DMA_CHAN 1
# TIM3_UP required for PWM5-8
define STM32_TIM_TIM3_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
define STM32_TIM_TIM3_UP_DMA_CHAN 1
define NO_FASTBOOT
define HAL_WITH_DSP FALSE
define HAL_DSHOT_ENABLED TRUE
define HAL_SERIALLED_ENABLED FALSE
# Tickless mode is required in order for the virtual timers used by dshot to work correctly
STM32_ST_USE_TIMER 15
define CH_CFG_ST_RESOLUTION 16
define CH_CFG_ST_TIMEDELTA 2
define CH_CFG_ST_FREQUENCY 1000000
# ChibiOS already correctly sets stack sizes and considers 64 extra as conservative
define PORT_INT_REQUIRED_STACK 64
# "main" stack is only used for exceptions and ISR, but they can be nested
MAIN_STACK 0x100