AP_Common: use standard realloc method from HAL

This commit is contained in:
bugobliterator 2020-03-17 06:06:54 +08:00 committed by Andrew Tridgell
parent b1c80d7d74
commit 2ce899c54f
1 changed files with 1 additions and 1 deletions

View File

@ -38,7 +38,7 @@ bool AP_ExpandingArrayGeneric::expand(uint16_t num_chunks)
// fail if reallocating would leave less than 100 bytes of memory free
return false;
}
chunk_ptr_t *chunk_ptrs_new = (chunk_ptr_t*)realloc(chunk_ptrs, chunk_ptr_size * sizeof(chunk_ptr_t));
chunk_ptr_t *chunk_ptrs_new = (chunk_ptr_t*)hal.util->std_realloc((void*)chunk_ptrs, chunk_ptr_size * sizeof(chunk_ptr_t));
if (chunk_ptrs_new == nullptr) {
return false;
}