2013-05-29 20:52:38 -03:00
|
|
|
// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
2010-10-17 01:02:06 -03:00
|
|
|
|
|
|
|
//
|
|
|
|
// C++ runtime support not provided by Arduino
|
|
|
|
//
|
|
|
|
// Note: use new/delete with caution. The heap is small and
|
|
|
|
// easily fragmented.
|
|
|
|
|
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>
|
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
|
|
|
|
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.
|
|
|
|
*/
|
2010-12-28 19:33:27 -04:00
|
|
|
void * operator new(size_t size)
|
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
|
|
|
}
|
|
|
|
|
2010-12-28 19:33:27 -04:00
|
|
|
void operator delete(void *p)
|
2010-10-17 01:02:06 -03:00
|
|
|
{
|
2011-10-28 15:43:43 -03:00
|
|
|
if (p) free(p);
|
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
|
|
|
}
|
|
|
|
|
|
|
|
void operator delete[](void * ptr)
|
|
|
|
{
|
|
|
|
if (ptr) free(ptr);
|
2010-10-17 01:02:06 -03:00
|
|
|
}
|
2010-11-18 13:52:41 -04:00
|
|
|
|
2015-06-26 02:41:11 -03:00
|
|
|
|
|
|
|
#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
|
|
|
|
|
2010-11-18 13:52:41 -04:00
|
|
|
__extension__ typedef int __guard __attribute__((mode (__DI__)));
|
|
|
|
|
2010-12-28 19:33:27 -04:00
|
|
|
int __cxa_guard_acquire(__guard *g)
|
2010-11-18 13:52:41 -04:00
|
|
|
{
|
2011-10-28 15:43:43 -03:00
|
|
|
return !*(char *)(g);
|
2010-11-18 13:52:41 -04:00
|
|
|
};
|
|
|
|
|
2012-10-27 00:02:59 -03:00
|
|
|
void __cxa_guard_release (__guard *g){
|
2011-10-28 15:43:43 -03:00
|
|
|
*(char *)g = 1;
|
2010-11-18 13:52:41 -04:00
|
|
|
};
|
|
|
|
|
2012-08-17 03:18:11 -03:00
|
|
|
void __cxa_guard_abort (__guard *) {
|
|
|
|
};
|
2010-12-23 19:02:51 -04:00
|
|
|
|
2013-01-01 03:25:47 -04:00
|
|
|
#endif // CONFIG_HAL_BOARD
|
2012-10-27 08:41:03 -03:00
|
|
|
|