diff --git a/libraries/AP_Common/AP_Common.h b/libraries/AP_Common/AP_Common.h index 65a5648ad6..d51e888e53 100644 --- a/libraries/AP_Common/AP_Common.h +++ b/libraries/AP_Common/AP_Common.h @@ -23,6 +23,7 @@ #include #include #include +#include // used to pack structures #define PACKED __attribute__((__packed__)) @@ -184,3 +185,10 @@ template void BIT_CLEAR (T& value, uint8_t bitnumber) noexcept { ((value) &= ~((T)(1U) << (bitnumber))); } +/* + See the comments in libraries/AP_Common/c++.cpp + */ +#ifndef NEW_NOTHROW +#define NEW_NOTHROW new(std::nothrow) +#endif + diff --git a/libraries/AP_Common/AP_ExpandingArray.cpp b/libraries/AP_Common/AP_ExpandingArray.cpp index b5327c6f91..99b95896c7 100644 --- a/libraries/AP_Common/AP_ExpandingArray.cpp +++ b/libraries/AP_Common/AP_ExpandingArray.cpp @@ -16,6 +16,8 @@ #include "AP_ExpandingArray.h" #include +#ifndef HAL_BOOTLOADER_BUILD + extern const AP_HAL::HAL& hal; AP_ExpandingArrayGeneric::~AP_ExpandingArrayGeneric(void) @@ -75,3 +77,5 @@ bool AP_ExpandingArrayGeneric::expand_to_hold(uint16_t num_items) uint16_t chunks_required = ((num_items - max_items()) / chunk_size) + 1; return expand(chunks_required); } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/ExpandingString.cpp b/libraries/AP_Common/ExpandingString.cpp index 31420d95fe..9be2b3a91a 100644 --- a/libraries/AP_Common/ExpandingString.cpp +++ b/libraries/AP_Common/ExpandingString.cpp @@ -17,9 +17,10 @@ */ #include "ExpandingString.h" - #include +#ifndef HAL_BOOTLOADER_BUILD + extern const AP_HAL::HAL& hal; #define EXPAND_INCREMENT 512 @@ -127,3 +128,5 @@ void ExpandingString::set_buffer(char *s, uint32_t total_len, uint32_t used_len) allocation_failed = false; external_buffer = true; } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/Location.cpp b/libraries/AP_Common/Location.cpp index f414b6a9a1..273ecb9fe5 100644 --- a/libraries/AP_Common/Location.cpp +++ b/libraries/AP_Common/Location.cpp @@ -4,6 +4,8 @@ #include "Location.h" +#ifndef HAL_BOOTLOADER_BUILD + #include #include @@ -527,3 +529,5 @@ void Location::linearly_interpolate_alt(const Location &point1, const Location & // new target's distance along the original track and then linear interpolate between the original origin and destination altitudes set_alt_cm(point1.alt + (point2.alt - point1.alt) * constrain_float(line_path_proportion(point1, point2), 0.0f, 1.0f), point2.get_alt_frame()); } + +#endif // HAL_BOOTLOADER_BUILD diff --git a/libraries/AP_Common/MultiHeap.cpp b/libraries/AP_Common/MultiHeap.cpp index 75033db1a1..af0b86cf26 100644 --- a/libraries/AP_Common/MultiHeap.cpp +++ b/libraries/AP_Common/MultiHeap.cpp @@ -10,6 +10,8 @@ #include "MultiHeap.h" +#ifndef HAL_BOOTLOADER_BUILD + /* on ChibiOS allow up to 4 heaps. On other HALs only allow a single heap. This is needed as hal.util->heap_realloc() needs to have the @@ -141,3 +143,6 @@ void *MultiHeap::change_size(void *ptr, uint32_t old_size, uint32_t new_size) */ return hal.util->heap_realloc(heaps[0], ptr, old_size, new_size); } + +#endif // HAL_BOOTLOADER_BUILD + diff --git a/libraries/AP_Common/c++.cpp b/libraries/AP_Common/c++.cpp index b9804818e8..8ab798744f 100644 --- a/libraries/AP_Common/c++.cpp +++ b/libraries/AP_Common/c++.cpp @@ -1,15 +1,61 @@ -// -// C++ runtime support not provided by Arduino -// -// Note: use new/delete with caution. The heap is small and -// easily fragmented. +/* + wrapper around new for C++ to ensure we always get zero filled memory + */ #include #include +#include +#include /* globally override new and delete to ensure that we always start with zero memory. This ensures consistent behaviour. + + Note that new comes in multiple different variants. When new is used + without std::nothrow the compiler is free to assume it will not fail + as it assumes exceptions are enabled. This makes code like this + unsafe when using -fno-exceptions: + + a = new b; + if (a == nullptr) { + handle_error() + } + + the compiler may remove the error handling. With g++ you can use + -fcheck-new to avoid this, but on clang++ the compiler accepts + -fcheck-new as a valid flag, but doesn't implement it, and may elide + the error checking. That makes using clang++ unsafe with + -fno-exceptions if you ever call new without std::nothrow. + + To avoid this we define NEW_NOTHROW as new(std::nothrow) and use it + everywhere in ArduPilot, then we catch any missing cases with both + an internal error and with a check of the elf for the symbols we + want to avoid +*/ + +/* + variant for new(std::nothrow), which is all that should be used in + ArduPilot + */ +void * operator new(size_t size, std::nothrow_t const ¬hrow) +{ + if (size < 1) { + size = 1; + } + return(calloc(size, 1)); +} + +void * operator new[](size_t size, std::nothrow_t const ¬hrow) +{ + if (size < 1) { + size = 1; + } + return(calloc(size, 1)); +} + +/* + These variants are for new without std::nothrow. We don't want to ever + use this from ArduPilot code */ void * operator new(size_t size) { @@ -19,20 +65,41 @@ void * operator new(size_t size) return(calloc(size, 1)); } + +void * operator new[](size_t size) +{ + if (size < 1) { + size = 1; + } + return(calloc(size, 1)); +} + void operator delete(void *p) { if (p) free(p); } -void * operator new[](size_t size) -{ - if (size < 1) { - size = 1; - } - return(calloc(size, 1)); -} - void operator delete[](void * ptr) { if (ptr) free(ptr); } + + +#if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS +/* + wrapper around malloc to ensure all memory is initialised as zero + ChibiOS has its own wrapper + */ +extern "C" { + void *__wrap_malloc(size_t size); + void *__real_malloc(size_t size); +} +void *__wrap_malloc(size_t size) +{ + void *ret = __real_malloc(size); + if (ret != nullptr) { + memset(ret, 0, size); + } + return ret; +} +#endif