sdcard.cpp 5.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227
  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. #include "SPIDevice.h"
  17. #include "sdcard.h"
  18. #include "hwdef/common/spi_hook.h"
  19. #include <AP_BoardConfig/AP_BoardConfig.h>
  20. #include <AP_Filesystem/AP_Filesystem.h>
  21. extern const AP_HAL::HAL& hal;
  22. #ifdef USE_POSIX
  23. static FATFS SDC_FS; // FATFS object
  24. static bool sdcard_running;
  25. static HAL_Semaphore sem;
  26. #endif
  27. #if HAL_USE_SDC
  28. static SDCConfig sdcconfig = {
  29. NULL,
  30. SDC_MODE_4BIT,
  31. 0
  32. };
  33. #elif HAL_USE_MMC_SPI
  34. MMCDriver MMCD1;
  35. static AP_HAL::OwnPtr<AP_HAL::SPIDevice> device;
  36. static MMCConfig mmcconfig;
  37. static SPIConfig lowspeed;
  38. static SPIConfig highspeed;
  39. #endif
  40. /*
  41. initialise microSD card if avaialble. This is called during
  42. AP_BoardConfig initialisation. The parameter BRD_SD_SLOWDOWN
  43. controls a scaling factor on the microSD clock
  44. */
  45. bool sdcard_init()
  46. {
  47. #ifdef USE_POSIX
  48. WITH_SEMAPHORE(sem);
  49. uint8_t sd_slowdown = AP_BoardConfig::get_sdcard_slowdown();
  50. #if HAL_USE_SDC
  51. if (SDCD1.bouncebuffer == nullptr) {
  52. bouncebuffer_init(&SDCD1.bouncebuffer, 512, true);
  53. }
  54. if (sdcard_running) {
  55. sdcard_stop();
  56. }
  57. const uint8_t tries = 3;
  58. for (uint8_t i=0; i<tries; i++) {
  59. sdcconfig.slowdown = sd_slowdown;
  60. sdcStart(&SDCD1, &sdcconfig);
  61. if(sdcConnect(&SDCD1) == HAL_FAILED) {
  62. sdcStop(&SDCD1);
  63. continue;
  64. }
  65. if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
  66. sdcDisconnect(&SDCD1);
  67. sdcStop(&SDCD1);
  68. continue;
  69. }
  70. printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
  71. // Create APM Directory if needed
  72. AP::FS().mkdir("/APM");
  73. sdcard_running = true;
  74. return true;
  75. }
  76. #elif HAL_USE_MMC_SPI
  77. if (sdcard_running) {
  78. sdcard_stop();
  79. }
  80. sdcard_running = true;
  81. device = AP_HAL::get_HAL().spi->get_device("sdcard");
  82. if (!device) {
  83. printf("No sdcard SPI device found\n");
  84. sdcard_running = false;
  85. return false;
  86. }
  87. device->set_slowdown(sd_slowdown);
  88. mmcObjectInit(&MMCD1);
  89. mmcconfig.spip =
  90. static_cast<ChibiOS::SPIDevice*>(device.get())->get_driver();
  91. mmcconfig.hscfg = &highspeed;
  92. mmcconfig.lscfg = &lowspeed;
  93. /*
  94. try up to 3 times to init microSD interface
  95. */
  96. const uint8_t tries = 3;
  97. for (uint8_t i=0; i<tries; i++) {
  98. mmcStart(&MMCD1, &mmcconfig);
  99. if (mmcConnect(&MMCD1) == HAL_FAILED) {
  100. mmcStop(&MMCD1);
  101. continue;
  102. }
  103. if (f_mount(&SDC_FS, "/", 1) != FR_OK) {
  104. mmcDisconnect(&MMCD1);
  105. mmcStop(&MMCD1);
  106. continue;
  107. }
  108. printf("Successfully mounted SDCard (slowdown=%u)\n", (unsigned)sd_slowdown);
  109. // Create APM Directory if needed
  110. AP::FS().mkdir("/APM");
  111. return true;
  112. }
  113. #endif
  114. sdcard_running = false;
  115. #endif
  116. return false;
  117. }
  118. /*
  119. stop sdcard interface (for reboot)
  120. */
  121. void sdcard_stop(void)
  122. {
  123. #ifdef USE_POSIX
  124. // unmount
  125. f_mount(nullptr, "/", 1);
  126. #endif
  127. #if HAL_USE_SDC
  128. if (sdcard_running) {
  129. sdcDisconnect(&SDCD1);
  130. sdcStop(&SDCD1);
  131. sdcard_running = false;
  132. }
  133. #elif HAL_USE_MMC_SPI
  134. if (sdcard_running) {
  135. mmcDisconnect(&MMCD1);
  136. mmcStop(&MMCD1);
  137. sdcard_running = false;
  138. }
  139. #endif
  140. }
  141. bool sdcard_retry(void)
  142. {
  143. #ifdef USE_POSIX
  144. if (!sdcard_running) {
  145. sdcard_init();
  146. }
  147. return sdcard_running;
  148. #endif
  149. return false;
  150. }
  151. #if HAL_USE_MMC_SPI
  152. /*
  153. hooks to allow hal_mmc_spi.c to work with HAL_ChibiOS SPI
  154. layer. This provides bounce buffers for DMA, DMA channel sharing and
  155. bus locking
  156. */
  157. void spiStartHook(SPIDriver *spip, const SPIConfig *config)
  158. {
  159. device->set_speed(config == &lowspeed ?
  160. AP_HAL::Device::SPEED_LOW : AP_HAL::Device::SPEED_HIGH);
  161. }
  162. void spiStopHook(SPIDriver *spip)
  163. {
  164. }
  165. void spiSelectHook(SPIDriver *spip)
  166. {
  167. if (sdcard_running) {
  168. device->get_semaphore()->take_blocking();
  169. device->set_chip_select(true);
  170. }
  171. }
  172. void spiUnselectHook(SPIDriver *spip)
  173. {
  174. if (sdcard_running) {
  175. device->set_chip_select(false);
  176. device->get_semaphore()->give();
  177. }
  178. }
  179. void spiIgnoreHook(SPIDriver *spip, size_t n)
  180. {
  181. if (sdcard_running) {
  182. device->clock_pulse(n);
  183. }
  184. }
  185. void spiSendHook(SPIDriver *spip, size_t n, const void *txbuf)
  186. {
  187. if (sdcard_running) {
  188. device->transfer((const uint8_t *)txbuf, n, nullptr, 0);
  189. }
  190. }
  191. void spiReceiveHook(SPIDriver *spip, size_t n, void *rxbuf)
  192. {
  193. if (sdcard_running) {
  194. device->transfer(nullptr, 0, (uint8_t *)rxbuf, n);
  195. }
  196. }
  197. #endif