ardupilot/libraries/AP_HAL_ChibiOS/hwdef/iomcu-dshot/hwdef.inc
Andy Piper 9f30d01561 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-12-18 19:02:52 +11:00

50 lines
1.7 KiB
PHP

# hw definition file for processing by chibios_pins.py
include ../iomcu/hwdef.inc
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
undef AP_HAL_SHARED_DMA_ENABLED
# 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 without sharing as channels used by high speed USART2 RX/TX
define AP_HAL_SHARED_DMA_ENABLED 1
define STM32_TIM_TIM4_UP_DMA_STREAM STM32_DMA_STREAM_ID(1, 7)
define STM32_TIM_TIM4_UP_DMA_CHAN 1
define SHARED_DMA_MASK (1U<<STM32_TIM_TIM4_UP_DMA_STREAM)
# 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 0x180
# defines to allow the loop timing to be observed with a Saleae
#define IOMCU_LOOP_TIMING_DEBUG 1
#undef PB0 PB1
#PB0 PINIO1 OUTPUT GPIO(107) LOW
#PB1 PINIO2 OUTPUT GPIO(108) LOW