mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-18 06:38:29 -04:00
Tools: on esp32 force constants to single-precision like chibios port does.
This commit is contained in:
parent
775f12387c
commit
f1af8bae0d
@ -841,6 +841,7 @@ class esp32(Board):
|
|||||||
env.CFLAGS += [
|
env.CFLAGS += [
|
||||||
'-fno-inline-functions',
|
'-fno-inline-functions',
|
||||||
'-mlongcalls',
|
'-mlongcalls',
|
||||||
|
'-fsingle-precision-constant',
|
||||||
]
|
]
|
||||||
env.CFLAGS.remove('-Werror=undef')
|
env.CFLAGS.remove('-Werror=undef')
|
||||||
|
|
||||||
@ -856,6 +857,8 @@ class esp32(Board):
|
|||||||
'-Wno-sign-compare',
|
'-Wno-sign-compare',
|
||||||
'-fno-inline-functions',
|
'-fno-inline-functions',
|
||||||
'-mlongcalls',
|
'-mlongcalls',
|
||||||
|
'-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f
|
||||||
|
'-fno-threadsafe-statics',
|
||||||
'-DCYGWIN_BUILD']
|
'-DCYGWIN_BUILD']
|
||||||
env.CXXFLAGS.remove('-Werror=undef')
|
env.CXXFLAGS.remove('-Werror=undef')
|
||||||
env.CXXFLAGS.remove('-Werror=shadow')
|
env.CXXFLAGS.remove('-Werror=shadow')
|
||||||
|
Loading…
Reference in New Issue
Block a user