1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-12 19:10:32 +03:00

PICO: Further implementation of DMA / SPI

This commit is contained in:
blckmn 2025-04-05 13:13:23 +11:00
parent add56ec155
commit 0b376bff50
7 changed files with 164 additions and 25 deletions

View file

@ -157,6 +157,8 @@ void spiInternalResetStream(dmaChannelDescriptor_t *descriptor)
void spiInternalInitStream(const extDevice_t *dev, bool preInit)
{
UNUSED(preInit);
int dma_tx = dma_claim_unused_channel(true);
int dma_rx = dma_claim_unused_channel(true);
@ -168,28 +170,24 @@ void spiInternalInitStream(const extDevice_t *dev, bool preInit)
const spiDevice_t *spi = &spiDevice[spiDeviceByInstance(dev->bus->busType_u.spi.instance)];
dma_channel_config config = dma_channel_get_default_config(dma_tx);
channel_config_set_transfer_data_size(&config, DMA_SIZE_8);
channel_config_set_dreq(&config, spi_get_dreq(spi, true));
channel_config_set_dreq(&config, spi_get_dreq(SPI_INST(spi->dev), true));
dma_channel_configure(dma_tx, &config, &spi_get_hw(spi)->dr, dev->txBuf, 0, false);
dma_channel_configure(dma_tx, &config, &spi_get_hw(SPI_INST(spi->dev))->dr, dev->txBuf, 0, false);
config = dma_channel_get_default_config(dma_rx);
channel_config_set_transfer_data_size(&config, DMA_SIZE_8);
channel_config_set_dreq(&config, spi_get_dreq(spi, false));
channel_config_set_dreq(&config, spi_get_dreq(SPI_INST(spi->dev), false));
dma_channel_configure(dma_rx, &config, dev->rxBuf, &spi_get_hw(spi)->dr, 0, false);
dev->
dma_channel_configure(dma_rx, &config, dev->rxBuf, &spi_get_hw(SPI_INST(spi->dev))->dr, 0, false);
}
void spiInternalStartDMA(const extDevice_t *dev)
{
const spiDevice_t *spi = &spiDevice[spiDeviceByInstance(dev->bus->busType_u.spi.instance)];
dma_channel_set_trans_count(dev->bus->dmaTx->channel, dev->bus->curSegment->len + 1, false);
dma_channel_set_trans_count(dev->bus->dmaRx->channel, dev->bus->curSegment->len + 1, false);
dma_channel_set_trans_count(dev->bus->dmaTx, dev->bus->curSegment->len + 1, false);
dma_channel_set_trans_count(dev->bus->dmaRx, dev->bus->curSegment->len + 1, false);
dma_channel_start(dev->bus->dmaTx);
dma_channel_start(dev->bus->dmaRx);
dma_channel_start(dev->bus->dmaTx->channel);
dma_channel_start(dev->bus->dmaRx->channel);
}
void spiInternalStopDMA (const extDevice_t *dev)

View file

@ -0,0 +1,108 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
#include "platform.h"
#ifdef USE_DMA_SPEC
#include "timer_def.h"
#include "drivers/adc.h"
#include "drivers/bus_spi.h"
#include "drivers/dma_reqmap.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
#include "pg/timerio.h"
#define DMA(c) { (c), (dmaResource_t *) dma_hw->ch[c] , 0 }
static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
DMA(1),
DMA(2),
DMA(3),
DMA(4),
DMA(5),
DMA(6),
DMA(7),
DMA(8),
DMA(9),
DMA(10),
DMA(11),
DMA(12),
#ifdef RP2350
DMA(13),
DMA(14),
DMA(15),
DMA(16),
#endif
};
#undef DMA
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
{
UNUSED(device);
UNUSED(index);
UNUSED(opt);
//TODO : Implementation for PICO
return NULL;
}
dmaoptValue_t dmaoptByTag(ioTag_t ioTag)
{
UNUSED(ioTag);
//TODO : Implementation for PICO
return DMA_OPT_UNUSED;
}
const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t channel, dmaoptValue_t dmaopt)
{
//TODO : Implementation for PICO
return NULL;
}
const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer)
{
if (!timer) {
return NULL;
}
//TODO : Implementation for PICO
return NULL;
}
// dmaGetOptionByTimer is called by pgResetFn_timerIOConfig to find out dmaopt for pre-configured timer.
dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
{
//TODO : Implementation for PICO
return DMA_OPT_UNUSED;
}
// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
{
//TODO : Implementation for PICO
return DMA_OPT_UNUSED;
}
#endif // USE_DMA_SPEC

View file

@ -0,0 +1,27 @@
/*
* This file is part of Betaflight.
*
* Betaflight is free software. You can redistribute this software
* and/or modify this software 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.
*
* Betaflight 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 software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
#pragma once
#define MAX_PERIPHERAL_DMA_OPTIONS 14
#define MAX_TIMER_DMA_OPTIONS 22
#define USE_DMA_MUX

View file

@ -40,6 +40,7 @@
#include "RP2350.h"
#include "pico/stdlib.h"
#include "hardware/spi.h"
#include "hardware/dma.h"
#if defined(RP2350A) || defined(RP2350B)
@ -52,7 +53,7 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define TIM_TypeDef void*
//#define TIM_OCInitTypeDef
#define DMA_TypeDef void*
//#define DMA_InitTypeDef
#define DMA_InitTypeDef void*
//#define DMA_Channel_TypeDef
#define SPI_TypeDef SPI0_Type
#define ADC_TypeDef void*
@ -69,6 +70,9 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
//#define EXTI_InitTypeDef
//#define IRQn_Type void*
#define SPI_INST(spi) ((spi_inst_t *)(spi))
#endif
#define DMA_DATA_ZERO_INIT
@ -103,3 +107,6 @@ extern uint32_t systemUniqueId[3];
#define UART_RX_BUFFER_ATTRIBUTE
#define MAX_SPI_PIN_SEL 4
#define SERIAL_TRAIT_PIN_CONFIG 1
#define xDMA_GetCurrDataCounter(dma_resource) (((dma_channel_hw_t *)(dma_resource))->transfer_count)

View file

@ -34,6 +34,7 @@
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/pwm_output.h"
#include "drivers/pwm_output_impl.h"
#include "drivers/motor_types.h"
#include "drivers/time.h"
@ -65,16 +66,6 @@ void pwmDisableMotors(void)
pwmShutdownPulsesForAllMotors();
}
bool pwmEnableMotors(void)
{
return pwmMotorCount > 0;
}
bool pwmIsMotorEnabled(unsigned index)
{
return pwmMotors[index].enabled;
}
static void pwmWriteStandard(uint8_t index, float value)
{
/* TODO: move value to be a number between 0-1 (i.e. percent throttle from mixer) */

View file

@ -26,6 +26,8 @@
#ifdef USE_UART
#include "build/build_config.h"
#include "drivers/system.h"
#include "drivers/io.h"
@ -208,4 +210,12 @@ void uartEnableTxInterrupt(uartPort_t *uartPort)
//TODO: Implement
}
#ifdef USE_DMA
void uartTryStartTxDMA(uartPort_t *s)
{
UNUSED(s);
//TODO: Implement
}
#endif
#endif /* USE_UART */

View file

@ -47,14 +47,12 @@
#define USE_VCP
#undef USE_TRANSPONDER
#undef USE_DMA
#undef USE_FLASH
#undef USE_FLASH_CHIP
#undef USE_SDCARD
#undef USE_TIMER
#undef USE_I2C
#undef USE_UART
#undef USE_RCC
#undef USE_CLI
#undef USE_RX_PWM