Browse Source

HAL_ChibiOS: switched to fix allocation for BMDA streams on H7

this avoids issues with BDMA stream assignments due to bugs found
while testing boards with both I2C4 and SPI6
gps-1.3.1
Andrew Tridgell 4 years ago
parent
commit
4cebcede31
  1. 21
      libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h
  2. 29
      libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py

21
libraries/AP_HAL_ChibiOS/hwdef/common/stm32h7_mcuconf.h

@ -582,3 +582,24 @@
#define STM32_WSPI_QUADSPI1_MDMA_PRIORITY 1 #define STM32_WSPI_QUADSPI1_MDMA_PRIORITY 1
#define STM32_WSPI_QUADSPI1_PRESCALER_VALUE ((STM32_QSPICLK / HAL_QSPI1_CLK) - 1) #define STM32_WSPI_QUADSPI1_PRESCALER_VALUE ((STM32_QSPICLK / HAL_QSPI1_CLK) - 1)
#endif #endif
/*
we use a fixed allocation of BDMA streams. We previously dynamically
allocated these, but bugs in the chip make that unreliable. This is
a tested set of allocations that is known to work on boards that are
using all 3 of ADC3, I2C4 and SPI6. They are the only peripherals
that can use BDMA, so fixed allocation is possible as we have 8
streams and a maximum of 6 needed.
The layout is chosen to:
- avoid stream 0, as this doesn't work on ADC3 or SPI6_RX for no known reason
- leave a gap between the peripheral types, as we have previously found that we sometimes
lost SPI6 BDMA completion interrupts if SPI6 and I2c4 are neighbours
*/
#define STM32_I2C_I2C4_RX_BDMA_STREAM 1
#define STM32_I2C_I2C4_TX_BDMA_STREAM 2
#define STM32_SPI_SPI6_RX_BDMA_STREAM 4
#define STM32_SPI_SPI6_TX_BDMA_STREAM 5
#define STM32_ADC_ADC3_BDMA_STREAM 7

29
libraries/AP_HAL_ChibiOS/hwdef/scripts/dma_resolver.py

@ -231,11 +231,14 @@ def generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude, stream_ofs):
else: else:
dmamux1_peripherals.append(p) dmamux1_peripherals.append(p)
map1 = generate_DMAMUX_map_mask(dmamux1_peripherals, 0xFFFF, noshare_list, dma_exclude, stream_ofs) map1 = generate_DMAMUX_map_mask(dmamux1_peripherals, 0xFFFF, noshare_list, dma_exclude, stream_ofs)
# there are 8 BDMA channels, but an issue has been found where if I2C4 and SPI6 # there are 8 BDMA streams, but an issue has been found where if I2C4 and
# use neighboring channels then we sometimes lose a BDMA completion interrupt. To # SPI6 use neighboring streams then we sometimes lose a BDMA completion
# avoid this we set the BDMA available mask to 0x54, which forces the channels not to be # interrupt. We also found that both ADC3 and SPI6_RX can't use the first
# adjacent. This issue was found on a CUAV-X7, with H743 RevV. # stream. To avoid more complications we now statically allocate the BDMA
map2 = generate_DMAMUX_map_mask(dmamux2_peripherals, 0x54, noshare_list, dma_exclude, stream_ofs) # streams for the 3 possible peripherals. To keep this code simpler we
# still have the mapping code here, but it ends not not being used and the
# static allocation is in stm32h7_mcuconf.h
map2 = generate_DMAMUX_map_mask(dmamux2_peripherals, 0xff, noshare_list, dma_exclude, stream_ofs)
# translate entries from map2 to "DMA controller 3", which is used for BDMA # translate entries from map2 to "DMA controller 3", which is used for BDMA
for p in map2.keys(): for p in map2.keys():
streams = [] streams = []
@ -447,10 +450,9 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
else: else:
dma_controller = curr_dict[key][0] dma_controller = curr_dict[key][0]
if dma_controller == 3: if dma_controller == 3:
# for BDMA we use 3 in the resolver # BDMA resources turn out to be very strange on H743. For now
f.write("#define %-30s %u%s\n" % # we will skip trying to allocate them automatically and
(chibios_dma_define_name(key)+'STREAM', # instead rely on allocation in stm32h7_mcuconf.h.
curr_dict[key][1], shared))
continue continue
else: else:
f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" % f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" %
@ -526,8 +528,13 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
key = 'SPI%u' % u key = 'SPI%u' % u
else: else:
continue continue
f.write('#define STM32_SPI_%s_DMA_STREAMS STM32_SPI_%s_TX_%s_STREAM, STM32_SPI_%s_RX_%s_STREAM\n' % ( if dma_name(key) == 'BDMA':
key, key, dma_name(key), key, dma_name(key))) # we use SHARED_DMA_NONE for SPI6 on H7 as we don't need to lock the stream
# as it is never shared
f.write('#define STM32_SPI_%s_DMA_STREAMS SHARED_DMA_NONE, SHARED_DMA_NONE\n' % key)
else:
f.write('#define STM32_SPI_%s_DMA_STREAMS STM32_SPI_%s_TX_%s_STREAM, STM32_SPI_%s_RX_%s_STREAM\n' % (
key, key, dma_name(key), key, dma_name(key)))
return unassigned, ordered_timers return unassigned, ordered_timers

Loading…
Cancel
Save