mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: define HAL_HAVE_HARDWARE_DOUBLE on F765, F777 and H7
This commit is contained in:
parent
1119ffe6ba
commit
e11c94602b
|
@ -42,6 +42,10 @@ mcu = {
|
||||||
# this MCU has M7 instructions and hardware double precision
|
# this MCU has M7 instructions and hardware double precision
|
||||||
'CORTEX' : 'cortex-m7',
|
'CORTEX' : 'cortex-m7',
|
||||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||||
|
|
||||||
|
'DEFINES' : {
|
||||||
|
'HAL_HAVE_HARDWARE_DOUBLE' : '1'
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
DMA_Map = {
|
DMA_Map = {
|
||||||
|
|
|
@ -39,6 +39,10 @@ mcu = {
|
||||||
# this MCU has M7 instructions and hardware double precision
|
# this MCU has M7 instructions and hardware double precision
|
||||||
'CORTEX' : 'cortex-m7',
|
'CORTEX' : 'cortex-m7',
|
||||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||||
|
|
||||||
|
'DEFINES' : {
|
||||||
|
'HAL_HAVE_HARDWARE_DOUBLE' : '1'
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
DMA_Map = {
|
DMA_Map = {
|
||||||
|
|
|
@ -39,6 +39,10 @@ mcu = {
|
||||||
# this MCU has M7 instructions and hardware double precision
|
# this MCU has M7 instructions and hardware double precision
|
||||||
'CORTEX' : 'cortex-m7',
|
'CORTEX' : 'cortex-m7',
|
||||||
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
'CPU_FLAGS' : '-mcpu=cortex-m7 -mfpu=fpv5-d16 -mfloat-abi=hard',
|
||||||
|
|
||||||
|
'DEFINES' : {
|
||||||
|
'HAL_HAVE_HARDWARE_DOUBLE' : '1'
|
||||||
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
pincount = {
|
pincount = {
|
||||||
|
|
|
@ -712,6 +712,12 @@ def write_mcu_config(f):
|
||||||
if 'OTG2' in bytype:
|
if 'OTG2' in bytype:
|
||||||
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
|
f.write('#define STM32_USB_USE_OTG2 TRUE\n')
|
||||||
|
|
||||||
|
defines = get_mcu_config('DEFINES', False)
|
||||||
|
if defines is not None:
|
||||||
|
for d in defines.keys():
|
||||||
|
v = defines[d]
|
||||||
|
f.write("#ifndef %s\n#define %s %s\n#endif\n" % (d, d, v))
|
||||||
|
|
||||||
if get_config('PROCESS_STACK', required=False):
|
if get_config('PROCESS_STACK', required=False):
|
||||||
env_vars['PROCESS_STACK'] = get_config('PROCESS_STACK')
|
env_vars['PROCESS_STACK'] = get_config('PROCESS_STACK')
|
||||||
else:
|
else:
|
||||||
|
@ -812,6 +818,12 @@ def write_mcu_config(f):
|
||||||
env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"]
|
env_vars['CPU_FLAGS'] = ["-mcpu=%s" % cortex, "-mfpu=fpv4-sp-d16", "-mfloat-abi=hard"]
|
||||||
build_info['MCU'] = cortex
|
build_info['MCU'] = cortex
|
||||||
|
|
||||||
|
f.write('''
|
||||||
|
#ifndef HAL_HAVE_HARDWARE_DOUBLE
|
||||||
|
#define HAL_HAVE_HARDWARE_DOUBLE 0
|
||||||
|
#endif
|
||||||
|
''')
|
||||||
|
|
||||||
if get_mcu_config('EXPECTED_CLOCK'):
|
if get_mcu_config('EXPECTED_CLOCK'):
|
||||||
f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK'))
|
f.write('#define HAL_EXPECTED_SYSCLOCK %u\n' % get_mcu_config('EXPECTED_CLOCK'))
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue