mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 22:18:29 -04:00
HAL_ChibiOS: go via AP_Filesystem for mount/unmount operations
this fixes a deadlock where a mount/unmount could access FATFS without holding the AP_Filesystem semaphore
This commit is contained in:
parent
2596875ceb
commit
ee50eaf3c9
@ -36,8 +36,8 @@
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
#include "hwdef/common/stm32_util.h"
|
||||
#include "hwdef/common/watchdog.h"
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include "shared_dma.h"
|
||||
#include "sdcard.h"
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
#include <AP_IOMCU/AP_IOMCU.h>
|
||||
@ -258,8 +258,8 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
||||
AP::logger().StopLogging();
|
||||
}
|
||||
|
||||
// stop sdcard driver, if active
|
||||
sdcard_stop();
|
||||
// unmount filesystem, if active
|
||||
AP::FS().unmount();
|
||||
#endif
|
||||
|
||||
#if !defined(NO_FASTBOOT)
|
||||
@ -465,22 +465,26 @@ void Scheduler::_io_thread(void* arg)
|
||||
while (!sched->_hal_initialized) {
|
||||
sched->delay_microseconds(1000);
|
||||
}
|
||||
#ifndef HAL_NO_LOGGING
|
||||
uint32_t last_sd_start_ms = AP_HAL::millis();
|
||||
#endif
|
||||
while (true) {
|
||||
sched->delay_microseconds(1000);
|
||||
|
||||
// run registered IO processes
|
||||
sched->_run_io();
|
||||
|
||||
#ifndef HAL_NO_LOGGING
|
||||
if (!hal.util->get_soft_armed()) {
|
||||
// if sdcard hasn't mounted then retry it every 3s in the IO
|
||||
// thread when disarmed
|
||||
uint32_t now = AP_HAL::millis();
|
||||
if (now - last_sd_start_ms > 3000) {
|
||||
last_sd_start_ms = now;
|
||||
sdcard_retry();
|
||||
AP::FS().retry_mount();
|
||||
}
|
||||
}
|
||||
#endif
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -22,7 +22,6 @@
|
||||
#include "Scheduler.h"
|
||||
#include "hwdef/common/flash.h"
|
||||
#include <AP_Filesystem/AP_Filesystem.h>
|
||||
#include "sdcard.h"
|
||||
#include <stdio.h>
|
||||
|
||||
using namespace ChibiOS;
|
||||
@ -88,7 +87,7 @@ void Storage::_storage_open(void)
|
||||
}
|
||||
|
||||
// use microSD based storage
|
||||
if (sdcard_retry()) {
|
||||
if (AP::FS().retry_mount()) {
|
||||
log_fd = AP::FS().open(HAL_STORAGE_FILE, O_RDWR|O_CREAT);
|
||||
if (log_fd == -1) {
|
||||
::printf("open failed of " HAL_STORAGE_FILE "\n");
|
||||
@ -145,7 +144,7 @@ void Storage::_save_backup(void)
|
||||
// We want to do this desperately,
|
||||
// So we keep trying this for a second
|
||||
uint32_t start_millis = AP_HAL::millis();
|
||||
while(!sdcard_retry() && (AP_HAL::millis() - start_millis) < 1000) {
|
||||
while(!AP::FS().retry_mount() && (AP_HAL::millis() - start_millis) < 1000) {
|
||||
hal.scheduler->delay(1);
|
||||
}
|
||||
|
||||
|
@ -288,16 +288,6 @@ bool Util::get_system_id_unformatted(uint8_t buf[], uint8_t &len)
|
||||
return true;
|
||||
}
|
||||
|
||||
#ifdef USE_POSIX
|
||||
/*
|
||||
initialise filesystem
|
||||
*/
|
||||
bool Util::fs_init(void)
|
||||
{
|
||||
return sdcard_retry();
|
||||
}
|
||||
#endif
|
||||
|
||||
// return true if the reason for the reboot was a watchdog reset
|
||||
bool Util::was_watchdog_reset() const
|
||||
{
|
||||
|
@ -55,13 +55,6 @@ public:
|
||||
void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override;
|
||||
#endif
|
||||
|
||||
#ifdef USE_POSIX
|
||||
/*
|
||||
initialise (or re-initialise) filesystem storage
|
||||
*/
|
||||
bool fs_init(void) override;
|
||||
#endif
|
||||
|
||||
// return true if the reason for the reboot was a watchdog reset
|
||||
bool was_watchdog_reset() const override;
|
||||
|
||||
|
@ -80,8 +80,6 @@ bool sdcard_init()
|
||||
}
|
||||
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||
|
||||
// Create APM Directory if needed
|
||||
AP::FS().mkdir("/APM");
|
||||
sdcard_running = true;
|
||||
return true;
|
||||
}
|
||||
@ -124,9 +122,6 @@ bool sdcard_init()
|
||||
continue;
|
||||
}
|
||||
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||
|
||||
// Create APM Directory if needed
|
||||
AP::FS().mkdir("/APM");
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
@ -163,7 +158,10 @@ bool sdcard_retry(void)
|
||||
{
|
||||
#ifdef USE_POSIX
|
||||
if (!sdcard_running) {
|
||||
sdcard_init();
|
||||
if (sdcard_init()) {
|
||||
// create APM directory
|
||||
AP::FS().mkdir("/APM");
|
||||
}
|
||||
}
|
||||
return sdcard_running;
|
||||
#endif
|
||||
|
Loading…
Reference in New Issue
Block a user