Tools: on esp32 force constants to single-precision like chibios port does.

This commit is contained in:
David Buzz 2023-05-02 09:53:22 +10:00 committed by Andrew Tridgell
parent 6d4747a38c
commit 9a4a3bf551

View File

@ -936,6 +936,7 @@ class esp32(Board):
env.CFLAGS += [
'-fno-inline-functions',
'-mlongcalls',
'-fsingle-precision-constant',
]
env.CFLAGS.remove('-Werror=undef')
@ -951,6 +952,7 @@ class esp32(Board):
'-Wno-sign-compare',
'-fno-inline-functions',
'-mlongcalls',
'-fsingle-precision-constant', # force const vals to be float , not double. so 100.0 means 100.0f
'-fno-threadsafe-statics',
'-DCYGWIN_BUILD']
env.CXXFLAGS.remove('-Werror=undef')