AP_HAL_ChibiOS: ensure UP and CH timer channels share DMA for H7
This commit is contained in:
parent
fc7a617b74
commit
4346264113
@ -163,36 +163,18 @@ def generate_DMAMUX_map_mask(peripheral_list, channel_mask, noshare_list, dma_ex
|
||||
continue
|
||||
|
||||
# prevent attempts to share with other half of same peripheral
|
||||
# also prevent sharing with Timer channels
|
||||
others = []
|
||||
if p.endswith('RX'):
|
||||
others.append(p[:-2] + 'TX')
|
||||
other = p[:-2] + 'TX'
|
||||
elif p.endswith('TX'):
|
||||
others.append(p[:-2] + 'RX')
|
||||
other = p[:-2] + 'RX'
|
||||
else:
|
||||
other = None
|
||||
|
||||
for p2 in peripheral_list:
|
||||
if "_CH" not in p2:
|
||||
if other is not None and ii in idsets[other]:
|
||||
if len(idsets[p]) >= len(idsets[other]) and len(idsets[other]) > 0:
|
||||
continue
|
||||
if "_UP" in p2 and "_CH" in p and p2[:4] == p[:4]:
|
||||
continue
|
||||
elif "_UP" in p and "_CH" in p2 and p[:4] == p2[:4]:
|
||||
continue
|
||||
elif "_CH" in p and "_CH" in p2 and p[:4] == p2[:4]:
|
||||
continue
|
||||
else:
|
||||
others.append(p2)
|
||||
if debug:
|
||||
print ("Others for ", p, others)
|
||||
skip_this_chan = False
|
||||
for other in others:
|
||||
if ii in idsets[other]:
|
||||
if len(idsets[p]) >= len(idsets[other]) or len(idsets[other]) <= 1:
|
||||
skip_this_chan = True
|
||||
break
|
||||
idsets[other].remove(ii)
|
||||
dma_map[other].remove((dma,stream))
|
||||
if skip_this_chan:
|
||||
continue
|
||||
idsets[other].remove(ii)
|
||||
dma_map[other].remove((dma,stream))
|
||||
found = ii
|
||||
break
|
||||
if found is None:
|
||||
@ -242,7 +224,10 @@ def generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude):
|
||||
def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
dma_priority='', dma_noshare=''):
|
||||
'''write out a DMA resolver header file'''
|
||||
global dma_map, have_DMAMUX
|
||||
global dma_map, have_DMAMUX, has_bdshot
|
||||
timer_ch_periph = []
|
||||
|
||||
has_bdshot = False
|
||||
|
||||
# form a list of DMA priorities
|
||||
priority_list = dma_priority.split()
|
||||
@ -265,6 +250,9 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
|
||||
if dma_map is None:
|
||||
have_DMAMUX = True
|
||||
# ensure we don't assign dma for TIMx_CH as we share that with TIMx_UP
|
||||
timer_ch_periph = [periph for periph in peripheral_list if "_CH" in periph]
|
||||
dma_exclude += timer_ch_periph
|
||||
dma_map = generate_DMAMUX_map(peripheral_list, noshare_list, dma_exclude)
|
||||
|
||||
print("Writing DMA map")
|
||||
@ -272,6 +260,8 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
curr_dict = {}
|
||||
|
||||
for periph in peripheral_list:
|
||||
if "_CH" in periph:
|
||||
has_bdshot = True # the list contains a CH port
|
||||
if periph in dma_exclude:
|
||||
continue
|
||||
assigned = False
|
||||
@ -310,18 +300,6 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
stream = (streamchan[0], streamchan[1])
|
||||
share_ok = True
|
||||
for periph2 in stream_assign[stream]:
|
||||
# can only share timer UP and CH streams on the same timer, everything else disallowed
|
||||
if "_CH" in periph or "_CH" in periph2:
|
||||
if "_UP" in periph and "_CH" in periph2 and periph[-4:1] == periph2[-5:1]:
|
||||
share_ok = True
|
||||
elif "_UP" in periph2 and "_CH" in periph and periph2[-4:1] == periph[-5:1]:
|
||||
share_ok = True
|
||||
elif "_CH" in periph2 and "_CH" in periph and periph2[-5:1] == periph[-5:1]:
|
||||
share_ok = True
|
||||
else:
|
||||
share_ok = False
|
||||
if debug:
|
||||
print ("Can't share ", periph, periph2)
|
||||
if not can_share(periph, noshare_list) or not can_share(periph2, noshare_list):
|
||||
share_ok = False
|
||||
if share_ok:
|
||||
@ -366,6 +344,15 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" %
|
||||
(chibios_dma_define_name(key)+'STREAM', dma_controller,
|
||||
curr_dict[key][1], shared))
|
||||
if have_DMAMUX and "_UP" in key:
|
||||
# share the dma with rest of the _CH ports
|
||||
for ch in range(1,5):
|
||||
chkey = key.replace('_UP', '_CH{}'.format(ch))
|
||||
if chkey not in timer_ch_periph:
|
||||
continue
|
||||
f.write("#define %-30s STM32_DMA_STREAM_ID(%u, %u)%s\n" %
|
||||
(chibios_dma_define_name(chkey)+'STREAM', dma_controller,
|
||||
curr_dict[key][1], shared))
|
||||
for streamchan in dma_map[key]:
|
||||
if stream == (streamchan[0], streamchan[1]):
|
||||
if have_DMAMUX:
|
||||
@ -374,6 +361,15 @@ def write_dma_header(f, peripheral_list, mcu_type, dma_exclude=[],
|
||||
chan = streamchan[2]
|
||||
f.write("#define %-30s %s\n" %
|
||||
(chibios_dma_define_name(key)+'CHAN', chan))
|
||||
if have_DMAMUX and "_UP" in key:
|
||||
# share the devid with rest of the _CH ports
|
||||
for ch in range(1,5):
|
||||
chkey = key.replace('_UP', '_CH{}'.format(ch))
|
||||
if chkey not in timer_ch_periph:
|
||||
continue
|
||||
f.write("#define %-30s %s\n" %
|
||||
(chibios_dma_define_name(chkey)+'CHAN',
|
||||
chan.replace('_UP', '_CH{}'.format(ch))))
|
||||
break
|
||||
|
||||
# now generate UARTDriver.cpp DMA config lines
|
||||
|
Loading…
Reference in New Issue
Block a user