APM:Libraries
sdcard.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  */
16 
17 #include "SPIDevice.h"
18 #include "sdcard.h"
19 #include "hwdef/common/spi_hook.h"
20 
21 extern const AP_HAL::HAL& hal;
22 
23 #ifdef USE_POSIX
24 static FATFS SDC_FS; // FATFS object
25 #endif
26 
27 #if HAL_USE_MMC_SPI
28 MMCDriver MMCD1;
30 static MMCConfig mmcconfig;
31 static SPIConfig lowspeed;
32 static SPIConfig highspeed;
33 static bool sdcard_running;
34 #endif
35 
36 /*
37  initialise microSD card if avaialble
38  */
40 {
41 #ifdef USE_POSIX
42 #if HAL_USE_SDC
43  sdcStart(&SDCD1, NULL);
44 
45  if(sdcConnect(&SDCD1) == HAL_FAILED) {
46  printf("Err: Failed to initialize SDIO!\n");
47  } else {
48  if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
49  printf("Err: Failed to mount SD Card!\n");
50  sdcDisconnect(&SDCD1);
51  } else {
52  printf("Successfully mounted SDCard..\n");
53  }
54  //Create APM Directory
55  mkdir("/APM", 0777);
56  }
57 #elif HAL_USE_MMC_SPI
58  device = AP_HAL::get_HAL().spi->get_device("sdcard");
59  if (!device) {
60  printf("No sdcard SPI device found\n");
61  return;
62  }
63 
64  sdcard_running = true;
65 
66  mmcObjectInit(&MMCD1);
67 
68  mmcconfig.spip =
69  static_cast<ChibiOS::SPIDevice*>(device.get())->get_driver();
70  mmcconfig.hscfg = &highspeed;
71  mmcconfig.lscfg = &lowspeed;
72 
73  mmcStart(&MMCD1, &mmcconfig);
74 
75  if (mmcConnect(&MMCD1) == HAL_FAILED) {
76  printf("Err: Failed to initialize SDCARD_SPI!\n");
77  sdcard_running = false;
78  } else {
79  if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
80  printf("Err: Failed to mount SD Card!\n");
81  mmcDisconnect(&MMCD1);
82  } else {
83  printf("Successfully mounted SDCard..\n");
84  }
85  //Create APM Directory
86  mkdir("/APM", 0777);
87  }
88 #endif
89 #endif
90 }
91 
92 /*
93  stop sdcard interface (for reboot)
94  */
95 void sdcard_stop(void)
96 {
97 #ifdef USE_POSIX
98  // unmount
99  f_mount(nullptr, "/", 1);
100 #endif
101 #if HAL_USE_MMC_SPI
102  if (sdcard_running) {
103  mmcDisconnect(&MMCD1);
104  mmcStop(&MMCD1);
105  sdcard_running = false;
106  }
107 #endif
108 }
109 
110 #if HAL_USE_MMC_SPI
111 
112 /*
113  hooks to allow hal_mmc_spi.c to work with HAL_ChibiOS SPI
114  layer. This provides bounce buffers for DMA, DMA channel sharing and
115  bus locking
116  */
117 
118 void spiStartHook(SPIDriver *spip, const SPIConfig *config)
119 {
120  device->set_speed(config == &lowspeed ?
122 }
123 
124 void spiStopHook(SPIDriver *spip)
125 {
126 }
127 
128 void spiSelectHook(SPIDriver *spip)
129 {
130  if (sdcard_running) {
131  device->get_semaphore()->take_blocking();
132  device->set_chip_select(true);
133  }
134 }
135 
136 void spiUnselectHook(SPIDriver *spip)
137 {
138  if (sdcard_running) {
139  device->set_chip_select(false);
140  device->get_semaphore()->give();
141  }
142 }
143 
144 void spiIgnoreHook(SPIDriver *spip, size_t n)
145 {
146  if (sdcard_running) {
147  device->clock_pulse(n);
148  }
149 }
150 
151 void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
152 {
153  if (sdcard_running) {
154  device->transfer((const uint8_t *)txbuf, n, nullptr, 0);
155  }
156 }
157 
158 void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
159 {
160  if (sdcard_running) {
161  device->transfer(nullptr, 0, (uint8_t *)rxbuf, n);
162  }
163 }
164 
165 #endif
166 
void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
int printf(const char *fmt,...)
Definition: stdio.c:113
void sdcard_init()
Definition: sdcard.cpp:39
virtual bool clock_pulse(uint32_t len)
Definition: SPIDevice.h:52
Definition: ff.h:99
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
void sdcard_stop(void)
Definition: sdcard.cpp:95
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
void spiStartHook(SPIDriver *spip, const SPIConfig *config)
virtual Semaphore * get_semaphore() override=0
virtual bool set_chip_select(bool set)
Definition: Device.h:214
virtual bool give()=0
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
FRESULT f_mount(FATFS *fs, const TCHAR *path, BYTE opt)
Definition: ff.c:3482
int mkdir(const char *pathname, mode_t mode)
POSIX make a directory.
Definition: posix.c:1620
#define NULL
Definition: hal_types.h:59
const HAL & get_HAL()
virtual void take_blocking()
Definition: Semaphores.h:15
void spiStopHook(SPIDriver *spip)
virtual bool set_speed(Device::Speed speed) override=0
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
void spiUnselectHook(SPIDriver *spip)
Definition: ff.h:244
void spiIgnoreHook(SPIDriver *spip, size_t n)
void spiSelectHook(SPIDriver *spip)
T * get() const
Definition: OwnPtr.h:88