Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AP_Common/c++.cpp
Views: 1798
/*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_SITL87/*88wrapper around malloc to ensure all memory is initialised as zero89cygwin needs to wrap _malloc_r90*/91#undef _malloc_r92extern "C" {93void *__wrap__malloc_r(_reent *r, size_t size);94void *__real__malloc_r(_reent *r, size_t size);95void *_malloc_r(_reent *r, size_t size);96}97void *__wrap__malloc_r(_reent *r, size_t size)98{99void *ret = __real__malloc_r(r, size);100if (ret != nullptr) {101memset(ret, 0, size);102}103return ret;104}105void *_malloc_r(_reent *x, size_t size)106{107void *ret = __real__malloc_r(x, size);108if (ret != nullptr) {109memset(ret, 0, size);110}111return ret;112}113114#elif CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS && CONFIG_HAL_BOARD != HAL_BOARD_QURT115/*116wrapper around malloc to ensure all memory is initialised as zero117ChibiOS and QURT have their own wrappers118*/119extern "C" {120void *__wrap_malloc(size_t size);121void *__real_malloc(size_t size);122}123void *__wrap_malloc(size_t size)124{125void *ret = __real_malloc(size);126if (ret != nullptr) {127memset(ret, 0, size);128}129return ret;130}131#endif132133134