Browse Source

HAL_ChibiOS: use calloc for malloc type

this is not strictly necessary on ChibiOS as we already override
malloc, but will keep static analysis happy
master
Andrew Tridgell 7 years ago
parent
commit
8dae3fe59b
  1. 4
      libraries/AP_HAL_ChibiOS/Util.cpp

4
libraries/AP_HAL_ChibiOS/Util.cpp

@ -52,7 +52,7 @@ void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type) @@ -52,7 +52,7 @@ void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
if (mem_type == AP_HAL::Util::MEM_FAST) {
return try_alloc_from_ccm_ram(size);
} else {
return malloc(size);
return calloc(1, size);
}
}
@ -69,7 +69,7 @@ void* Util::try_alloc_from_ccm_ram(size_t size) @@ -69,7 +69,7 @@ void* Util::try_alloc_from_ccm_ram(size_t size)
void *ret = malloc_ccm(size);
if (ret == nullptr) {
//we failed to allocate from CCM so we are going to try common SRAM
ret = malloc(size);
ret = calloc(1, size);
}
return ret;
}

Loading…
Cancel
Save