mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
HAL_ChibiOS: support microSD slowdown
allow use of BRD_SD_SLOWDOWN to slow down clock on microSD
This commit is contained in:
parent
5a76aa9023
commit
85c3ef229d
@ -163,9 +163,6 @@ static THD_FUNCTION(main_loop,arg)
|
|||||||
ChibiOS::SPIDevice::test_clock_freq();
|
ChibiOS::SPIDevice::test_clock_freq();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
//Setup SD Card and Initialise FATFS bindings
|
|
||||||
sdcard_init();
|
|
||||||
|
|
||||||
hal.uartB->begin(38400);
|
hal.uartB->begin(38400);
|
||||||
hal.uartC->begin(57600);
|
hal.uartC->begin(57600);
|
||||||
hal.analogin->init();
|
hal.analogin->init();
|
||||||
|
@ -15,6 +15,7 @@
|
|||||||
#include "SPIDevice.h"
|
#include "SPIDevice.h"
|
||||||
|
|
||||||
#include <AP_HAL/AP_HAL.h>
|
#include <AP_HAL/AP_HAL.h>
|
||||||
|
#include <AP_Math/AP_Math.h>
|
||||||
#include <AP_HAL/utility/OwnPtr.h>
|
#include <AP_HAL/utility/OwnPtr.h>
|
||||||
#include "Util.h"
|
#include "Util.h"
|
||||||
#include "Scheduler.h"
|
#include "Scheduler.h"
|
||||||
@ -138,6 +139,15 @@ bool SPIDevice::set_speed(AP_HAL::Device::Speed speed)
|
|||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
setup a bus slowdown factor for high speed mode
|
||||||
|
*/
|
||||||
|
void SPIDevice::set_slowdown(uint8_t slowdown)
|
||||||
|
{
|
||||||
|
slowdown = constrain_int16(slowdown+1, 1, 32);
|
||||||
|
freq_flag_high = derive_freq_flag(device_desc.highspeed / slowdown);
|
||||||
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
low level transfer function
|
low level transfer function
|
||||||
*/
|
*/
|
||||||
|
@ -34,6 +34,7 @@ public:
|
|||||||
void dma_allocate(Shared_DMA *ctx);
|
void dma_allocate(Shared_DMA *ctx);
|
||||||
void dma_deallocate(Shared_DMA *ctx);
|
void dma_deallocate(Shared_DMA *ctx);
|
||||||
bool spi_started;
|
bool spi_started;
|
||||||
|
uint8_t slowdown;
|
||||||
|
|
||||||
// we need an additional lock in the dma_allocate and
|
// we need an additional lock in the dma_allocate and
|
||||||
// dma_deallocate functions to cope with 3-way contention as we
|
// dma_deallocate functions to cope with 3-way contention as we
|
||||||
@ -109,6 +110,9 @@ public:
|
|||||||
static void test_clock_freq(void);
|
static void test_clock_freq(void);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// setup a bus clock slowdown factor
|
||||||
|
void set_slowdown(uint8_t slowdown) override;
|
||||||
|
|
||||||
private:
|
private:
|
||||||
SPIBus &bus;
|
SPIBus &bus;
|
||||||
SPIDesc &device_desc;
|
SPIDesc &device_desc;
|
||||||
|
@ -23,6 +23,7 @@
|
|||||||
#include "hwdef/common/stm32_util.h"
|
#include "hwdef/common/stm32_util.h"
|
||||||
#include "hwdef/common/flash.h"
|
#include "hwdef/common/flash.h"
|
||||||
#include <AP_ROMFS/AP_ROMFS.h>
|
#include <AP_ROMFS/AP_ROMFS.h>
|
||||||
|
#include "sdcard.h"
|
||||||
|
|
||||||
#if HAL_WITH_IO_MCU
|
#if HAL_WITH_IO_MCU
|
||||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
@ -250,3 +251,13 @@ bool Util::get_system_id(char buf[40])
|
|||||||
buf[39] = 0;
|
buf[39] = 0;
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef USE_POSIX
|
||||||
|
/*
|
||||||
|
initialise filesystem
|
||||||
|
*/
|
||||||
|
bool Util::fs_init(void)
|
||||||
|
{
|
||||||
|
return sdcard_init();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
@ -51,6 +51,13 @@ public:
|
|||||||
void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override;
|
void toneAlarm_set_buzzer_tone(float frequency, float volume, uint32_t duration_ms) override;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_POSIX
|
||||||
|
/*
|
||||||
|
initialise (or re-initialise) filesystem storage
|
||||||
|
*/
|
||||||
|
bool fs_init(void) override;
|
||||||
|
#endif
|
||||||
|
|
||||||
private:
|
private:
|
||||||
#ifdef HAL_PWM_ALARM
|
#ifdef HAL_PWM_ALARM
|
||||||
struct ToneAlarmPwmGroup {
|
struct ToneAlarmPwmGroup {
|
||||||
|
@ -17,60 +17,83 @@
|
|||||||
#include "SPIDevice.h"
|
#include "SPIDevice.h"
|
||||||
#include "sdcard.h"
|
#include "sdcard.h"
|
||||||
#include "hwdef/common/spi_hook.h"
|
#include "hwdef/common/spi_hook.h"
|
||||||
|
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||||
|
|
||||||
extern const AP_HAL::HAL& hal;
|
extern const AP_HAL::HAL& hal;
|
||||||
|
|
||||||
#ifdef USE_POSIX
|
#ifdef USE_POSIX
|
||||||
static FATFS SDC_FS; // FATFS object
|
static FATFS SDC_FS; // FATFS object
|
||||||
static bool sdcard_init_done;
|
static bool sdcard_running;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAL_USE_MMC_SPI
|
#if HAL_USE_SDC
|
||||||
|
static SDCConfig sdcconfig = {
|
||||||
|
NULL,
|
||||||
|
SDC_MODE_4BIT,
|
||||||
|
0
|
||||||
|
};
|
||||||
|
#elif HAL_USE_MMC_SPI
|
||||||
MMCDriver MMCD1;
|
MMCDriver MMCD1;
|
||||||
static AP_HAL::OwnPtr<AP_HAL::SPIDevice> device;
|
static AP_HAL::OwnPtr<AP_HAL::SPIDevice> device;
|
||||||
static MMCConfig mmcconfig;
|
static MMCConfig mmcconfig;
|
||||||
static SPIConfig lowspeed;
|
static SPIConfig lowspeed;
|
||||||
static SPIConfig highspeed;
|
static SPIConfig highspeed;
|
||||||
static bool sdcard_running;
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/*
|
/*
|
||||||
initialise microSD card if avaialble
|
initialise microSD card if avaialble. This is called during
|
||||||
|
AP_BoardConfig initialisation. The parameter BRD_SD_SLOWDOWN
|
||||||
|
controls a scaling factor on the microSD clock
|
||||||
*/
|
*/
|
||||||
void sdcard_init()
|
bool sdcard_init()
|
||||||
{
|
{
|
||||||
#ifdef USE_POSIX
|
#ifdef USE_POSIX
|
||||||
if (sdcard_init_done) {
|
uint8_t sd_slowdown = AP_BoardConfig::get_sdcard_slowdown();
|
||||||
return;
|
|
||||||
}
|
|
||||||
sdcard_init_done = true;
|
|
||||||
#if HAL_USE_SDC
|
#if HAL_USE_SDC
|
||||||
|
|
||||||
|
if (SDCD1.bouncebuffer == nullptr) {
|
||||||
bouncebuffer_init(&SDCD1.bouncebuffer, 512);
|
bouncebuffer_init(&SDCD1.bouncebuffer, 512);
|
||||||
|
|
||||||
sdcStart(&SDCD1, NULL);
|
|
||||||
|
|
||||||
if(sdcConnect(&SDCD1) == HAL_FAILED) {
|
|
||||||
printf("Err: Failed to initialize SDIO!\n");
|
|
||||||
} else {
|
|
||||||
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
|
||||||
printf("Err: Failed to mount SD Card!\n");
|
|
||||||
sdcDisconnect(&SDCD1);
|
|
||||||
} else {
|
|
||||||
printf("Successfully mounted SDCard..\n");
|
|
||||||
}
|
}
|
||||||
//Create APM Directory
|
|
||||||
|
if (sdcard_running) {
|
||||||
|
sdcard_stop();
|
||||||
|
}
|
||||||
|
|
||||||
|
const uint8_t tries = 3;
|
||||||
|
for (uint8_t i=0; i<tries; i++) {
|
||||||
|
hal.scheduler->delay(10);
|
||||||
|
sdcconfig.slowdown = sd_slowdown;
|
||||||
|
sdcStart(&SDCD1, &sdcconfig);
|
||||||
|
if(sdcConnect(&SDCD1) == HAL_FAILED) {
|
||||||
|
sdcStop(&SDCD1);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
||||||
|
sdcDisconnect(&SDCD1);
|
||||||
|
sdcStop(&SDCD1);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||||
|
|
||||||
|
// Create APM Directory if needed
|
||||||
mkdir("/APM", 0777);
|
mkdir("/APM", 0777);
|
||||||
|
sdcard_running = true;
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
#elif HAL_USE_MMC_SPI
|
#elif HAL_USE_MMC_SPI
|
||||||
device = AP_HAL::get_HAL().spi->get_device("sdcard");
|
if (sdcard_running) {
|
||||||
if (!device) {
|
sdcard_stop();
|
||||||
printf("No sdcard SPI device found\n");
|
|
||||||
return;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
sdcard_running = true;
|
sdcard_running = true;
|
||||||
|
|
||||||
|
device = AP_HAL::get_HAL().spi->get_device("sdcard");
|
||||||
|
if (!device) {
|
||||||
|
printf("No sdcard SPI device found\n");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
device->set_slowdown(sd_slowdown);
|
||||||
|
|
||||||
mmcObjectInit(&MMCD1);
|
mmcObjectInit(&MMCD1);
|
||||||
|
|
||||||
mmcconfig.spip =
|
mmcconfig.spip =
|
||||||
@ -78,23 +101,33 @@ void sdcard_init()
|
|||||||
mmcconfig.hscfg = &highspeed;
|
mmcconfig.hscfg = &highspeed;
|
||||||
mmcconfig.lscfg = &lowspeed;
|
mmcconfig.lscfg = &lowspeed;
|
||||||
|
|
||||||
|
/*
|
||||||
|
try up to 3 times to init microSD interface
|
||||||
|
*/
|
||||||
|
const uint8_t tries = 3;
|
||||||
|
for (uint8_t i=0; i<tries; i++) {
|
||||||
|
hal.scheduler->delay(10);
|
||||||
mmcStart(&MMCD1, &mmcconfig);
|
mmcStart(&MMCD1, &mmcconfig);
|
||||||
|
|
||||||
if (mmcConnect(&MMCD1) == HAL_FAILED) {
|
if (mmcConnect(&MMCD1) == HAL_FAILED) {
|
||||||
printf("Err: Failed to initialize SDCARD_SPI!\n");
|
mmcStop(&MMCD1);
|
||||||
sdcard_running = false;
|
continue;
|
||||||
} else {
|
}
|
||||||
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
||||||
printf("Err: Failed to mount SD Card!\n");
|
|
||||||
mmcDisconnect(&MMCD1);
|
mmcDisconnect(&MMCD1);
|
||||||
} else {
|
mmcStop(&MMCD1);
|
||||||
printf("Successfully mounted SDCard..\n");
|
continue;
|
||||||
}
|
}
|
||||||
//Create APM Directory
|
printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
|
||||||
|
|
||||||
|
// Create APM Directory if needed
|
||||||
mkdir("/APM", 0777);
|
mkdir("/APM", 0777);
|
||||||
|
return true;
|
||||||
}
|
}
|
||||||
|
sdcard_running = false;
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
/*
|
/*
|
||||||
@ -106,7 +139,13 @@ void sdcard_stop(void)
|
|||||||
// unmount
|
// unmount
|
||||||
f_mount(nullptr, "/", 1);
|
f_mount(nullptr, "/", 1);
|
||||||
#endif
|
#endif
|
||||||
#if HAL_USE_MMC_SPI
|
#if HAL_USE_SDC
|
||||||
|
if (sdcard_running) {
|
||||||
|
sdcDisconnect(&SDCD1);
|
||||||
|
sdcStop(&SDCD1);
|
||||||
|
sdcard_running = false;
|
||||||
|
}
|
||||||
|
#elif HAL_USE_MMC_SPI
|
||||||
if (sdcard_running) {
|
if (sdcard_running) {
|
||||||
mmcDisconnect(&MMCD1);
|
mmcDisconnect(&MMCD1);
|
||||||
mmcStop(&MMCD1);
|
mmcStop(&MMCD1);
|
||||||
|
@ -15,5 +15,5 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
void sdcard_init();
|
bool sdcard_init();
|
||||||
void sdcard_stop();
|
void sdcard_stop();
|
||||||
|
Loading…
Reference in New Issue
Block a user