AP_Common: override new and delete on all platforms to zero memory

this guarantees that all classes get zero initial members when
they are dynamically allocated.
This commit is contained in:
Andrew Tridgell 2015-06-26 15:41:11 +10:00
parent f2756ecb22
commit 21c8a2d94a
1 changed files with 23 additions and 9 deletions

View File

@ -9,10 +9,18 @@
#include <AP_HAL.h>
#include <stdlib.h>
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
/*
globally override new and delete to ensure that we always start with
zero memory. This ensures consistent behaviour. Note that
initialising all members of all C++ classes separately takes a lot
of flash space. On APM1/APM2 it would mean we wouldn't fit on the
board at all.
*/
void * operator new(size_t size)
{
if (size < 1) {
size = 1;
}
return(calloc(size, 1));
}
@ -21,15 +29,11 @@ void operator delete(void *p)
if (p) free(p);
}
// Conflicts with libmaple wirish/cxxabi-compat.cpp
#if CONFIG_HAL_BOARD != HAL_BOARD_FLYMAPLE
extern "C" void __cxa_pure_virtual(){
while (1){}
}
#endif
void * operator new[](size_t size)
{
if (size < 1) {
size = 1;
}
return(calloc(size, 1));
}
@ -38,6 +42,16 @@ void operator delete[](void * ptr)
if (ptr) free(ptr);
}
#if CONFIG_HAL_BOARD == HAL_BOARD_APM1 || CONFIG_HAL_BOARD == HAL_BOARD_APM2 || CONFIG_HAL_BOARD == HAL_BOARD_FLYMAPLE
// Conflicts with libmaple wirish/cxxabi-compat.cpp
#if CONFIG_HAL_BOARD != HAL_BOARD_FLYMAPLE
extern "C" void __cxa_pure_virtual(){
while (1){}
}
#endif
__extension__ typedef int __guard __attribute__((mode (__DI__)));
int __cxa_guard_acquire(__guard *g)