HAL_Linux: use calloc in preferance to malloc

This commit is contained in:
Andrew Tridgell 2018-01-17 08:10:23 +11:00
parent 3f5534eed5
commit 8fea99e1da
3 changed files with 5 additions and 5 deletions

View File

@ -283,7 +283,7 @@ void OpticalFlow_Onboard::_run_optflow()
convert_buffer_size = _width * _height; convert_buffer_size = _width * _height;
} }
convert_buffer = (uint8_t *)malloc(convert_buffer_size); convert_buffer = (uint8_t *)calloc(1, convert_buffer_size);
if (!convert_buffer) { if (!convert_buffer) {
AP_HAL::panic("OpticalFlow_Onboard: couldn't allocate conversion buffer\n"); AP_HAL::panic("OpticalFlow_Onboard: couldn't allocate conversion buffer\n");
} }
@ -293,7 +293,7 @@ void OpticalFlow_Onboard::_run_optflow()
output_buffer_size = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH * output_buffer_size = HAL_OPTFLOW_ONBOARD_OUTPUT_WIDTH *
HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT; HAL_OPTFLOW_ONBOARD_OUTPUT_HEIGHT;
output_buffer = (uint8_t *)malloc(output_buffer_size); output_buffer = (uint8_t *)calloc(1, output_buffer_size);
if (!output_buffer) { if (!output_buffer) {
if (convert_buffer) { if (convert_buffer) {
free(convert_buffer); free(convert_buffer);

View File

@ -113,8 +113,8 @@ Memory_table::Memory_table(uint32_t page_count, int version)
uint64_t pageInfo; uint64_t pageInfo;
void *offset; void *offset;
_virt_pages = (void **)malloc(page_count * sizeof(void *)); _virt_pages = (void **)calloc(page_count, sizeof(void *));
_phys_pages = (void **)malloc(page_count * sizeof(void *)); _phys_pages = (void **)calloc(page_count, sizeof(void *));
_page_count = page_count; _page_count = page_count;
if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) { if ((fdMem = open("/dev/mem", O_RDWR | O_SYNC | O_CLOEXEC)) < 0) {

View File

@ -113,7 +113,7 @@ bool VideoIn::allocate_buffers(uint32_t nbufs)
return ret; return ret;
} }
buffers = (struct buffer *)malloc(rb.count * sizeof buffers[0]); buffers = (struct buffer *)calloc(rb.count, sizeof buffers[0]);
if (buffers == nullptr) { if (buffers == nullptr) {
hal.console->printf("Unable to allocate buffers\n"); hal.console->printf("Unable to allocate buffers\n");
return false; return false;