mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fix sdcard param init
the write was failing because of a 0 byte write attempt, the response was -1 vs 0 this results in not using the sdcard backend for storage for all boots after the initial
This commit is contained in:
parent
96f5e2a20a
commit
4e9848ab3a
|
@ -103,7 +103,7 @@ void Storage::_storage_open(void)
|
|||
}
|
||||
// pre-fill to full size
|
||||
if (AP::FS().lseek(log_fd, ret, SEEK_SET) != ret ||
|
||||
AP::FS().write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret) {
|
||||
(CH_STORAGE_SIZE-ret > 0 && AP::FS().write(log_fd, &_buffer[ret], CH_STORAGE_SIZE-ret) != CH_STORAGE_SIZE-ret)) {
|
||||
::printf("setup failed for " HAL_STORAGE_FILE "\n");
|
||||
AP::FS().close(log_fd);
|
||||
log_fd = -1;
|
||||
|
|
Loading…
Reference in New Issue