/*1wrapper around new for C++ to ensure we always get zero filled memory2*/34#include <AP_HAL/AP_HAL.h>5#include <stdlib.h>6#include <new>7#include <AP_InternalError/AP_InternalError.h>89/*10globally override new and delete to ensure that we always start with11zero memory. This ensures consistent behaviour.1213Note that new comes in multiple different variants. When new is used14without std::nothrow the compiler is free to assume it will not fail15as it assumes exceptions are enabled. This makes code like this16unsafe when using -fno-exceptions:1718a = new b;19if (a == nullptr) {20handle_error()21}2223the compiler may remove the error handling. With g++ you can use24-fcheck-new to avoid this, but on clang++ the compiler accepts25-fcheck-new as a valid flag, but doesn't implement it, and may elide26the error checking. That makes using clang++ unsafe with27-fno-exceptions if you ever call new without std::nothrow.2829To avoid this we define NEW_NOTHROW as new(std::nothrow) and use it30everywhere in ArduPilot, then we catch any missing cases with both31an internal error and with a check of the elf for the symbols we32want to avoid33*/3435/*36variant for new(std::nothrow), which is all that should be used in37ArduPilot38*/39void * operator new(size_t size, std::nothrow_t const ¬hrow)40{41if (size < 1) {42size = 1;43}44return(calloc(size, 1));45}4647void * operator new[](size_t size, std::nothrow_t const ¬hrow)48{49if (size < 1) {50size = 1;51}52return(calloc(size, 1));53}5455/*56These variants are for new without std::nothrow. We don't want to ever57use this from ArduPilot code58*/59void * operator new(size_t size)60{61if (size < 1) {62size = 1;63}64return(calloc(size, 1));65}666768void * operator new[](size_t size)69{70if (size < 1) {71size = 1;72}73return(calloc(size, 1));74}7576void operator delete(void *p)77{78if (p) free(p);79}8081void operator delete[](void * ptr)82{83if (ptr) free(ptr);84}8586#if defined(CYGWIN_BUILD) && CONFIG_HAL_BOARD == HAL_BOARD_SITL8788// intercept malloc to ensure memory so allocated is zeroed. this is rather89// nasty hack that hopefully does not live long! if it breaks again, that's it!90// this is completely unsupported!9192// __imp_malloc is a pointer to a function that will be called to actually93// do the malloc work. we can't replace it (or malloc itself) at build time as94// that will cause cygwin to disable its own malloc. we therefore use a95// constructor function that runs before main but after cygwin's disable check96// to set the pointer to our own malloc which calls back into cygwin's allocator97// through calloc to actually do the work and the zeroing.9899#include <stdio.h> // perror100#include <sys/mman.h> // mprotect and constants101102extern "C" void *__imp_malloc; // the pointer of our affection103104static void *do_the_malloc(size_t size) { // replacement for malloc105// allocate zeroed using calloc (malloc would of course recurse infinitely)106return calloc(1, size);107}108109// called before main to set __imp_malloc. priority of 101 guarantees execution110// before C++ constructors.111__attribute__((constructor(101))) static void hack_in_malloc() {112// __imp_malloc is in .text which is read-only so make it read-write first113114// compute address of its memory page as mprotect mandates page alignment115size_t page_size = (size_t)sysconf(_SC_PAGESIZE);116void *page_base = (void *)((size_t)&__imp_malloc & (~(page_size-1)));117118// make it writable and executable as we (unlikely) may be executing near it119int res = mprotect(page_base, page_size, PROT_READ|PROT_WRITE|PROT_EXEC);120if (res) {121perror("hack_in_malloc() mprotect writable");122}123124*(void **)&__imp_malloc = (void *)&do_the_malloc; // set the pointer now125126// put the page back to read-only (and let execution keep happening)127res = mprotect(page_base, page_size, PROT_READ|PROT_EXEC);128if (res) {129perror("hack_in_malloc() mprotect readable");130}131}132133#elif CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS && CONFIG_HAL_BOARD != HAL_BOARD_QURT134/*135wrapper around malloc to ensure all memory is initialised as zero136ChibiOS and QURT have their own wrappers137*/138extern "C" {139void *__wrap_malloc(size_t size);140void *__real_malloc(size_t size);141}142void *__wrap_malloc(size_t size)143{144void *ret = __real_malloc(size);145if (ret != nullptr) {146memset(ret, 0, size);147}148return ret;149}150#endif151152/*153custom realloc which is guaranteed to zero newly-allocated memory154(assuming malloc does). marked as WEAK so tests can override it.155156* always frees ptr (and returns nullptr) if new_size is 0157* allocates if ptr is nullptr and new_size is not 0158* else allocates new_size and copies over the smaller of old_size and new_size159and frees ptr (old_size can be <= actual original requested size)160* returns nullptr if allocation fails and leaves ptr and its data unchanged161*/162void * WEAK mem_realloc(void *ptr, size_t old_size, size_t new_size)163{164if (new_size == 0) {165free(ptr);166return nullptr;167}168169if (ptr == nullptr) {170return malloc(new_size);171}172173void *new_ptr = malloc(new_size);174if (new_ptr != nullptr) {175size_t copy_size = new_size > old_size ? old_size : new_size;176memcpy(new_ptr, ptr, copy_size);177free(ptr);178}179180return new_ptr;181}182183184