mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-09 01:13:57 -04:00
HAL_ChibiOS: stop sdcard interface on reboot
This commit is contained in:
parent
86ded2c40c
commit
ea37cede28
@ -30,6 +30,7 @@
|
|||||||
#include <AP_Scheduler/AP_Scheduler.h>
|
#include <AP_Scheduler/AP_Scheduler.h>
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
#include "shared_dma.h"
|
#include "shared_dma.h"
|
||||||
|
#include "sdcard.h"
|
||||||
|
|
||||||
#if CH_CFG_USE_DYNAMIC == TRUE
|
#if CH_CFG_USE_DYNAMIC == TRUE
|
||||||
|
|
||||||
@ -241,6 +242,9 @@ void Scheduler::reboot(bool hold_in_bootloader)
|
|||||||
hal.rcout->force_safety_on();
|
hal.rcout->force_safety_on();
|
||||||
hal.rcout->force_safety_no_wait();
|
hal.rcout->force_safety_no_wait();
|
||||||
|
|
||||||
|
// stop sdcard driver, if active
|
||||||
|
sdcard_stop();
|
||||||
|
|
||||||
// lock all shared DMA channels. This has the effect of waiting
|
// lock all shared DMA channels. This has the effect of waiting
|
||||||
// till the sensor buses are idle
|
// till the sensor buses are idle
|
||||||
Shared_DMA::lock_all();
|
Shared_DMA::lock_all();
|
||||||
|
@ -94,6 +94,10 @@ void sdcard_init()
|
|||||||
*/
|
*/
|
||||||
void sdcard_stop(void)
|
void sdcard_stop(void)
|
||||||
{
|
{
|
||||||
|
#ifdef USE_POSIX
|
||||||
|
// unmount
|
||||||
|
f_mount(nullptr, "/", 1);
|
||||||
|
#endif
|
||||||
#if HAL_USE_MMC_SPI
|
#if HAL_USE_MMC_SPI
|
||||||
if (sdcard_running) {
|
if (sdcard_running) {
|
||||||
mmcDisconnect(&MMCD1);
|
mmcDisconnect(&MMCD1);
|
||||||
|
Loading…
Reference in New Issue
Block a user