2018-06-02 00:25:55 -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/>.
|
|
|
|
*/
|
|
|
|
/*
|
|
|
|
bouncebuffer code for DMA safe memory operations
|
|
|
|
*/
|
|
|
|
#include "stm32_util.h"
|
|
|
|
#include <stdint.h>
|
|
|
|
#include <string.h>
|
|
|
|
#include <stdio.h>
|
|
|
|
#include "bouncebuffer.h"
|
|
|
|
|
2019-02-09 17:52:15 -04:00
|
|
|
#if defined(STM32H7)
|
|
|
|
// always use a bouncebuffer on H7, to ensure alignment and padding
|
|
|
|
#define IS_DMA_SAFE(addr) false
|
2019-02-17 20:10:53 -04:00
|
|
|
#elif defined(STM32F7)
|
|
|
|
// on F76x we only consider first half of DTCM memory as DMA safe, 2nd half is used as fast memory for EKF
|
|
|
|
// on F74x we only have 64k of DTCM
|
|
|
|
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & ((0xFFFFFFFF & ~(64*1024U-1)) | 1U)) == 0x20000000)
|
2019-05-26 22:45:30 -03:00
|
|
|
#elif defined(STM32F1)
|
|
|
|
#define IS_DMA_SAFE(addr) true
|
2018-06-02 00:25:55 -03:00
|
|
|
#else
|
|
|
|
// this checks an address is in main memory and 16 bit aligned
|
|
|
|
#define IS_DMA_SAFE(addr) ((((uint32_t)(addr)) & 0xF0000001) == 0x20000000)
|
|
|
|
#endif
|
|
|
|
|
|
|
|
/*
|
|
|
|
initialise a bouncebuffer
|
|
|
|
*/
|
2019-03-06 20:21:51 -04:00
|
|
|
void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer, uint32_t prealloc_bytes, bool sdcard)
|
2018-06-02 00:25:55 -03:00
|
|
|
{
|
|
|
|
(*bouncebuffer) = calloc(1, sizeof(struct bouncebuffer_t));
|
|
|
|
osalDbgAssert(((*bouncebuffer) != NULL), "bouncebuffer init");
|
2019-03-06 20:21:51 -04:00
|
|
|
(*bouncebuffer)->is_sdcard = sdcard;
|
2018-07-12 00:12:21 -03:00
|
|
|
if (prealloc_bytes) {
|
2019-03-06 20:21:51 -04:00
|
|
|
(*bouncebuffer)->dma_buf = sdcard?malloc_sdcard_dma(prealloc_bytes):malloc_dma(prealloc_bytes);
|
2020-01-17 21:27:23 -04:00
|
|
|
if ((*bouncebuffer)->dma_buf) {
|
|
|
|
(*bouncebuffer)->size = prealloc_bytes;
|
|
|
|
}
|
2018-07-12 00:12:21 -03:00
|
|
|
}
|
2018-06-02 00:25:55 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup for reading from a device into memory, allocating a bouncebuffer if needed
|
2019-02-17 19:21:28 -04:00
|
|
|
Note that *buf can be NULL, in which case we allocate DMA capable memory, but don't
|
|
|
|
copy to it in bouncebuffer_finish_read(). This avoids DMA failures in dummyrx in the SPI LLD
|
2018-06-02 00:25:55 -03:00
|
|
|
*/
|
2020-01-17 21:27:23 -04:00
|
|
|
bool bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, uint32_t size)
|
2018-06-02 00:25:55 -03:00
|
|
|
{
|
2018-06-02 00:27:02 -03:00
|
|
|
if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
|
2018-06-02 00:25:55 -03:00
|
|
|
// nothing needs to be done
|
2020-01-17 21:27:23 -04:00
|
|
|
return true;
|
2018-06-02 00:25:55 -03:00
|
|
|
}
|
|
|
|
osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer read");
|
|
|
|
bouncebuffer->orig_buf = *buf;
|
|
|
|
if (bouncebuffer->size < size) {
|
|
|
|
if (bouncebuffer->size > 0) {
|
|
|
|
free(bouncebuffer->dma_buf);
|
|
|
|
}
|
2019-03-06 20:21:51 -04:00
|
|
|
bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
|
2020-01-17 21:27:23 -04:00
|
|
|
if (!bouncebuffer->dma_buf) {
|
|
|
|
bouncebuffer->size = 0;
|
|
|
|
return false;
|
|
|
|
}
|
2018-06-02 00:25:55 -03:00
|
|
|
bouncebuffer->size = size;
|
|
|
|
}
|
|
|
|
*buf = bouncebuffer->dma_buf;
|
2019-02-09 17:52:15 -04:00
|
|
|
#if defined(STM32H7)
|
|
|
|
osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer read align");
|
2019-08-02 07:57:01 -03:00
|
|
|
stm32_cacheBufferInvalidate(*buf, (size+31)&~31);
|
2019-02-09 17:52:15 -04:00
|
|
|
#endif
|
2018-06-02 00:25:55 -03:00
|
|
|
bouncebuffer->busy = true;
|
2020-01-17 21:27:23 -04:00
|
|
|
return true;
|
2018-06-02 00:25:55 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
/*
|
|
|
|
finish a read operation
|
|
|
|
*/
|
|
|
|
void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf, uint32_t size)
|
|
|
|
{
|
2018-06-02 00:27:02 -03:00
|
|
|
if (bouncebuffer && buf == bouncebuffer->dma_buf) {
|
2019-02-17 19:21:28 -04:00
|
|
|
osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_read");
|
|
|
|
if (bouncebuffer->orig_buf) {
|
|
|
|
memcpy(bouncebuffer->orig_buf, buf, size);
|
|
|
|
}
|
2018-06-02 00:25:55 -03:00
|
|
|
bouncebuffer->busy = false;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
setup for reading from memory to a device, allocating a bouncebuffer if needed
|
|
|
|
*/
|
2020-01-17 21:27:23 -04:00
|
|
|
bool bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t **buf, uint32_t size)
|
2018-06-02 00:25:55 -03:00
|
|
|
{
|
2018-06-02 00:27:02 -03:00
|
|
|
if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
|
2018-06-02 00:25:55 -03:00
|
|
|
// nothing needs to be done
|
2020-01-17 21:27:23 -04:00
|
|
|
return true;
|
2018-06-02 00:25:55 -03:00
|
|
|
}
|
|
|
|
osalDbgAssert((bouncebuffer->busy == false), "bouncebuffer write");
|
|
|
|
if (bouncebuffer->size < size) {
|
|
|
|
if (bouncebuffer->size > 0) {
|
|
|
|
free(bouncebuffer->dma_buf);
|
|
|
|
}
|
2019-03-06 20:21:51 -04:00
|
|
|
bouncebuffer->dma_buf = bouncebuffer->is_sdcard?malloc_sdcard_dma(size):malloc_dma(size);
|
2020-01-17 21:27:23 -04:00
|
|
|
if (!bouncebuffer->dma_buf) {
|
|
|
|
bouncebuffer->size = 0;
|
|
|
|
return false;
|
|
|
|
}
|
2018-06-02 00:25:55 -03:00
|
|
|
bouncebuffer->size = size;
|
|
|
|
}
|
2019-02-17 19:21:28 -04:00
|
|
|
if (*buf) {
|
|
|
|
memcpy(bouncebuffer->dma_buf, *buf, size);
|
|
|
|
}
|
2018-06-02 00:25:55 -03:00
|
|
|
*buf = bouncebuffer->dma_buf;
|
2019-02-09 17:52:15 -04:00
|
|
|
#if defined(STM32H7)
|
|
|
|
osalDbgAssert((((uint32_t)*buf)&31) == 0, "bouncebuffer write align");
|
2019-08-02 07:57:01 -03:00
|
|
|
stm32_cacheBufferFlush(*buf, (size+31)&~31);
|
2019-02-09 17:52:15 -04:00
|
|
|
#endif
|
2018-06-02 00:25:55 -03:00
|
|
|
bouncebuffer->busy = true;
|
2020-01-17 21:27:23 -04:00
|
|
|
return true;
|
2018-06-02 00:25:55 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
|
|
|
|
/*
|
|
|
|
finish a write operation
|
|
|
|
*/
|
|
|
|
void bouncebuffer_finish_write(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf)
|
|
|
|
{
|
2018-06-02 00:27:02 -03:00
|
|
|
if (bouncebuffer && buf == bouncebuffer->dma_buf) {
|
2018-06-02 00:25:55 -03:00
|
|
|
osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_wite");
|
|
|
|
bouncebuffer->busy = false;
|
|
|
|
}
|
|
|
|
}
|
2020-01-17 21:27:23 -04:00
|
|
|
|
|
|
|
/*
|
|
|
|
abort an operation
|
|
|
|
*/
|
|
|
|
void bouncebuffer_abort(struct bouncebuffer_t *bouncebuffer)
|
|
|
|
{
|
|
|
|
if (bouncebuffer) {
|
|
|
|
bouncebuffer->busy = false;
|
|
|
|
}
|
|
|
|
}
|