mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: implement newlib alloc functions as malloc wrappers
this fixes issue #24106
This commit is contained in:
parent
799833fdaa
commit
24ec48d1e3
|
@ -536,3 +536,25 @@ void* get_addr_mem_region_end_addr(void *addr)
|
|||
}
|
||||
return 0;
|
||||
}
|
||||
|
||||
/*
|
||||
alloction functions for newlib
|
||||
*/
|
||||
void *__wrap__calloc_r(void *rptr, size_t nmemb, size_t size)
|
||||
{
|
||||
(void)rptr;
|
||||
return calloc(nmemb, size);
|
||||
}
|
||||
|
||||
void *__wrap__malloc_r(void *rptr, size_t size)
|
||||
{
|
||||
(void)rptr;
|
||||
// we want consistent zero memory
|
||||
return calloc(1, size);
|
||||
}
|
||||
|
||||
void __wrap__free_r(void *rptr, void *ptr)
|
||||
{
|
||||
(void)rptr;
|
||||
return free(ptr);
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue