HAL_ChibiOS: generate a dma map for H7
this allows for DMA sharing, allowing for more peripherals with DMA
This commit is contained in:
parent
423ad60c47
commit
cb77b06460
@ -11,8 +11,8 @@ dma_map = None
|
||||
|
||||
debug = False
|
||||
|
||||
|
||||
def check_possibility(periph, dma_stream, curr_dict, dma_map, check_list):
|
||||
def check_possibility(periph, dma_stream, curr_dict, dma_map, check_list, recurse=False):
|
||||
global ignore_list
|
||||
for other_periph in curr_dict:
|
||||
if other_periph != periph:
|
||||
if curr_dict[other_periph] == dma_stream:
|
||||
@ -30,9 +30,9 @@ def check_possibility(periph, dma_stream, curr_dict, dma_map, check_list):
|
||||
#check if we can resolve by swapping with other periphs
|
||||
for streamchan in dma_map[other_periph]:
|
||||
stream = (streamchan[0], streamchan[1])
|
||||
if stream != curr_dict[other_periph] and \
|
||||
check_possibility(other_periph, stream, curr_dict, dma_map, check_list):
|
||||
curr_dict[other_periph] = stream
|
||||
if stream != curr_dict[other_periph] and check_possibility(other_periph, stream, curr_dict, dma_map, check_list, False):
|
||||
if not recurse:
|
||||
curr_dict[other_periph] = stream
|
||||
return True
|
||||
return False
|
||||
return True
|
||||
@ -88,6 +88,82 @@ def get_sharing_priority(periph_list, priority_list):
|
||||
highest = prio
|
||||
return highest
|
||||
|
||||
def generate_DMAMUX_map(peripheral_list, noshare_list):
|
||||
'''
|
||||
generate a dma map suitable for a board with a DMAMUX
|
||||
|
||||
In principle any peripheral can use any stream, but we need to
|
||||
ensure that a peripheral doesn't try to use the same stream as its
|
||||
partner (eg. a RX/TX pair)
|
||||
'''
|
||||
dma_map = {}
|
||||
idsets = {}
|
||||
|
||||
# first unshareable peripherals
|
||||
available = 0xFFFF
|
||||
for p in peripheral_list:
|
||||
dma_map[p] = []
|
||||
idsets[p] = set()
|
||||
|
||||
for p in peripheral_list:
|
||||
if can_share(p, noshare_list):
|
||||
continue
|
||||
for i in range(16):
|
||||
mask = (1<<i)
|
||||
if available & mask != 0:
|
||||
available ^= mask
|
||||
dma = (i // 8) + 1
|
||||
stream = i % 8
|
||||
dma_map[p].append((dma,stream,0))
|
||||
idsets[p].add(i)
|
||||
break
|
||||
|
||||
# now shareable
|
||||
idx = 0
|
||||
for p in peripheral_list:
|
||||
if not can_share(p, noshare_list):
|
||||
continue
|
||||
base = idx % 16
|
||||
for i in range(16):
|
||||
found = None
|
||||
for ii in range(base,16) + range(0,base):
|
||||
if (1<<ii) & available == 0:
|
||||
continue
|
||||
|
||||
dma = (ii // 8) + 1
|
||||
stream = ii % 8
|
||||
|
||||
if (dma,stream) in dma_map[p]:
|
||||
continue
|
||||
|
||||
# prevent attempts to share with other half of same peripheral
|
||||
if p.endswith('RX'):
|
||||
other = p[:-2] + 'TX'
|
||||
elif p.endswith('TX'):
|
||||
other = p[:-2] + 'RX'
|
||||
else:
|
||||
other = None
|
||||
|
||||
if other is not None and ii in idsets[other]:
|
||||
if len(idsets[p]) >= len(idsets[other]):
|
||||
continue
|
||||
idsets[other].remove(ii)
|
||||
dma_map[other].remove((dma,stream))
|
||||
found = ii
|
||||
break
|
||||
if found is None:
|
||||
continue
|
||||
base = (found+1) % 16
|
||||
dma = (found // 8) + 1
|
||||
stream = found % 8
|
||||
dma_map[p].append((dma,stream))
|
||||
idsets[p].add(found)
|
||||
idx = (idx+1) % 16
|
||||
if debug:
|
||||
print('dma_map: ', dma_map)
|
||||
print('idsets: ', idsets)
|
||||
return dma_map
|
||||
|
||||
def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
dma_priority='', dma_noshare=''):
|
||||
'''write out a DMA resolver header file'''
|
||||
@ -112,6 +188,12 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
print("Unable to find module for MCU %s" % mcu_type)
|
||||
sys.exit(1)
|
||||
|
||||
if dma_map is None:
|
||||
have_DMAMUX = True
|
||||
dma_map = generate_DMAMUX_map(peripheral_list, noshare_list)
|
||||
else:
|
||||
have_DMAMUX = False
|
||||
|
||||
print("Writing DMA map")
|
||||
unassigned = []
|
||||
curr_dict = {}
|
||||
@ -121,10 +203,6 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
continue
|
||||
assigned = False
|
||||
check_list = []
|
||||
if dma_map is None:
|
||||
curr_dict[periph] = "STM32_DMA_STREAM_ID_ANY"
|
||||
assigned = True
|
||||
continue
|
||||
if not periph in dma_map:
|
||||
print("Unknown peripheral function %s in DMA map for %s" %
|
||||
(periph, mcu_type))
|
||||
@ -139,10 +217,18 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
if assigned == False:
|
||||
unassigned.append(periph)
|
||||
|
||||
if debug:
|
||||
print('curr_dict: ', curr_dict)
|
||||
print('unassigned: ', unassigned)
|
||||
|
||||
# now look for shared DMA possibilities
|
||||
stream_assign = {}
|
||||
for k in curr_dict.keys():
|
||||
stream_assign[curr_dict[k]] = [k]
|
||||
p = curr_dict[k]
|
||||
if not p in stream_assign:
|
||||
stream_assign[p] = [k]
|
||||
else:
|
||||
stream_assign[p].append(k)
|
||||
|
||||
unassigned_new = unassigned[:]
|
||||
for periph in unassigned:
|
||||
@ -168,6 +254,9 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
unassigned_new.remove(periph)
|
||||
unassigned = unassigned_new
|
||||
|
||||
if debug:
|
||||
print(stream_assign)
|
||||
|
||||
f.write("\n\n// auto-generated DMA mapping from dma_resolver.py\n")
|
||||
|
||||
if unassigned:
|
||||
@ -190,8 +279,12 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
curr_dict[key][1], shared))
|
||||
for streamchan in dma_map[key]:
|
||||
if stream == (streamchan[0], streamchan[1]):
|
||||
f.write("#define %-30s %u\n" %
|
||||
(chibios_dma_define_name(key)+'CHAN', streamchan[2]))
|
||||
if have_DMAMUX:
|
||||
chan = 'STM32_DMAMUX1_%s' % key
|
||||
else:
|
||||
chan = streamchan[2]
|
||||
f.write("#define %-30s %s\n" %
|
||||
(chibios_dma_define_name(key)+'CHAN', chan))
|
||||
break
|
||||
|
||||
# now generate UARTDriver.cpp DMA config lines
|
||||
@ -208,13 +301,13 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
key = 'UART%u' % u
|
||||
if key is None:
|
||||
continue
|
||||
if dma_map is None:
|
||||
if have_DMAMUX:
|
||||
# use DMAMUX ID as channel number
|
||||
dma_rx_chn = "STM32_DMAMUX1_" + key + "_RX"
|
||||
dma_tx_chn = "STM32_DMAMUX1_" + key + "_TX"
|
||||
else:
|
||||
dma_rx_chn = "STM32_%s_RX_DMA_CHN" % key
|
||||
dma_tx_chn = "STM32_%s_TX_DMA_CHN" % key
|
||||
dma_rx_chn = "STM32_UART_%s_RX_DMA_CHN" % key
|
||||
dma_tx_chn = "STM32_UART_%s_TX_DMA_CHN" % key
|
||||
|
||||
f.write("#define STM32_%s_RX_DMA_CONFIG " % key)
|
||||
if key + "_RX" in curr_dict:
|
||||
|
Loading…
Reference in New Issue
Block a user