diff --git a/libraries/AP_HAL_PX4/Storage.cpp b/libraries/AP_HAL_PX4/Storage.cpp index 898483593e5fe17aa29e0418f71c01d6b974050d..4d7b10716c6c8b70ad493f1030356c37cedf0820 100644 --- a/libraries/AP_HAL_PX4/Storage.cpp +++ b/libraries/AP_HAL_PX4/Storage.cpp @@ -154,15 +154,8 @@ void PX4Storage::_storage_open(void) if (fd == -1) { hal.scheduler->panic("Failed to open " MTD_PARAMS_FILE); } - const uint16_t chunk_size = 128; - for (uint16_t ofs=0; ofs<sizeof(_buffer); ofs += chunk_size) { - ssize_t ret = read(fd, &_buffer[ofs], chunk_size); - if (ret != chunk_size) { - ::printf("storage read of %u bytes at %u to %p failed - got %d errno=%d\n", - (unsigned)sizeof(_buffer), (unsigned)ofs, &_buffer[ofs], (int)ret, (int)errno); - hal.scheduler->panic("Failed to read " MTD_PARAMS_FILE); - } - ofs += chunk_size; + if (read(fd, _buffer, sizeof(_buffer)) != sizeof(_buffer)) { + hal.scheduler->panic("Failed to read " MTD_PARAMS_FILE); } close(fd); _initialised = true;