bouncebuffer.c 4.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136
  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. bouncebuffer code for DMA safe memory operations
  17. */
  18. #include "stm32_util.h"
  19. #include <stdint.h>
  20. #include <string.h>
  21. #include <stdio.h>
  22. #include "bouncebuffer.h"
  23. #if defined(STM32H7)
  24. // always use a bouncebuffer on H7, to ensure alignment and padding
  25. #define IS_DMA_SAFE(addr) false
  26. #elif defined(STM32F7)
  27. // on F76x we only consider first half of DTCM memory as DMA safe, 2nd half is used as fast memory for EKF
  28. // on F74x we only have 64k of DTCM
  29. #define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & ((0xFFFFFFFF & ~(64*1024U-1)) | 1U)) == 0x20000000)
  30. #elif defined(STM32F1)
  31. #define IS_DMA_SAFE(addr) true
  32. #else
  33. // this checks an address is in main memory and 16 bit aligned
  34. #define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & 0xF0000001) == 0x20000000)
  35. #endif
  36. /*
  37. initialise a bouncebuffer
  38. */
  39. void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes, bool sdcard)
  40. {
  41. (*bouncebuffer) = calloc(1, sizeof(struct bouncebuffer_t));
  42. osalDbgAssert(((*bouncebuffer) != NULL), "bouncebuffer init");
  43. (*bouncebuffer)->is_sdcard = sdcard;
  44. if (prealloc_bytes) {
  45. (*bouncebuffer)->dma_buf = sdcard?malloc_sdcard_dma(prealloc_bytes):malloc_dma(prealloc_bytes);
  46. osalDbgAssert(((*bouncebuffer)->dma_buf != NULL), "bouncebuffer preallocate");
  47. (*bouncebuffer)->size = prealloc_bytes;
  48. }
  49. }
  50. /*
  51. setup for reading from a device into memory, allocating a bouncebuffer if needed
  52. Note that *buf can be NULL, in which case we allocate DMA capable memory, but don't
  53. copy to it in bouncebuffer_finish_read(). This avoids DMA failures in dummyrx in the SPI LLD
  54. */
  55. void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, uint32_t size)
  56. {
  57. if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
  58. // nothing needs to be done
  59. return;
  60. }
  61. osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer read");
  62. bouncebuffer->orig_buf = *buf;
  63. if (bouncebuffer->size < size) {
  64. if (bouncebuffer->size > 0) {
  65. free(bouncebuffer->dma_buf);
  66. }
  67. bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
  68. osalDbgAssert((bouncebuffer->dma_buf != NULL), "bouncebuffer read allocate");
  69. bouncebuffer->size = size;
  70. }
  71. *buf = bouncebuffer->dma_buf;
  72. #if defined(STM32H7)
  73. osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer read align");
  74. stm32_cacheBufferInvalidate(*buf, (size+31)&~31);
  75. #endif
  76. bouncebuffer->busy = true;
  77. }
  78. /*
  79. finish a read operation
  80. */
  81. void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf, uint32_t size)
  82. {
  83. if (bouncebuffer && buf == bouncebuffer->dma_buf) {
  84. osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_read");
  85. if (bouncebuffer->orig_buf) {
  86. memcpy(bouncebuffer->orig_buf, buf, size);
  87. }
  88. bouncebuffer->busy = false;
  89. }
  90. }
  91. /*
  92. setup for reading from memory to a device, allocating a bouncebuffer if needed
  93. */
  94. void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t **buf, uint32_t size)
  95. {
  96. if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
  97. // nothing needs to be done
  98. return;
  99. }
  100. osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer write");
  101. if (bouncebuffer->size < size) {
  102. if (bouncebuffer->size > 0) {
  103. free(bouncebuffer->dma_buf);
  104. }
  105. bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
  106. osalDbgAssert((bouncebuffer->dma_buf != NULL), "bouncebuffer write allocate");
  107. bouncebuffer->size = size;
  108. }
  109. if (*buf) {
  110. memcpy(bouncebuffer->dma_buf, *buf, size);
  111. }
  112. *buf = bouncebuffer->dma_buf;
  113. #if defined(STM32H7)
  114. osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer write align");
  115. stm32_cacheBufferFlush(*buf, (size+31)&~31);
  116. #endif
  117. bouncebuffer->busy = true;
  118. }
  119. /*
  120. finish a write operation
  121. */
  122. void bouncebuffer_finish_write(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf)
  123. {
  124. if (bouncebuffer && buf == bouncebuffer->dma_buf) {
  125. osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_wite");
  126. bouncebuffer->busy = false;
  127. }
  128. }