HAL_ChibiOS: fixed fallback to microSD for storage

this is used when FRAM fails on a board with microSD support. The
double init caused the validate() in the FATFS code to fail
This commit is contained in:
Andrew Tridgell 2019-04-07 13:40:24 +10:00 committed by Randy Mackay
parent 481a6ea570
commit 06cfdedfb2
4 changed files with 9 additions and 6 deletions

View File

@ -72,7 +72,7 @@ void Storage::_storage_open(void)
_flash_load();
#elif defined(USE_POSIX)
// allow for fallback to microSD based storage
sdcard_init();
sdcard_retry();
log_fd = open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
if (log_fd == -1) {
@ -110,7 +110,7 @@ void Storage::_save_backup(void)
{
#ifdef USE_POSIX
// allow for fallback to microSD based storage
sdcard_init();
sdcard_retry();
int fd = open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
if (fd != -1) {
write(fd, _buffer, CH_STORAGE_SIZE);

View File

@ -258,6 +258,6 @@ bool Util::get_system_id(char buf[40])
*/
bool Util::fs_init(void)
{
return sdcard_init();
return sdcard_retry();
}
#endif

View File

@ -95,6 +95,7 @@ bool sdcard_init()
device = AP_HAL::get_HAL().spi->get_device("sdcard");
if (!device) {
printf("No sdcard SPI device found\n");
sdcard_running = false;
sem.give();
return false;
}
@ -131,8 +132,8 @@ bool sdcard_init()
sem.give();
return true;
}
sdcard_running = false;
#endif
sdcard_running = false;
sem.give();
#endif
return false;
@ -162,13 +163,15 @@ void sdcard_stop(void)
#endif
}
void sdcard_retry(void)
bool sdcard_retry(void)
{
#ifdef USE_POSIX
if (!sdcard_running) {
sdcard_init();
}
return sdcard_running;
#endif
return false;
}
#if HAL_USE_MMC_SPI

View File

@ -17,4 +17,4 @@
bool sdcard_init();
void sdcard_stop();
void sdcard_retry();
bool sdcard_retry();