/*
* This file is free software: you can redistribute it and/or modify it
* under the terms of the GNU General Public License as published by the
* Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This file is distributed in the hope that it will be useful, but
* WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
* See the GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License along
* with this program. If not, see .
*
*/
#include
#include "SPIDevice.h"
#include "sdcard.h"
#include "hwdef/common/spi_hook.h"
#include
#include
extern const AP_HAL::HAL& hal;
#ifdef USE_POSIX
static FATFS SDC_FS; // FATFS object
static bool sdcard_running;
static HAL_Semaphore sem;
#endif
#if HAL_USE_SDC
static SDCConfig sdcconfig = {
NULL,
SDC_MODE_4BIT,
0
};
#elif HAL_USE_MMC_SPI
MMCDriver MMCD1;
static AP_HAL::OwnPtr device;
static MMCConfig mmcconfig;
static SPIConfig lowspeed;
static SPIConfig highspeed;
#endif
/*
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
*/
bool sdcard_init()
{
#ifdef USE_POSIX
WITH_SEMAPHORE(sem);
uint8_t sd_slowdown = AP_BoardConfig::get_sdcard_slowdown();
#if HAL_USE_SDC
#if STM32_SDC_USE_SDMMC2 == TRUE
auto &sdcd = SDCD2;
#else
auto &sdcd = SDCD1;
#endif
if (sdcd.bouncebuffer == nullptr) {
// allocate 4k bouncebuffer for microSD to match size in
// AP_Logger
bouncebuffer_init(&sdcd.bouncebuffer, 4096, true);
}
if (sdcard_running) {
sdcard_stop();
}
const uint8_t tries = 3;
for (uint8_t i=0; iget_device("sdcard");
if (!device) {
printf("No sdcard SPI device found\n");
sdcard_running = false;
return false;
}
device->set_slowdown(sd_slowdown);
mmcObjectInit(&MMCD1);
mmcconfig.spip =
static_cast(device.get())->get_driver();
mmcconfig.hscfg = &highspeed;
mmcconfig.lscfg = &lowspeed;
/*
try up to 3 times to init microSD interface
*/
const uint8_t tries = 3;
for (uint8_t i=0; iset_speed(config == &lowspeed ?
AP_HAL::Device::SPEED_LOW : AP_HAL::Device::SPEED_HIGH);
}
void spiStopHook(SPIDriver *spip)
{
}
__RAMFUNC__ void spiSelectHook(SPIDriver *spip)
{
if (sdcard_running) {
device->get_semaphore()->take_blocking();
device->set_chip_select(true);
}
}
__RAMFUNC__ void spiUnselectHook(SPIDriver *spip)
{
if (sdcard_running) {
device->set_chip_select(false);
device->get_semaphore()->give();
}
}
void spiIgnoreHook(SPIDriver *spip, size_t n)
{
if (sdcard_running) {
device->clock_pulse(n);
}
}
__RAMFUNC__ void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
{
if (sdcard_running) {
device->transfer((const uint8_t *)txbuf, n, nullptr, 0);
}
}
__RAMFUNC__ void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
{
if (sdcard_running) {
device->transfer(nullptr, 0, (uint8_t *)rxbuf, n);
}
}
#endif