2018-04-28 21:09:09 -03:00
|
|
|
/*
|
|
|
|
* 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 <http://www.gnu.org/licenses/>.
|
|
|
|
*
|
|
|
|
*/
|
|
|
|
|
|
|
|
#include "SPIDevice.h"
|
|
|
|
#include "sdcard.h"
|
|
|
|
#include "hwdef/common/spi_hook.h"
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
2018-04-28 21:09:09 -03:00
|
|
|
#ifdef USE_POSIX
|
|
|
|
static FATFS SDC_FS; // FATFS object
|
2018-08-01 05:54:36 -03:00
|
|
|
static bool sdcard_init_done;
|
2018-04-28 21:09:09 -03:00
|
|
|
#endif
|
|
|
|
|
|
|
|
#if HAL_USE_MMC_SPI
|
|
|
|
MMCDriver MMCD1;
|
|
|
|
static AP_HAL::OwnPtr<AP_HAL::SPIDevice> device;
|
|
|
|
static MMCConfig mmcconfig;
|
|
|
|
static SPIConfig lowspeed;
|
|
|
|
static SPIConfig highspeed;
|
2018-05-26 05:59:41 -03:00
|
|
|
static bool sdcard_running;
|
2018-04-28 21:09:09 -03:00
|
|
|
#endif
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
/*
|
|
|
|
initialise microSD card if avaialble
|
|
|
|
*/
|
|
|
|
void sdcard_init()
|
|
|
|
{
|
2018-04-28 21:09:09 -03:00
|
|
|
#ifdef USE_POSIX
|
2018-08-01 05:54:36 -03:00
|
|
|
if (sdcard_init_done) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
sdcard_init_done = true;
|
2018-04-28 21:09:09 -03:00
|
|
|
#if HAL_USE_SDC
|
2018-06-02 00:27:02 -03:00
|
|
|
|
2018-08-01 05:54:36 -03:00
|
|
|
bouncebuffer_init(&SDCD1.bouncebuffer, 512);
|
2018-06-02 00:27:02 -03:00
|
|
|
|
2018-04-28 21:09:09 -03:00
|
|
|
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
|
|
|
|
mkdir("/APM", 0777);
|
|
|
|
}
|
2018-05-26 05:59:41 -03:00
|
|
|
#elif HAL_USE_MMC_SPI
|
2018-04-28 21:09:09 -03:00
|
|
|
device = AP_HAL::get_HAL().spi->get_device("sdcard");
|
2018-05-26 05:59:41 -03:00
|
|
|
if (!device) {
|
|
|
|
printf("No sdcard SPI device found\n");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
sdcard_running = true;
|
2018-04-28 21:09:09 -03:00
|
|
|
|
|
|
|
mmcObjectInit(&MMCD1);
|
|
|
|
|
|
|
|
mmcconfig.spip =
|
|
|
|
static_cast<ChibiOS::SPIDevice*>(device.get())->get_driver();
|
|
|
|
mmcconfig.hscfg = &highspeed;
|
|
|
|
mmcconfig.lscfg = &lowspeed;
|
|
|
|
|
|
|
|
mmcStart(&MMCD1, &mmcconfig);
|
|
|
|
|
|
|
|
if (mmcConnect(&MMCD1) == HAL_FAILED) {
|
|
|
|
printf("Err: Failed to initialize SDCARD_SPI!\n");
|
2018-05-26 05:59:41 -03:00
|
|
|
sdcard_running = false;
|
2018-04-28 21:09:09 -03:00
|
|
|
} else {
|
|
|
|
if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
|
|
|
|
printf("Err: Failed to mount SD Card!\n");
|
|
|
|
mmcDisconnect(&MMCD1);
|
|
|
|
} else {
|
|
|
|
printf("Successfully mounted SDCard..\n");
|
|
|
|
}
|
|
|
|
//Create APM Directory
|
|
|
|
mkdir("/APM", 0777);
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
/*
|
|
|
|
stop sdcard interface (for reboot)
|
|
|
|
*/
|
|
|
|
void sdcard_stop(void)
|
|
|
|
{
|
2018-05-26 06:00:49 -03:00
|
|
|
#ifdef USE_POSIX
|
|
|
|
// unmount
|
|
|
|
f_mount(nullptr, "/", 1);
|
|
|
|
#endif
|
2018-05-26 05:59:41 -03:00
|
|
|
#if HAL_USE_MMC_SPI
|
|
|
|
if (sdcard_running) {
|
|
|
|
mmcDisconnect(&MMCD1);
|
|
|
|
mmcStop(&MMCD1);
|
|
|
|
sdcard_running = false;
|
|
|
|
}
|
|
|
|
#endif
|
|
|
|
}
|
|
|
|
|
2018-04-28 21:09:09 -03:00
|
|
|
#if HAL_USE_MMC_SPI
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
/*
|
|
|
|
hooks to allow hal_mmc_spi.c to work with HAL_ChibiOS SPI
|
|
|
|
layer. This provides bounce buffers for DMA, DMA channel sharing and
|
|
|
|
bus locking
|
|
|
|
*/
|
|
|
|
|
|
|
|
void spiStartHook(SPIDriver *spip, const SPIConfig *config)
|
|
|
|
{
|
|
|
|
device->set_speed(config == &lowspeed ?
|
|
|
|
AP_HAL::Device::SPEED_LOW : AP_HAL::Device::SPEED_HIGH);
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiStopHook(SPIDriver *spip)
|
|
|
|
{
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiSelectHook(SPIDriver *spip)
|
|
|
|
{
|
|
|
|
if (sdcard_running) {
|
|
|
|
device->get_semaphore()->take_blocking();
|
|
|
|
device->set_chip_select(true);
|
|
|
|
}
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiUnselectHook(SPIDriver *spip)
|
|
|
|
{
|
|
|
|
if (sdcard_running) {
|
|
|
|
device->set_chip_select(false);
|
|
|
|
device->get_semaphore()->give();
|
|
|
|
}
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiIgnoreHook(SPIDriver *spip, size_t n)
|
|
|
|
{
|
|
|
|
if (sdcard_running) {
|
|
|
|
device->clock_pulse(n);
|
|
|
|
}
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
|
|
|
|
{
|
|
|
|
if (sdcard_running) {
|
|
|
|
device->transfer((const uint8_t *)txbuf, n, nullptr, 0);
|
|
|
|
}
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
2018-05-26 05:59:41 -03:00
|
|
|
void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
|
|
|
|
{
|
|
|
|
if (sdcard_running) {
|
|
|
|
device->transfer(nullptr, 0, (uint8_t *)rxbuf, n);
|
|
|
|
}
|
2018-04-28 21:09:09 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
#endif
|
|
|
|
|