mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-11 17:13:56 -03:00
HAL_ChibiOS: implement newlib alloc functions as malloc wrappers
this fixes issue #24106
This commit is contained in:
parent
37253c13d9
commit
0aab2f7974
@ -537,6 +537,28 @@ 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);
|
||||
}
|
||||
|
||||
#ifdef USE_POSIX
|
||||
/*
|
||||
allocation functions for FATFS
|
||||
|
Loading…
Reference in New Issue
Block a user