ardupilot/libraries/AP_HAL_ChibiOS/hwdef/iomcu-f103-dshot/hwdef.dat

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

51 lines
1.5 KiB
Plaintext
Raw Normal View History

# hw definition file for processing by chibios_pins.py
# MCU class and specific type
MCU STM32F103 STM32F103xB
include ../iomcu-dshot/hwdef.inc
undef STM32_ST_USE_TIMER
# directly define DMA channels
DMA_NOMAP 1
# only four timers on F103xB so use TIM1 for system timer
STM32_ST_USE_TIMER 1
AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file
2023-09-24 10:09:23 -03:00
define HAL_WITH_ESC_TELEM 1
undef PA0 PA1 PB8 PB9
# the order is important here as it determines the order that timers are used to sending dshot
# TIM4 needs to go first so that TIM4_UP can be freed up to be used by input capture for TIM2
PB8 TIM4_CH3 TIM4 PWM(3) GPIO(103) BIDIR UP_SHARED
AP_HAL_ChibiOS: bdshot for f103 iofirmware add support to tell if shared DMA channel is actually shared avoid starting and stopping the timer peripheral with bdshot ensure that rcout DMA allocation and deallocation happens entirely within the lock increase rcout thread working area for bdshot fix mode mask that is sent to the iomcu ensure iomcu rcout thread gets timeouts for callbacks control bdshot input and output line levels on f103 use input capture channel pairs to read rising and falling edges of telemetry on f103 reset channel pairs together on iomcu generalize the bdshot input path to support suitable buffer sizes for iomcu generalize DMAR reading of CCR registers to read two at a time on iomcu enable bi-directional dshot channels on PWM1-4 on iomcu add methods to directly access erpm values from rcout update erpm mask and esc telemetry correctly for firmware supporting dshot add support for propagating bdmask to iomcu dshot commands to all channels need to be aware of iomcu ensure esc type is propagated to iomcu cope with iomcu channel numbering when using EDT ensure pwm driver is reset properly for dshot commands on iomcu correctly reset pwm for dshot commands correctly mask off bdshot bits going to iomcu don't reset GPIO modes on disabled lines don't reset pwm_started when sharing DMA channels set thread name on iomcu rcout and reduce stack size on iomcu ensure that bdshot pulses with no response are handled correctly correctly setup DMA for input capture on f103 deal with out of order captured bytes when decoding bdshot telemetry ensure DMA sharing on f103 does not pull lines low only disable the timer peripheral when switching DMA channels on iomcu add support for waiting for _UP to finish before proceeding with dshot re-order iomcu dshot channels to let TIM4_UP go first ensure that a cascading event will always come when expected on rcout allow timeouts when using cascading dshot always rotate telemetry channel after trying to capture input cater for both in order and out-of-order bdshot telemetry packets cope with reversed packets when decoding bdshot telemetry ensure UP DMA channel is fully free on iomcu before starting next dshot cycle refactor rcout for iofirmware into separate file
2023-09-24 10:09:23 -03:00
PB9 TIM4_CH4 TIM4 PWM(4) GPIO(104)
PA0 TIM2_CH1 TIM2 PWM(1) GPIO(101)
PA1 TIM2_CH2 TIM2 PWM(2) GPIO(102) BIDIR # DMA channel 7, shared with TIM4_UP and USART2_TX
# currently no support for having mixed outputs on the same timer
# PB1 TIM3_CH4 TIM3 PWM(8) GPIO(108) BIDIR # DMA channel 3, shared with TIM3_UP
# TIM2_UP - (1,2)
# TIM4_UP - (1,7)
# TIM3_UP - (1,3)
# TIM2_CH2 (PWM 1/2)
define STM32_TIM_TIM2_CH2_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
define STM32_TIM_TIM2_CH2_DMA_CHAN 1
# TIM4_CH3 (PWM 3/4)
define STM32_TIM_TIM4_CH3_DMA_STREAM STM32_DMA_STREAM_ID(1, 5)
define STM32_TIM_TIM4_CH3_DMA_CHAN 1
# TIM3_CH4 (PWM 7-8)
define STM32_TIM_TIM3_CH4_DMA_STREAM STM32_DMA_STREAM_ID(1, 3)
define STM32_TIM_TIM3_CH4_DMA_CHAN 1
undef SHARED_DMA_MASK
define SHARED_DMA_MASK (1U<<STM32_TIM_TIM4_UP_DMA_STREAM | 1U<<STM32_TIM_TIM2_CH2_DMA_STREAM | 1U<<STM32_UART_USART2_TX_DMA_STREAM)
undef MAIN_STACK
MAIN_STACK 0x400