mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_Common: wrap _malloc_r on cygwin
fixes dual allocation heap bug See https://cygwin.com/pipermail/cygwin/2000-July/038916.html
This commit is contained in:
parent
9c8175994e
commit
db19bce1d2
@ -84,8 +84,35 @@ void operator delete[](void * ptr)
|
|||||||
if (ptr) free(ptr);
|
if (ptr) free(ptr);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef CYGWIN_BUILD
|
||||||
|
/*
|
||||||
|
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;
|
||||||
|
}
|
||||||
|
|
||||||
#if CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS
|
#elif CONFIG_HAL_BOARD != HAL_BOARD_CHIBIOS
|
||||||
/*
|
/*
|
||||||
wrapper around malloc to ensure all memory is initialised as zero
|
wrapper around malloc to ensure all memory is initialised as zero
|
||||||
ChibiOS has its own wrapper
|
ChibiOS has its own wrapper
|
||||||
|
Loading…
Reference in New Issue
Block a user