mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: correct compilation warning
../../../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);
This commit is contained in:
parent
222dd0c9be
commit
23d91c93c8
|
@ -126,7 +126,10 @@ Memory_table::Memory_table(uint32_t page_count, int version)
|
||||||
// Get list of available cache coherent physical addresses
|
// Get list of available cache coherent physical addresses
|
||||||
for (i = 0; i < _page_count; i++) {
|
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);
|
_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);
|
_phys_pages[i] = (void *)((uintptr_t)(pageInfo * PAGE_SIZE) | bus);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue