mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: use cortex m7 instructions on F7/H7
This commit is contained in:
parent
b0af48745e
commit
7a812a5516
|
@ -21,7 +21,13 @@ mcu = {
|
|||
'RAM_MAP' : [
|
||||
(0x20010000, 256, 0), # main memory, not DMA safe
|
||||
(0x20000000, 64, 1), # DTCM memory, DMA safe
|
||||
]
|
||||
],
|
||||
|
||||
# this board has M7 instructions, but single precision only FPU
|
||||
# we build as m4 as it makes for a smaller build, and given the 1M
|
||||
# flash limit we care more about size
|
||||
'CORTEX' : 'cortex-m4',
|
||||
'CPU_FLAGS' : '-mcpu=cortex-m4 -mfpu=fpv4-sp-d16 -mfloat-abi=hard'
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
|
|
@ -38,7 +38,11 @@ mcu = {
|
|||
# split DTCM in two to allow for fast checking of IS_DMA_SAFE in bouncebuffer code
|
||||
(0x20000000, 64, 1), # DTCM, DMA safe
|
||||
(0x20010000, 64, 2), # DTCM, 2nd half, used as fast memory. This lowers memory contention in the EKF code
|
||||
]
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
'CORTEX' : 'cortex-m7',
|
||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
|
|
@ -35,7 +35,11 @@ mcu = {
|
|||
'RAM_MAP' : [
|
||||
(0x20020000, 384, 0), # SRAM1/SRAM2
|
||||
(0x20000000, 128, 1), # DTCM, DMA
|
||||
]
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
'CORTEX' : 'cortex-m7',
|
||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||
}
|
||||
|
||||
DMA_Map = {
|
||||
|
|
|
@ -24,7 +24,11 @@ mcu = {
|
|||
(0x38000000, 64, 1), # SRAM4. This supports both DMA and BDMA ops
|
||||
(0x24000000, 512, 4), # AXI SRAM. Use this for SDMMC IDMA ops
|
||||
(0x00000400, 63, 2), # ITCM (first 1k removed, to keep address 0 unused)
|
||||
]
|
||||
],
|
||||
|
||||
# this MCU has M7 instructions and hardware double precision
|
||||
'CORTEX' : 'cortex-m7',
|
||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||
}
|
||||
|
||||
pincount = {
|
||||
|
|
|
@ -705,17 +705,26 @@ def write_mcu_config(f):
|
|||
lib = get_mcu_lib(mcu_type)
|
||||
build_info = lib.build
|
||||
|
||||
if mcu_series.startswith("STM32F1"):
|
||||
if get_mcu_config('CPU_FLAGS') and get_mcu_config('CORTEX'):
|
||||
# CPU flags specified in mcu file
|
||||
cortex = get_mcu_config('CORTEX')
|
||||
env_vars['CPU_FLAGS'] = get_mcu_config('CPU_FLAGS').split()
|
||||
build_info['MCU'] = cortex
|
||||
print("MCU Flags: %s %s" % (cortex, env_vars['CPU_FLAGS']))
|
||||
elif mcu_series.startswith("STM32F1"):
|
||||
cortex = "cortex-m3"
|
||||
env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex]
|
||||
build_info['MCU'] = cortex
|
||||
else:
|
||||
# default to F4
|
||||
cortex = "cortex-m4"
|
||||
env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"]
|
||||
build_info['MCU'] = cortex
|
||||
if not args.bootloader:
|
||||
|
||||
if not mcu_series.startswith("STM32F1") and not args.bootloader:
|
||||
env_vars['CPU_FLAGS'].append('-u_printf_float')
|
||||
build_info['ENV_UDEFS'] = "-DCHPRINTF_USE_FLOAT=1"
|
||||
|
||||
# setup build variables
|
||||
for v in build_info.keys():
|
||||
build_flags.append('%s=%s' % (v, build_info[v]))
|
||||
|
|
Loading…
Reference in New Issue