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:
parent
27ad9ac3ca
commit
edd793c152
@ -74,7 +74,7 @@ void Storage::_storage_open(void)
|
|||||||
_flash_load();
|
_flash_load();
|
||||||
#elif defined(USE_POSIX)
|
#elif defined(USE_POSIX)
|
||||||
// allow for fallback to microSD based storage
|
// allow for fallback to microSD based storage
|
||||||
sdcard_init();
|
sdcard_retry();
|
||||||
|
|
||||||
log_fd = open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
|
log_fd = open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
|
||||||
if (log_fd == -1) {
|
if (log_fd == -1) {
|
||||||
@ -112,7 +112,7 @@ void Storage::_save_backup(void)
|
|||||||
{
|
{
|
||||||
#ifdef USE_POSIX
|
#ifdef USE_POSIX
|
||||||
// allow for fallback to microSD based storage
|
// allow for fallback to microSD based storage
|
||||||
sdcard_init();
|
sdcard_retry();
|
||||||
int fd = open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
|
int fd = open(HAL_STORAGE_BACKUP_FILE, O_WRONLY|O_CREAT|O_TRUNC);
|
||||||
if (fd != -1) {
|
if (fd != -1) {
|
||||||
write(fd, _buffer, CH_STORAGE_SIZE);
|
write(fd, _buffer, CH_STORAGE_SIZE);
|
||||||
|
@ -307,6 +307,6 @@ bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len)
|
|||||||
*/
|
*/
|
||||||
bool Util::fs_init(void)
|
bool Util::fs_init(void)
|
||||||
{
|
{
|
||||||
return sdcard_init();
|
return sdcard_retry();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -93,6 +93,7 @@ bool sdcard_init()
|
|||||||
device = AP_HAL::get_HAL().spi->get_device("sdcard");
|
device = AP_HAL::get_HAL().spi->get_device("sdcard");
|
||||||
if (!device) {
|
if (!device) {
|
||||||
printf("No sdcard SPI device found\n");
|
printf("No sdcard SPI device found\n");
|
||||||
|
sdcard_running = false;
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
device->set_slowdown(sd_slowdown);
|
device->set_slowdown(sd_slowdown);
|
||||||
@ -126,8 +127,8 @@ bool sdcard_init()
|
|||||||
mkdir("/APM", 0777);
|
mkdir("/APM", 0777);
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
sdcard_running = false;
|
|
||||||
#endif
|
#endif
|
||||||
|
sdcard_running = false;
|
||||||
#endif
|
#endif
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
@ -156,13 +157,15 @@ void sdcard_stop(void)
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
void sdcard_retry(void)
|
bool sdcard_retry(void)
|
||||||
{
|
{
|
||||||
#ifdef USE_POSIX
|
#ifdef USE_POSIX
|
||||||
if (!sdcard_running) {
|
if (!sdcard_running) {
|
||||||
sdcard_init();
|
sdcard_init();
|
||||||
}
|
}
|
||||||
|
return sdcard_running;
|
||||||
#endif
|
#endif
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if HAL_USE_MMC_SPI
|
#if HAL_USE_MMC_SPI
|
||||||
|
@ -17,4 +17,4 @@
|
|||||||
|
|
||||||
bool sdcard_init();
|
bool sdcard_init();
|
||||||
void sdcard_stop();
|
void sdcard_stop();
|
||||||
void sdcard_retry();
|
bool sdcard_retry();
|
||||||
|
Loading…
Reference in New Issue
Block a user