From 23d91c93c82a9bc15b05af9ff97e6bad81a537f8 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 16 Aug 2017 19:49:28 +1000 Subject: [PATCH] AP_HAL_Linux: correct compilation warning MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit ../../../libraries/AP_HAL_Linux/RCInput_RPI.cpp:129:35: warning: ignoring return value of ‘ssize_t read(int, void*, size_t)’, declared with attribute warn_unused_result [-Wunused-result] ::read(file, &pageInfo, 8); --- libraries/AP_HAL_Linux/RCInput_RPI.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_Linux/RCInput_RPI.cpp b/libraries/AP_HAL_Linux/RCInput_RPI.cpp index 0d4c74d66d..72d01ac068 100644 --- a/libraries/AP_HAL_Linux/RCInput_RPI.cpp +++ b/libraries/AP_HAL_Linux/RCInput_RPI.cpp @@ -126,7 +126,10 @@ Memory_table::Memory_table(uint32_t page_count, int version) // Get list of available cache coherent physical addresses for (i = 0; i < _page_count; i++) { _virt_pages[i] = mmap(0, PAGE_SIZE, PROT_READ | PROT_WRITE, MAP_SHARED | MAP_ANONYMOUS | MAP_NORESERVE | MAP_LOCKED, -1, 0); - ::read(file, &pageInfo, 8); + if (::read(file, &pageInfo, 8) < 8) { + fprintf(stderr, "Failed to read pagemap\n"); + exit(-1); + } _phys_pages[i] = (void *)((uintptr_t)(pageInfo * PAGE_SIZE) | bus); }