mirror of https://github.com/ArduPilot/ardupilot
waf: add -fcheck-new to g++ build
this ensures the compiler doesn't assume that new always returns a non-NULL value. Without this the compiler may remove the error path in code like this: ``` MyObject *x = new MyObject; if (x == nullptr) { ::printf("Alloc failed\n"); } ``` the reason it can do this is the new operator is marked as throwing an exception on failure, which means the error path is unreachable. As we don't have C++ exceptions in ArduPilot could (and do!) have code that ends up losing protection against allocation failures
This commit is contained in:
parent
0d18ee71fa
commit
6d2e060deb
|
@ -249,6 +249,9 @@ class Board:
|
|||
env.CXXFLAGS += [
|
||||
'-Werror=implicit-fallthrough',
|
||||
]
|
||||
env.CXXFLAGS += [
|
||||
'-fcheck-new',
|
||||
]
|
||||
|
||||
if cfg.env.DEBUG:
|
||||
env.CFLAGS += [
|
||||
|
|
Loading…
Reference in New Issue