mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-19 14:23:57 -04:00
HAL_ChibiOS: switch to new bouncebuffer system
this removes the dma_flush and dma_invalidate methods and uses a common bouncebuffer system for all CPU types. This enables microSD support on STM32F7
This commit is contained in:
parent
0b1e26a470
commit
2493cdbcb6
@ -187,7 +187,6 @@ void AnalogIn::adccallback(ADCDriver *adcp, adcsample_t *buffer, size_t n)
|
||||
if (buffer != samples) {
|
||||
return;
|
||||
}
|
||||
dma_invalidate(buffer, ADC_DMA_BUF_DEPTH * ADC_GRP1_NUM_CHANNELS * sizeof(adcsample_t));
|
||||
for (uint8_t i = 0; i < ADC_DMA_BUF_DEPTH; i++) {
|
||||
for (uint8_t j = 0; j < ADC_GRP1_NUM_CHANNELS; j++) {
|
||||
sample_sum[j] += *buffer++;
|
||||
|
@ -20,6 +20,7 @@
|
||||
#include "Scheduler.h"
|
||||
#include "Semaphores.h"
|
||||
#include "Util.h"
|
||||
#include "hwdef/common/stm32_util.h"
|
||||
|
||||
#if HAL_USE_I2C == TRUE || HAL_USE_SPI == TRUE
|
||||
|
||||
@ -27,6 +28,13 @@ using namespace ChibiOS;
|
||||
|
||||
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
||||
|
||||
DeviceBus::DeviceBus(uint8_t _thread_priority) :
|
||||
thread_priority(_thread_priority)
|
||||
{
|
||||
bouncebuffer_init(&bounce_buffer_tx);
|
||||
bouncebuffer_init(&bounce_buffer_rx);
|
||||
}
|
||||
|
||||
/*
|
||||
per-bus callback thread
|
||||
*/
|
||||
@ -150,53 +158,25 @@ bool DeviceBus::adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_u
|
||||
void DeviceBus::bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
|
||||
uint8_t *&buf_rx, uint16_t rx_len)
|
||||
{
|
||||
bouncebuffer_setup_tx(buf_tx, tx_len);
|
||||
bouncebuffer_setup_rx(buf_rx, rx_len);
|
||||
}
|
||||
|
||||
void DeviceBus::bouncebuffer_setup_tx(const uint8_t *&buf_tx, uint16_t tx_len)
|
||||
{
|
||||
if (buf_tx && !IS_DMA_SAFE(buf_tx)) {
|
||||
if (tx_len > bounce_buffer_tx_size) {
|
||||
if (bounce_buffer_tx_size) {
|
||||
hal.util->free_type(bounce_buffer_tx, bounce_buffer_tx_size, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
bounce_buffer_tx_size = 0;
|
||||
}
|
||||
bounce_buffer_tx = (uint8_t *)hal.util->malloc_type(tx_len, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
if (bounce_buffer_tx == nullptr) {
|
||||
AP_HAL::panic("Out of memory for DMA TX");
|
||||
}
|
||||
bounce_buffer_tx_size = tx_len;
|
||||
}
|
||||
memcpy(bounce_buffer_tx, buf_tx, tx_len);
|
||||
buf_tx = bounce_buffer_tx;
|
||||
if (buf_rx) {
|
||||
bouncebuffer_setup_read(bounce_buffer_rx, &buf_rx, rx_len);
|
||||
}
|
||||
}
|
||||
|
||||
void DeviceBus::bouncebuffer_setup_rx(uint8_t *&buf_rx, uint16_t rx_len)
|
||||
{
|
||||
if (buf_rx && !IS_DMA_SAFE(buf_rx)) {
|
||||
if (rx_len > bounce_buffer_rx_size) {
|
||||
if (bounce_buffer_rx_size) {
|
||||
hal.util->free_type(bounce_buffer_rx, bounce_buffer_rx_size, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
bounce_buffer_rx_size = 0;
|
||||
}
|
||||
bounce_buffer_rx = (uint8_t *)hal.util->malloc_type(rx_len, AP_HAL::Util::MEM_DMA_SAFE);
|
||||
if (bounce_buffer_rx == nullptr) {
|
||||
AP_HAL::panic("Out of memory for DMA RX");
|
||||
}
|
||||
bounce_buffer_rx_size = rx_len;
|
||||
}
|
||||
buf_rx = bounce_buffer_rx;
|
||||
if (buf_tx) {
|
||||
bouncebuffer_setup_write(bounce_buffer_tx, &buf_tx, tx_len);
|
||||
}
|
||||
}
|
||||
|
||||
/*
|
||||
complete a transfer using DMA bounce buffer
|
||||
*/
|
||||
void DeviceBus::bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len)
|
||||
void DeviceBus::bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len)
|
||||
{
|
||||
memcpy(buf_rx, bounce_buffer_rx, rx_len);
|
||||
if (buf_rx) {
|
||||
bouncebuffer_finish_read(bounce_buffer_rx, buf_rx, rx_len);
|
||||
}
|
||||
if (buf_tx) {
|
||||
bouncebuffer_finish_write(bounce_buffer_tx, buf_tx);
|
||||
}
|
||||
}
|
||||
|
||||
#endif // HAL_USE_I2C || HAL_USE_SPI
|
||||
|
@ -19,13 +19,13 @@
|
||||
#include "Semaphores.h"
|
||||
#include "Scheduler.h"
|
||||
#include "shared_dma.h"
|
||||
#include "hwdef/common/bouncebuffer.h"
|
||||
|
||||
namespace ChibiOS {
|
||||
|
||||
class DeviceBus {
|
||||
public:
|
||||
DeviceBus(uint8_t _thread_priority = APM_I2C_PRIORITY) :
|
||||
thread_priority(_thread_priority) {}
|
||||
DeviceBus(uint8_t _thread_priority = APM_I2C_PRIORITY);
|
||||
|
||||
struct DeviceBus *next;
|
||||
Semaphore semaphore;
|
||||
@ -37,12 +37,7 @@ public:
|
||||
|
||||
void bouncebuffer_setup(const uint8_t *&buf_tx, uint16_t tx_len,
|
||||
uint8_t *&buf_rx, uint16_t rx_len);
|
||||
|
||||
void bouncebuffer_setup_tx(const uint8_t *&buf_tx, uint16_t tx_len);
|
||||
|
||||
void bouncebuffer_setup_rx(uint8_t *&buf_rx, uint16_t rx_len);
|
||||
|
||||
void bouncebuffer_rx_copy(uint8_t *buf_rx, uint16_t rx_len);
|
||||
void bouncebuffer_finish(const uint8_t *buf_tx, uint8_t *buf_rx, uint16_t rx_len);
|
||||
|
||||
private:
|
||||
struct callback_info {
|
||||
@ -57,10 +52,8 @@ private:
|
||||
AP_HAL::Device *hal_device;
|
||||
|
||||
// support for bounce buffers for DMA-safe transfers
|
||||
uint8_t *bounce_buffer_tx;
|
||||
uint8_t *bounce_buffer_rx;
|
||||
uint16_t bounce_buffer_tx_size;
|
||||
uint16_t bounce_buffer_rx_size;
|
||||
struct bouncebuffer_t *bounce_buffer_tx;
|
||||
struct bouncebuffer_t *bounce_buffer_rx;
|
||||
};
|
||||
|
||||
}
|
||||
|
@ -241,16 +241,9 @@ bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
||||
bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
uint8_t *recv, uint32_t recv_len)
|
||||
{
|
||||
uint8_t *recv_buf = recv;
|
||||
const uint8_t *send_buf = send;
|
||||
|
||||
bus.bouncebuffer_setup(send_buf, send_len, recv_buf, recv_len);
|
||||
|
||||
if (send_len) {
|
||||
dma_flush(send_buf, send_len);
|
||||
}
|
||||
|
||||
i2cAcquireBus(I2CD[bus.busnum].i2c);
|
||||
|
||||
bus.bouncebuffer_setup(send, send_len, recv, recv_len);
|
||||
|
||||
for(uint8_t i=0 ; i <= _retries; i++) {
|
||||
int ret;
|
||||
@ -260,13 +253,10 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
bus.i2c_active = true;
|
||||
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||
if(send_len == 0) {
|
||||
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv_buf, recv_len, MS2ST(timeout_ms));
|
||||
ret = i2cMasterReceiveTimeout(I2CD[bus.busnum].i2c, _address, recv, recv_len, MS2ST(timeout_ms));
|
||||
} else {
|
||||
ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send_buf, send_len,
|
||||
recv_buf, recv_len, MS2ST(timeout_ms));
|
||||
}
|
||||
if (recv_len) {
|
||||
dma_invalidate(recv_buf, recv_len);
|
||||
ret = i2cMasterTransmitTimeout(I2CD[bus.busnum].i2c, _address, send, send_len,
|
||||
recv, recv_len, MS2ST(timeout_ms));
|
||||
}
|
||||
|
||||
bus.i2c_active = false;
|
||||
@ -279,13 +269,12 @@ bool I2CDevice::_transfer(const uint8_t *send, uint32_t send_len,
|
||||
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||
} else {
|
||||
osalDbgAssert(I2CD[bus.busnum].i2c->state == I2C_READY, "i2cStart state");
|
||||
if (recv_buf != recv) {
|
||||
memcpy(recv, recv_buf, recv_len);
|
||||
}
|
||||
bus.bouncebuffer_finish(send, recv, recv_len);
|
||||
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
||||
return true;
|
||||
}
|
||||
}
|
||||
bus.bouncebuffer_finish(send, recv, recv_len);
|
||||
i2cReleaseBus(I2CD[bus.busnum].i2c);
|
||||
return false;
|
||||
}
|
||||
|
@ -932,7 +932,6 @@ void RCOutput::send_pulses_DMAR(pwm_group &group, uint32_t buffer_length)
|
||||
datasheet. Many thanks to the betaflight developers for coming
|
||||
up with this great method.
|
||||
*/
|
||||
dma_flush(group.dma_buffer, buffer_length);
|
||||
dmaStreamSetPeripheral(group.dma, &(group.pwm_drv->tim->DMAR));
|
||||
dmaStreamSetMemory0(group.dma, group.dma_buffer);
|
||||
dmaStreamSetTransactionSize(group.dma, buffer_length/sizeof(uint32_t));
|
||||
|
@ -144,26 +144,18 @@ void SPIDevice::do_transfer(const uint8_t *send, uint8_t *recv, uint32_t len)
|
||||
if (!set_chip_select(true)) {
|
||||
return;
|
||||
}
|
||||
uint8_t *recv_buf = recv;
|
||||
const uint8_t *send_buf = send;
|
||||
|
||||
bus.bouncebuffer_setup(send_buf, len, recv_buf, len);
|
||||
bus.bouncebuffer_setup(send, len, recv, len);
|
||||
|
||||
if (send == nullptr) {
|
||||
spiReceive(spi_devices[device_desc.bus].driver, len, recv_buf);
|
||||
dma_invalidate(recv_buf, len);
|
||||
spiReceive(spi_devices[device_desc.bus].driver, len, recv);
|
||||
} else if (recv == nullptr) {
|
||||
dma_flush(send_buf, len);
|
||||
spiSend(spi_devices[device_desc.bus].driver, len, send_buf);
|
||||
spiSend(spi_devices[device_desc.bus].driver, len, send);
|
||||
} else {
|
||||
dma_flush(send_buf, len);
|
||||
spiExchange(spi_devices[device_desc.bus].driver, len, send_buf, recv_buf);
|
||||
dma_invalidate(recv_buf, len);
|
||||
spiExchange(spi_devices[device_desc.bus].driver, len, send, recv);
|
||||
}
|
||||
|
||||
if (recv_buf != recv) {
|
||||
memcpy(recv, recv_buf, len);
|
||||
}
|
||||
bus.bouncebuffer_finish(send, recv, len);
|
||||
|
||||
set_chip_select(old_cs_forced);
|
||||
}
|
||||
|
@ -90,7 +90,6 @@ bool SoftSigReader::attach_capture_timer(ICUDriver* icu_drv, icuchannel_t chan,
|
||||
void SoftSigReader::_irq_handler(void* self, uint32_t flags)
|
||||
{
|
||||
SoftSigReader* sig_reader = (SoftSigReader*)self;
|
||||
dma_invalidate(sig_reader->signal, sig_reader->_bounce_buf_size);
|
||||
sig_reader->sigbuf.push(sig_reader->signal, sig_reader->_bounce_buf_size);
|
||||
//restart the DMA transfers
|
||||
dmaStreamSetMemory0(sig_reader->dma, sig_reader->signal);
|
||||
|
@ -374,7 +374,6 @@ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
|
||||
return;
|
||||
}
|
||||
|
||||
dma_invalidate(uart_drv->rx_bounce_buf, len);
|
||||
uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len);
|
||||
|
||||
uart_drv->receive_timestamp_update();
|
||||
@ -645,7 +644,6 @@ void UARTDriver::write_pending_bytes_DMA(uint32_t n)
|
||||
}
|
||||
tx_bounce_buf_ready = false;
|
||||
osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
|
||||
dma_flush(tx_bounce_buf, tx_len);
|
||||
dmaStreamSetMemory0(txdma, tx_bounce_buf);
|
||||
dmaStreamSetTransactionSize(txdma, tx_len);
|
||||
uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
|
||||
@ -747,7 +745,6 @@ void UARTDriver::_timer_tick(void)
|
||||
if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
|
||||
uint8_t len = RX_BOUNCE_BUFSIZE - rxdma->stream->NDTR;
|
||||
if (len != 0) {
|
||||
dma_invalidate(rx_bounce_buf, len);
|
||||
_readbuf.write(rx_bounce_buf, len);
|
||||
|
||||
receive_timestamp_update();
|
||||
|
@ -21,6 +21,7 @@
|
||||
#include <chheap.h>
|
||||
#include "ToneAlarm.h"
|
||||
#include "RCOutput.h"
|
||||
#include "hwdef/common/stm32_util.h"
|
||||
|
||||
#if HAL_WITH_IO_MCU
|
||||
#include <AP_BoardConfig/AP_BoardConfig.h>
|
||||
@ -34,12 +35,6 @@ using namespace ChibiOS;
|
||||
|
||||
#if CH_CFG_USE_HEAP == TRUE
|
||||
|
||||
extern "C" {
|
||||
size_t mem_available(void);
|
||||
void *malloc_ccm(size_t size);
|
||||
void *malloc_dtcm(size_t size);
|
||||
};
|
||||
|
||||
/**
|
||||
how much free memory do we have in bytes.
|
||||
*/
|
||||
@ -55,12 +50,9 @@ uint32_t Util::available_memory(void)
|
||||
|
||||
void* Util::malloc_type(size_t size, AP_HAL::Util::Memory_Type mem_type)
|
||||
{
|
||||
#if defined(DTCM_RAM_SIZE) && defined(DTCM_BASE_ADDRESS)
|
||||
if (mem_type == AP_HAL::Util::MEM_DMA_SAFE) {
|
||||
return malloc_dtcm(size);
|
||||
}
|
||||
#endif
|
||||
if (mem_type == AP_HAL::Util::MEM_FAST) {
|
||||
return malloc_dma(size);
|
||||
} else if (mem_type == AP_HAL::Util::MEM_FAST) {
|
||||
return try_alloc_from_ccm_ram(size);
|
||||
} else {
|
||||
return calloc(1, size);
|
||||
|
@ -21,14 +21,6 @@
|
||||
#include "Semaphores.h"
|
||||
#include "ToneAlarm.h"
|
||||
|
||||
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
|
||||
// on F7 we check we are in the DTCM region, and 16 bit aligned
|
||||
#define IS_DMA_SAFE(addr) ((uint32_t(addr) & 0xFFFE0001) == 0x20000000)
|
||||
#else
|
||||
// this checks an address is in main memory and 16 bit aligned
|
||||
#define IS_DMA_SAFE(addr) ((uint32_t(addr) & 0xF0000001) == 0x20000000)
|
||||
#endif
|
||||
|
||||
class ChibiOS::Util : public AP_HAL::Util {
|
||||
public:
|
||||
static Util *from(AP_HAL::Util *util) {
|
||||
|
@ -43,7 +43,7 @@ void bouncebuffer_init(struct bouncebuffer_t **bouncebuffer)
|
||||
*/
|
||||
void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf, uint32_t size)
|
||||
{
|
||||
if (IS_DMA_SAFE(*buf)) {
|
||||
if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
|
||||
// nothing needs to be done
|
||||
return;
|
||||
}
|
||||
@ -66,7 +66,7 @@ void bouncebuffer_setup_read(struct bouncebuffer_t *bouncebuffer, uint8_t **buf,
|
||||
*/
|
||||
void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf, uint32_t size)
|
||||
{
|
||||
if (buf == bouncebuffer->dma_buf) {
|
||||
if (bouncebuffer && buf == bouncebuffer->dma_buf) {
|
||||
osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_read");
|
||||
memcpy(bouncebuffer->orig_buf, buf, size);
|
||||
bouncebuffer->busy = false;
|
||||
@ -79,7 +79,7 @@ void bouncebuffer_finish_read(struct bouncebuffer_t *bouncebuffer, const uint8_t
|
||||
*/
|
||||
void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t **buf, uint32_t size)
|
||||
{
|
||||
if (IS_DMA_SAFE(*buf)) {
|
||||
if (!bouncebuffer || IS_DMA_SAFE(*buf)) {
|
||||
// nothing needs to be done
|
||||
return;
|
||||
}
|
||||
@ -103,7 +103,7 @@ void bouncebuffer_setup_write(struct bouncebuffer_t *bouncebuffer, const uint8_t
|
||||
*/
|
||||
void bouncebuffer_finish_write(struct bouncebuffer_t *bouncebuffer, const uint8_t *buf)
|
||||
{
|
||||
if (buf == bouncebuffer->dma_buf) {
|
||||
if (bouncebuffer && buf == bouncebuffer->dma_buf) {
|
||||
osalDbgAssert((bouncebuffer->busy == true), "bouncebuffer finish_wite");
|
||||
bouncebuffer->busy = false;
|
||||
}
|
||||
|
@ -129,7 +129,8 @@ CSRC = $(STARTUPSRC) \
|
||||
$(HWDEF)/common/malloc.c \
|
||||
$(HWDEF)/common/stdio.c \
|
||||
$(HWDEF)/common/hrt.c \
|
||||
$(HWDEF)/common/stm32_util.c
|
||||
$(HWDEF)/common/stm32_util.c \
|
||||
$(HWDEF)/common/bouncebuffer.c
|
||||
|
||||
ifeq ($(USE_FATFS),yes)
|
||||
CSRC += $(HWDEF)/common/posix.c
|
||||
|
@ -29,6 +29,7 @@
|
||||
#include <hal.h>
|
||||
#include <chheap.h>
|
||||
#include <stdarg.h>
|
||||
#include "stm32_util.h"
|
||||
|
||||
#define MIN_ALIGNMENT 8
|
||||
|
||||
@ -108,6 +109,22 @@ void *malloc(size_t size)
|
||||
return NULL;
|
||||
}
|
||||
|
||||
/*
|
||||
allocte DMA-safe memory
|
||||
*/
|
||||
void *malloc_dma(size_t size)
|
||||
{
|
||||
#if defined(DTCM_RAM_SIZE)
|
||||
return malloc_dtcm(size);
|
||||
#else
|
||||
void *p = chHeapAllocAligned(NULL, size, MIN_ALIGNMENT);
|
||||
if (p) {
|
||||
memset(p, 0, size);
|
||||
}
|
||||
return p;
|
||||
#endif
|
||||
}
|
||||
|
||||
void *calloc(size_t nmemb, size_t size)
|
||||
{
|
||||
return malloc(nmemb * size);
|
||||
|
@ -16,6 +16,7 @@
|
||||
#include "stm32_util.h"
|
||||
#include <stdint.h>
|
||||
#include <stdio.h>
|
||||
#include <string.h>
|
||||
|
||||
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode)
|
||||
{
|
||||
@ -35,31 +36,6 @@ void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t fil
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
/*
|
||||
invalidate data cache following a DMA transfer into memory.
|
||||
*/
|
||||
void dma_invalidate(void *buf, uint32_t size)
|
||||
{
|
||||
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
|
||||
if (((ptrdiff_t)buf) > (ptrdiff_t)0x20020000) {
|
||||
dmaBufferInvalidate(buf, size);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
/*
|
||||
flush data cache into RAM before a DMA transfer
|
||||
*/
|
||||
void dma_flush(const void *buf, uint32_t size)
|
||||
{
|
||||
#if defined(STM32F7) && STM32_DMA_CACHE_HANDLING == TRUE
|
||||
if (((ptrdiff_t)buf) > (ptrdiff_t)0x20020000) {
|
||||
dmaBufferFlush(buf, size);
|
||||
}
|
||||
#endif
|
||||
}
|
||||
|
||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||
void show_stack_usage(void)
|
||||
{
|
||||
|
@ -22,20 +22,16 @@ extern "C" {
|
||||
|
||||
void stm32_timer_set_input_filter(stm32_tim_t *tim, uint8_t channel, uint8_t filter_mode);
|
||||
|
||||
/*
|
||||
invalidate data cache following a DMA transfer into memory.
|
||||
*/
|
||||
void dma_invalidate(void *buf, uint32_t size);
|
||||
|
||||
/*
|
||||
flush data cache into RAM before a DMA transfer
|
||||
*/
|
||||
void dma_flush(const void *buf, uint32_t size);
|
||||
|
||||
#if CH_DBG_ENABLE_STACK_CHECK == TRUE
|
||||
// print stack usage
|
||||
void show_stack_usage(void);
|
||||
#endif
|
||||
|
||||
// allocation functions in malloc.c
|
||||
size_t mem_available(void);
|
||||
void *malloc_ccm(size_t size);
|
||||
void *malloc_dtcm(size_t size);
|
||||
void *malloc_dma(size_t size);
|
||||
|
||||
#ifdef __cplusplus
|
||||
}
|
||||
|
@ -252,4 +252,10 @@ define CH_DBG_ENABLE_STACK_CHECK TRUE
|
||||
|
||||
# define HAL_SPI_CHECK_CLOCK_FREQ 1
|
||||
|
||||
# enable FAT filesystem support (needs a microSD defined via SDMMC)
|
||||
define HAL_OS_FATFS_IO 1
|
||||
|
||||
define HAL_BOARD_LOG_DIRECTORY "/APM/LOGS"
|
||||
define HAL_BOARD_TERRAIN_DIRECTORY "/APM/TERRAIN"
|
||||
|
||||
ROMFS io_firmware.bin Tools/IO_Firmware/fmuv2_IO.bin
|
||||
|
@ -40,6 +40,11 @@ void sdcard_init()
|
||||
{
|
||||
#ifdef USE_POSIX
|
||||
#if HAL_USE_SDC
|
||||
|
||||
#if defined(STM32_SDC_USE_SDMMC1) && STM32_SDC_USE_SDMMC1 == TRUE
|
||||
bouncebuffer_init(&SDCD1.bouncebuffer);
|
||||
#endif
|
||||
|
||||
sdcStart(&SDCD1, NULL);
|
||||
|
||||
if(sdcConnect(&SDCD1) == HAL_FAILED) {
|
||||
|
Loading…
Reference in New Issue
Block a user