2024-05-26 23:36:26 -03:00
|
|
|
/*
|
|
|
|
wrapper around new for C++ to ensure we always get zero filled memory
|
|
|
|
*/
|
2010-10-17 01:02:06 -03:00
|
|
|
|
2015-08-11 03:28:42 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2010-10-17 01:02:06 -03:00
|
|
|
#include <stdlib.h>
|
2024-05-26 23:36:26 -03:00
|
|
|
#include <new>
|
|
|
|
#include <AP_InternalError/AP_InternalError.h>
|
2012-08-22 21:31:03 -03:00
|
|
|
|
2015-06-26 02:41:11 -03:00
|
|
|
/*
|
|
|
|
globally override new and delete to ensure that we always start with
|
2015-11-03 09:46:29 -04:00
|
|
|
zero memory. This ensures consistent behaviour.
|
2024-05-26 23:36:26 -03:00
|
|
|
|
|
|
|
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
|
2015-06-26 02:41:11 -03:00
|
|
|
*/
|
2024-05-26 23:36:26 -03:00
|
|
|
void * operator new(size_t size, std::nothrow_t const ¬hrow)
|
2010-10-17 01:02:06 -03:00
|
|
|
{
|
2015-06-26 02:41:11 -03:00
|
|
|
if (size < 1) {
|
|
|
|
size = 1;
|
|
|
|
}
|
2011-10-28 15:43:43 -03:00
|
|
|
return(calloc(size, 1));
|
2010-10-17 01:02:06 -03:00
|
|
|
}
|
|
|
|
|
2024-05-26 23:36:26 -03:00
|
|
|
void * operator new[](size_t size, std::nothrow_t const ¬hrow)
|
2010-10-17 01:02:06 -03:00
|
|
|
{
|
2024-05-26 23:36:26 -03:00
|
|
|
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)
|
|
|
|
{
|
|
|
|
if (size < 1) {
|
|
|
|
size = 1;
|
|
|
|
}
|
|
|
|
return(calloc(size, 1));
|
2010-12-23 19:02:51 -04:00
|
|
|
}
|
|
|
|
|
2024-05-26 23:36:26 -03:00
|
|
|
|
2010-12-23 19:02:51 -04:00
|
|
|
void * operator new[](size_t size)
|
|
|
|
{
|
2015-06-26 02:41:11 -03:00
|
|
|
if (size < 1) {
|
|
|
|
size = 1;
|
|
|
|
}
|
2010-12-28 19:29:46 -04:00
|
|
|
return(calloc(size, 1));
|
2010-12-23 19:02:51 -04:00
|
|
|
}
|
|
|
|
|
2024-05-26 23:36:26 -03:00
|
|
|
void operator delete(void *p)
|
|
|
|
{
|
|
|
|
if (p) free(p);
|
|
|
|
}
|
|
|
|
|
2010-12-23 19:02:51 -04:00
|
|
|
void operator delete[](void * ptr)
|
|
|
|
{
|
|
|
|
if (ptr) free(ptr);
|
2010-10-17 01:02:06 -03:00
|
|
|
}
|
2024-05-26 23:36:26 -03:00
|
|
|
|
2024-09-02 20:21:15 -03:00
|
|
|
#if defined(CYGWIN_BUILD) && CONFIG_HAL_BOARD == HAL_BOARD_SITL
|
2024-07-06 02:50:43 -03:00
|
|
|
/*
|
|
|
|
wrapper around malloc to ensure all memory is initialised as zero
|
|
|
|
cygwin needs to wrap _malloc_r
|
|
|
|
*/
|
|
|
|
#undef _malloc_r
|
|
|
|
extern "C" {
|
|
|
|
void *__wrap__malloc_r(_reent *r, size_t size);
|
|
|
|
void *__real__malloc_r(_reent *r, size_t size);
|
|
|
|
void *_malloc_r(_reent *r, size_t size);
|
|
|
|
}
|
|
|
|
void *__wrap__malloc_r(_reent *r, size_t size)
|
|
|
|
{
|
|
|
|
void *ret = __real__malloc_r(r, size);
|
|
|
|
if (ret != nullptr) {
|
|
|
|
memset(ret, 0, size);
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
|
|
|
void *_malloc_r(_reent *x, size_t size)
|
|
|
|
{
|
|
|
|
void *ret = __real__malloc_r(x, size);
|
|
|
|
if (ret != nullptr) {
|
|
|
|
memset(ret, 0, size);
|
|
|
|
}
|
|
|
|
return ret;
|
|
|
|
}
|
2024-05-26 23:36:26 -03:00
|
|
|
|
2024-07-05 20:18:09 -03:00
|
|
|
#elif CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS && CONFIG_HAL_BOARD != HAL_BOARD_QURT
|
2024-05-26 23:36:26 -03:00
|
|
|
/*
|
|
|
|
wrapper around malloc to ensure all memory is initialised as zero
|
2024-07-05 20:18:09 -03:00
|
|
|
ChibiOS and QURT have their own wrappers
|
2024-05-26 23:36:26 -03:00
|
|
|
*/
|
|
|
|
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
|