mirror of https://github.com/ArduPilot/ardupilot
HAL_PX4: use calloc for malloc_type()
this ensures that EKF memory is zero on start
This commit is contained in:
parent
4322ef7ca4
commit
a99b690d49
|
@ -250,10 +250,10 @@ void *PX4Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||||
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
||||||
return fat_dma_alloc(size);
|
return fat_dma_alloc(size);
|
||||||
} else {
|
} else {
|
||||||
return malloc(size);
|
return calloc(1, size);
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
return malloc(size);
|
return calloc(1, size);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
void PX4Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
|
void PX4Util::free_type(void *ptr, size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||||
|
|
Loading…
Reference in New Issue