mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 03:20:00 +03:00
* serial - refactor serial resource handling - port related resources (tx/rx/inverted,dma) - are stored sequentially, with space in place of ports that are not enabled (RESOURCE_UART_COUNT + RESOURCE_LPUART_COUNT + RESOURCE_SOFTSERIAL_COUNT) - RESOURCE_UART_OFFSET, RESOURCE_LPUART_OFFSET, RESOURCE_SOFTSERIAL_OFFSET - resource entries are pointing into this array (UART, LPUART, SOFTSERIAL) - both pins and DMA - inverter is supproted only for UART + LPUART (makes sense only for UART, to be removed) - softSerialPinConfig is removed, it is no longer necessary - serialResourceIndex(identifier) is used universally to get correct index into resource array - unified handling of resources where possible - serialOwnerTxRx() + serialOwnerIndex() are used for displaying resources correctly to user. - serialType(identifier) implemented - serialOwnerTxRx / serialOwnerIndex are trivial with it - large switch() statemens are greatly simplified * serial - merge code duplicated in all UART implementations - drivers/serial_uart_hw.c contains merged serialUART code. Code did not match exactly. Obvious cases are fixed, more complicated use #ifs - pin inversion unified - uartOpen is refactored a bit * serial - refactor uartDevice - use 'compressed' enum from uartDeviceIdx_e. Only enabled ports are in this enum. - uartDeviceIdx directly indexes uartDevice (no search necessary, no wasted space) - use `serialPortIdentifier_e identifier;` for uartHardware - for DMA remap, define only entries for enabled ports (uartDeviceIdx_e does not exist disabled port) * serial - apply changes to inverter New implementation is trivial * serial - HAL - rxIrq, txIrq replaces by irqn There is only one IRQ for serial * serial - serial_post.h Generated code to normalize target configuration. jinja2 template is used to generate header file. Port handling is unified a lot. SERIAL_<type><n>_USED 0/1 - always defined, value depends on target configuration SERIAL_<type>_MASK - bitmask of used ports or given type. <port>1 is BIT(0) SERIAL_<type>_COUNT - number of enabled ports of given type SERIAL_<type>_MAX - <index of highest used port> + 1, 0 when no port is enabled * targets - remove automatically calculated valued from configs serial_post.h generated it * serial - remove definitions replaced by serial_post.h * serial - change LPUART to UART_LP1 in places LPUART is mostly handled as another UART port, this change reflects it * serial - use ARRAYLEN / ARRAYEND in some places replaces constant that may not match actual array size * serial - adapt softserial to changes * serial - whitespace, comments * softserial - fix serialTimerConfigureTimebase * serial - suspicious code * serial - unittests * serial - cleanup * serial - simpler port names Is this useful ? * serial - no port count for SITL necessary * serial - fix unittests include serial_post.h, some ports are defined, so normalization will work fine * timers - remove obsolete defines from SITL and unittests * serial - cosmetic improvements comments, whitespace, minor refactoring * serial - fix serialInit bug serialPortToDisable was preventing further tests * serial - fix possible NULL pointer dereference * serial - move serialResourceIndex to drivers * serial - refactor pp/od and pulldown/pullup/nopull Centralize serial options handling, decouple it from MCU type Move some code into new drivers/serial_impl.c * serial - make port.identifier valid early in port initialization * serial - fix unittest Code is moved around a bit to make unittests implementation easier * serial - bug - fix off-by-one error uart1/softserial1/lpuart was not working properly because of this * serial - whipespace + formating + style + comments No functional changes * utils - add popcount functions Wrap __builtin_popcount for easier use. Refactor existing code using it. Update code using BITCOUNT macro in dynamic context (BITCOUNT is for compile-time use only) * serial - inverter - simplify code * pinio - prevent array access overflow * serial - refactor SERIAL_BIDIR_* SERIAL_BIDIR_OD / SERIAL_BIDIR_PP SERIAL_PULL_DEFAULT / SERIAL_PULL_NONE / SERIAL_PULL_PD * serial - simplify code minor refactoring - cleaner AVOID_UARTx_FOR_PWM_PPM (unused anyway) - serialFindPortConfiguration* - remove code duplication - use serialType in smartaudio * serial - add port names - const string is assiociated with each compiled-in port (easy to pass around) - findSerialPortByName * cli - improve serialpassthrough - support port options (in current mode argument) - support port names (`serialpassthrough uart1`) - improve error handling; check more parse errors * cli - resources - minor refactor - prevent SERIAL_TX_NONSENSE when parsing resource type - fix possible NULL pointer dereference - store resource tag only after checking all conditions - slighty better error reporting - `resource serial_tx 1` will print resource assignment * serial - remane pulldown to SERIAL_PULL_SMARTAUDIO Make sure nobody uses it by mistake. SERIAL_PULL_SMARTAUDIO_SUPER_DANGEROUS_USE_AT_YOUR_OWN_RISK_THIS_WILL_BREAK_EVERYTHING_AND_KILL_YOUR_PET_FISH would be better choice, but try shorter version first. * smartaudio - minor refactor/improvement - Fix softserial on AT32 - make it easier to handle SA on per-cpu basis * softserial - minor refactoring no functional changes * UART - move AF handling before MCU dependent code * UART - adapt APM32 / APM32F4 code - Modeled after F4 where possible - come code moved from APM32 to APM32F4, possbily not necessary, but it improves similarity with STM32F4 * UART - APM32 - remove per-pin AF * UART - APM32 - bugfix - fix pinswap #if conditions * UART - apply some improvemnts from APM32 to STM32 * UART - add todo for F4 serial speed * UART - fix typo * UART - refactor support for USE_SMARTAUDIO_NOPULLDOWN * UART - typos, comments, minor improvements * UART - move code into enableRxIrq TODO: split into mcu-specific filer (but in sepatate PR) * UART - add UART_TRAIT_xx makes #if test easier and more consistent more traits shall follow * UART - fix variable name unused branch, would trigger compilation error otherwise * UART - use tables instead of switch * UART - smartaudio minor style change + better comments * UART - unify mspPorts iteration * UART - fix spelling * UART - another typo * UART - fix serialResourceIndex offset must be added, not subtracted offset can be negative * UART - fix typo Bad day ... * UART - use const table GCC does optimize it better. Should not cause functional change * UART - use OwnerIndex for inverter - 1 based - only UART has inversion * UART - refactor serial_resource a bit Single table + helper function. New table is easier to read * UART - serial_impl header is necessary * UART - style-only changes typos unify whitespace comment improvement add some const modifiers use cfg in uartConfigureDma minor improvemnt of for loops * UART - remove LPUART inverter LPUART always supports internal inversion, code was incomplete and unused * UART - update jinja template, regenerate files * UART - enable UART module RCC clk before configuring DMA Does not change anything, UART RCCs are enabled unconditionally
634 lines
19 KiB
C
634 lines
19 KiB
C
/*
|
|
* This file is part of Cleanflight and Betaflight.
|
|
*
|
|
* Cleanflight and Betaflight are 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.
|
|
*
|
|
* Cleanflight and Betaflight are distributed in the hope that they
|
|
* 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"
|
|
|
|
typedef struct dmaPeripheralMapping_s {
|
|
dmaPeripheral_e device;
|
|
uint8_t index;
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
uint8_t dmaRequest;
|
|
#else
|
|
dmaChannelSpec_t channelSpec[MAX_PERIPHERAL_DMA_OPTIONS];
|
|
#endif
|
|
} dmaPeripheralMapping_t;
|
|
|
|
typedef struct dmaTimerMapping_s {
|
|
TIM_TypeDef *tim;
|
|
uint8_t channel;
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
uint8_t dmaRequest;
|
|
#else
|
|
dmaChannelSpec_t channelSpec[MAX_TIMER_DMA_OPTIONS];
|
|
#endif
|
|
} dmaTimerMapping_t;
|
|
|
|
#if defined(STM32G4)
|
|
|
|
#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph }
|
|
#define REQMAP(periph, device) { DMA_PERIPH_ ## periph, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device }
|
|
#define REQMAP_DIR(periph, device, dir) { DMA_PERIPH_ ## periph ## _ ## dir, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device ## _ ## dir }
|
|
#define REQMAP_TIMUP(periph, timno) { DMA_PERIPH_TIMUP, timno - 1, DMA_REQUEST_ ## TIM ## timno ## _UP }
|
|
|
|
// Resolve UART/USART mess
|
|
#define DMA_REQUEST_UART1_RX DMA_REQUEST_USART1_RX
|
|
#define DMA_REQUEST_UART1_TX DMA_REQUEST_USART1_TX
|
|
#define DMA_REQUEST_UART2_RX DMA_REQUEST_USART2_RX
|
|
#define DMA_REQUEST_UART2_TX DMA_REQUEST_USART2_TX
|
|
#define DMA_REQUEST_UART3_RX DMA_REQUEST_USART3_RX
|
|
#define DMA_REQUEST_UART3_TX DMA_REQUEST_USART3_TX
|
|
|
|
// Resolve our preference for SDO/SDI rather than TX/RX
|
|
#define DMA_REQUEST_SPI1_SDO DMA_REQUEST_SPI1_TX
|
|
#define DMA_REQUEST_SPI1_SDI DMA_REQUEST_SPI1_RX
|
|
#define DMA_REQUEST_SPI2_SDO DMA_REQUEST_SPI2_TX
|
|
#define DMA_REQUEST_SPI2_SDI DMA_REQUEST_SPI2_RX
|
|
#define DMA_REQUEST_SPI3_SDO DMA_REQUEST_SPI3_TX
|
|
#define DMA_REQUEST_SPI3_SDI DMA_REQUEST_SPI3_RX
|
|
#define DMA_REQUEST_SPI4_SDO DMA_REQUEST_SPI4_TX
|
|
#define DMA_REQUEST_SPI4_SDI DMA_REQUEST_SPI4_RX
|
|
|
|
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
|
|
#ifdef USE_SPI
|
|
REQMAP_DIR(SPI, 1, SDO),
|
|
REQMAP_DIR(SPI, 1, SDI),
|
|
REQMAP_DIR(SPI, 2, SDO),
|
|
REQMAP_DIR(SPI, 2, SDI),
|
|
REQMAP_DIR(SPI, 3, SDO),
|
|
REQMAP_DIR(SPI, 3, SDI),
|
|
REQMAP_DIR(SPI, 4, SDO),
|
|
REQMAP_DIR(SPI, 4, SDI),
|
|
#endif // USE_SPI
|
|
|
|
#ifdef USE_ADC
|
|
REQMAP(ADC, 1),
|
|
REQMAP(ADC, 2),
|
|
REQMAP(ADC, 3),
|
|
REQMAP(ADC, 4),
|
|
REQMAP(ADC, 5),
|
|
#endif
|
|
|
|
#ifdef USE_UART1
|
|
REQMAP_DIR(UART, 1, TX),
|
|
REQMAP_DIR(UART, 1, RX),
|
|
#endif
|
|
#ifdef USE_UART2
|
|
REQMAP_DIR(UART, 2, TX),
|
|
REQMAP_DIR(UART, 2, RX),
|
|
#endif
|
|
#ifdef USE_UART3
|
|
REQMAP_DIR(UART, 3, TX),
|
|
REQMAP_DIR(UART, 3, RX),
|
|
#endif
|
|
#ifdef USE_UART4
|
|
REQMAP_DIR(UART, 4, TX),
|
|
REQMAP_DIR(UART, 4, RX),
|
|
#endif
|
|
#ifdef USE_UART5
|
|
REQMAP_DIR(UART, 5, TX),
|
|
REQMAP_DIR(UART, 5, RX),
|
|
#endif
|
|
#ifdef USE_LPUART1
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_LP1, DMA_REQUEST_LPUART1_TX },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_LP1, DMA_REQUEST_LPUART1_RX },
|
|
#endif
|
|
|
|
#ifdef USE_TIMER
|
|
// Pseudo peripheral for TIMx_UP channel
|
|
REQMAP_TIMUP(TIMUP, 1),
|
|
REQMAP_TIMUP(TIMUP, 2),
|
|
REQMAP_TIMUP(TIMUP, 3),
|
|
REQMAP_TIMUP(TIMUP, 4),
|
|
REQMAP_TIMUP(TIMUP, 5),
|
|
REQMAP_TIMUP(TIMUP, 6),
|
|
REQMAP_TIMUP(TIMUP, 7),
|
|
REQMAP_TIMUP(TIMUP, 8),
|
|
REQMAP_TIMUP(TIMUP, 15),
|
|
REQMAP_TIMUP(TIMUP, 16),
|
|
REQMAP_TIMUP(TIMUP, 17),
|
|
REQMAP_TIMUP(TIMUP, 20),
|
|
#endif
|
|
};
|
|
|
|
#undef REQMAP_TIMUP
|
|
#undef REQMAP
|
|
#undef REQMAP_SGL
|
|
#undef REQMAP_DIR
|
|
|
|
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)
|
|
|
|
#define REQMAP_TIM(tim, chan) { tim, TC(chan), DMA_REQUEST_ ## tim ## _ ## chan }
|
|
|
|
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
|
REQMAP_TIM(TIM1, CH1),
|
|
REQMAP_TIM(TIM1, CH2),
|
|
REQMAP_TIM(TIM1, CH3),
|
|
REQMAP_TIM(TIM1, CH4),
|
|
REQMAP_TIM(TIM2, CH1),
|
|
REQMAP_TIM(TIM2, CH2),
|
|
REQMAP_TIM(TIM2, CH3),
|
|
REQMAP_TIM(TIM2, CH4),
|
|
REQMAP_TIM(TIM3, CH1),
|
|
REQMAP_TIM(TIM3, CH2),
|
|
REQMAP_TIM(TIM3, CH3),
|
|
REQMAP_TIM(TIM3, CH4),
|
|
REQMAP_TIM(TIM4, CH1),
|
|
REQMAP_TIM(TIM4, CH2),
|
|
REQMAP_TIM(TIM4, CH3),
|
|
REQMAP_TIM(TIM5, CH1),
|
|
REQMAP_TIM(TIM5, CH2),
|
|
REQMAP_TIM(TIM5, CH3),
|
|
REQMAP_TIM(TIM5, CH4),
|
|
REQMAP_TIM(TIM8, CH1),
|
|
REQMAP_TIM(TIM8, CH2),
|
|
REQMAP_TIM(TIM8, CH3),
|
|
REQMAP_TIM(TIM8, CH4),
|
|
REQMAP_TIM(TIM15, CH1),
|
|
REQMAP_TIM(TIM16, CH1),
|
|
REQMAP_TIM(TIM17, CH1),
|
|
REQMAP_TIM(TIM20, CH1),
|
|
REQMAP_TIM(TIM20, CH2),
|
|
REQMAP_TIM(TIM20, CH3),
|
|
REQMAP_TIM(TIM20, CH4),
|
|
// XXX Check non-CH1 for TIM15,16,17 and 20
|
|
};
|
|
|
|
#undef TC
|
|
#undef REQMAP_TIM
|
|
|
|
#define DMA(d, c) { DMA_CODE(d, c, 0), (dmaResource_t *)DMA ## d ## _Channel ## c, 0 }
|
|
|
|
static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
|
|
DMA(1, 1),
|
|
DMA(1, 2),
|
|
DMA(1, 3),
|
|
DMA(1, 4),
|
|
DMA(1, 5),
|
|
DMA(1, 6),
|
|
DMA(1, 7),
|
|
DMA(1, 8),
|
|
DMA(2, 1),
|
|
DMA(2, 2),
|
|
DMA(2, 3),
|
|
DMA(2, 4),
|
|
DMA(2, 5),
|
|
DMA(2, 6),
|
|
DMA(2, 7),
|
|
DMA(2, 8),
|
|
};
|
|
|
|
#undef DMA
|
|
|
|
#elif defined(STM32H7)
|
|
|
|
#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph }
|
|
#define REQMAP(periph, device) { DMA_PERIPH_ ## periph, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device }
|
|
#define REQMAP_DIR(periph, device, dir) { DMA_PERIPH_ ## periph ## _ ## dir, periph ## DEV_ ## device, DMA_REQUEST_ ## periph ## device ## _ ## dir }
|
|
#define REQMAP_TIMUP(periph, timno) { DMA_PERIPH_TIMUP, timno - 1, DMA_REQUEST_ ## TIM ## timno ## _UP }
|
|
|
|
// Resolve UART/USART mess
|
|
#define DMA_REQUEST_UART1_RX DMA_REQUEST_USART1_RX
|
|
#define DMA_REQUEST_UART1_TX DMA_REQUEST_USART1_TX
|
|
#define DMA_REQUEST_UART2_RX DMA_REQUEST_USART2_RX
|
|
#define DMA_REQUEST_UART2_TX DMA_REQUEST_USART2_TX
|
|
#define DMA_REQUEST_UART3_RX DMA_REQUEST_USART3_RX
|
|
#define DMA_REQUEST_UART3_TX DMA_REQUEST_USART3_TX
|
|
#define DMA_REQUEST_UART6_RX DMA_REQUEST_USART6_RX
|
|
#define DMA_REQUEST_UART6_TX DMA_REQUEST_USART6_TX
|
|
#define DMA_REQUEST_UART10_RX DMA_REQUEST_USART10_RX
|
|
#define DMA_REQUEST_UART10_TX DMA_REQUEST_USART10_TX
|
|
|
|
// Resolve our preference for SDO/SDI rather than TX/RX
|
|
#define DMA_REQUEST_SPI1_SDO DMA_REQUEST_SPI1_TX
|
|
#define DMA_REQUEST_SPI1_SDI DMA_REQUEST_SPI1_RX
|
|
#define DMA_REQUEST_SPI2_SDO DMA_REQUEST_SPI2_TX
|
|
#define DMA_REQUEST_SPI2_SDI DMA_REQUEST_SPI2_RX
|
|
#define DMA_REQUEST_SPI3_SDO DMA_REQUEST_SPI3_TX
|
|
#define DMA_REQUEST_SPI3_SDI DMA_REQUEST_SPI3_RX
|
|
#define DMA_REQUEST_SPI4_SDO DMA_REQUEST_SPI4_TX
|
|
#define DMA_REQUEST_SPI4_SDI DMA_REQUEST_SPI4_RX
|
|
#define DMA_REQUEST_SPI5_SDO DMA_REQUEST_SPI5_TX
|
|
#define DMA_REQUEST_SPI5_SDI DMA_REQUEST_SPI5_RX
|
|
|
|
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
|
|
#ifdef USE_SPI
|
|
REQMAP_DIR(SPI, 1, SDO),
|
|
REQMAP_DIR(SPI, 1, SDI),
|
|
REQMAP_DIR(SPI, 2, SDO),
|
|
REQMAP_DIR(SPI, 2, SDI),
|
|
REQMAP_DIR(SPI, 3, SDO),
|
|
REQMAP_DIR(SPI, 3, SDI),
|
|
REQMAP_DIR(SPI, 4, SDO),
|
|
REQMAP_DIR(SPI, 4, SDI),
|
|
REQMAP_DIR(SPI, 5, SDO), // Not available in smaller packages
|
|
REQMAP_DIR(SPI, 5, SDI), // ditto
|
|
// REQMAP_DIR(SPI, 6, SDO), // SPI6 is on BDMA (todo)
|
|
// REQMAP_DIR(SPI, 6, SDO), // ditto
|
|
#endif // USE_SPI
|
|
|
|
#ifdef USE_ADC
|
|
REQMAP(ADC, 1),
|
|
REQMAP(ADC, 2),
|
|
#if defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) || defined(STM32H730xx)
|
|
REQMAP(ADC, 3),
|
|
#endif
|
|
#endif
|
|
|
|
#ifdef USE_UART1
|
|
REQMAP_DIR(UART, 1, TX),
|
|
REQMAP_DIR(UART, 1, RX),
|
|
#endif
|
|
#ifdef USE_UART2
|
|
REQMAP_DIR(UART, 2, TX),
|
|
REQMAP_DIR(UART, 2, RX),
|
|
#endif
|
|
#ifdef USE_UART3
|
|
REQMAP_DIR(UART, 3, TX),
|
|
REQMAP_DIR(UART, 3, RX),
|
|
#endif
|
|
#ifdef USE_UART4
|
|
REQMAP_DIR(UART, 4, TX),
|
|
REQMAP_DIR(UART, 4, RX),
|
|
#endif
|
|
#ifdef USE_UART5
|
|
REQMAP_DIR(UART, 5, TX),
|
|
REQMAP_DIR(UART, 5, RX),
|
|
#endif
|
|
#ifdef USE_UART6
|
|
REQMAP_DIR(UART, 6, TX),
|
|
REQMAP_DIR(UART, 6, RX),
|
|
#endif
|
|
#ifdef USE_UART7
|
|
REQMAP_DIR(UART, 7, TX),
|
|
REQMAP_DIR(UART, 7, RX),
|
|
#endif
|
|
#ifdef USE_UART8
|
|
REQMAP_DIR(UART, 8, TX),
|
|
REQMAP_DIR(UART, 8, RX),
|
|
#endif
|
|
#ifdef USE_UART9
|
|
REQMAP_DIR(UART, 9, TX),
|
|
REQMAP_DIR(UART, 9, RX),
|
|
#endif
|
|
#ifdef USE_UART10
|
|
REQMAP_DIR(UART, 10, TX),
|
|
REQMAP_DIR(UART, 10, RX),
|
|
#endif
|
|
#ifdef USE_LPUART1
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_LP1, BDMA_REQUEST_LPUART1_TX },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_LP1, BDMA_REQUEST_LPUART1_RX },
|
|
#endif
|
|
|
|
#ifdef USE_TIMER
|
|
// Pseudo peripheral for TIMx_UP channel
|
|
REQMAP_TIMUP(TIMUP, 1),
|
|
REQMAP_TIMUP(TIMUP, 2),
|
|
REQMAP_TIMUP(TIMUP, 3),
|
|
REQMAP_TIMUP(TIMUP, 4),
|
|
REQMAP_TIMUP(TIMUP, 5),
|
|
REQMAP_TIMUP(TIMUP, 6),
|
|
REQMAP_TIMUP(TIMUP, 7),
|
|
REQMAP_TIMUP(TIMUP, 8),
|
|
REQMAP_TIMUP(TIMUP, 15),
|
|
REQMAP_TIMUP(TIMUP, 16),
|
|
REQMAP_TIMUP(TIMUP, 17),
|
|
#endif
|
|
};
|
|
|
|
#undef REQMAP_TIMUP
|
|
#undef REQMAP
|
|
#undef REQMAP_SGL
|
|
#undef REQMAP_DIR
|
|
|
|
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)
|
|
|
|
#define REQMAP_TIM(tim, chan) { tim, TC(chan), DMA_REQUEST_ ## tim ## _ ## chan }
|
|
|
|
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
|
REQMAP_TIM(TIM1, CH1),
|
|
REQMAP_TIM(TIM1, CH2),
|
|
REQMAP_TIM(TIM1, CH3),
|
|
REQMAP_TIM(TIM1, CH4),
|
|
REQMAP_TIM(TIM2, CH1),
|
|
REQMAP_TIM(TIM2, CH2),
|
|
REQMAP_TIM(TIM2, CH3),
|
|
REQMAP_TIM(TIM2, CH4),
|
|
REQMAP_TIM(TIM3, CH1),
|
|
REQMAP_TIM(TIM3, CH2),
|
|
REQMAP_TIM(TIM3, CH3),
|
|
REQMAP_TIM(TIM3, CH4),
|
|
REQMAP_TIM(TIM4, CH1),
|
|
REQMAP_TIM(TIM4, CH2),
|
|
REQMAP_TIM(TIM4, CH3),
|
|
REQMAP_TIM(TIM5, CH1),
|
|
REQMAP_TIM(TIM5, CH2),
|
|
REQMAP_TIM(TIM5, CH3),
|
|
REQMAP_TIM(TIM5, CH4),
|
|
REQMAP_TIM(TIM8, CH1),
|
|
REQMAP_TIM(TIM8, CH2),
|
|
REQMAP_TIM(TIM8, CH3),
|
|
REQMAP_TIM(TIM8, CH4),
|
|
REQMAP_TIM(TIM15, CH1),
|
|
REQMAP_TIM(TIM16, CH1),
|
|
REQMAP_TIM(TIM17, CH1),
|
|
};
|
|
|
|
#undef TC
|
|
#undef REQMAP_TIM
|
|
|
|
#define DMA(d, s) { DMA_CODE(d, s, 0), (dmaResource_t *)DMA ## d ## _Stream ## s, 0 }
|
|
|
|
static dmaChannelSpec_t dmaChannelSpec[MAX_PERIPHERAL_DMA_OPTIONS] = {
|
|
DMA(1, 0),
|
|
DMA(1, 1),
|
|
DMA(1, 2),
|
|
DMA(1, 3),
|
|
DMA(1, 4),
|
|
DMA(1, 5),
|
|
DMA(1, 6),
|
|
DMA(1, 7),
|
|
DMA(2, 0),
|
|
DMA(2, 1),
|
|
DMA(2, 2),
|
|
DMA(2, 3),
|
|
DMA(2, 4),
|
|
DMA(2, 5),
|
|
DMA(2, 6),
|
|
DMA(2, 7),
|
|
};
|
|
|
|
#undef DMA
|
|
|
|
#elif defined(STM32F4) || defined(STM32F7)
|
|
|
|
#if defined(STM32F4)
|
|
#define DMA(d, s, c) { DMA_CODE(d, s, c), (dmaResource_t *)DMA ## d ## _Stream ## s, DMA_Channel_ ## c }
|
|
#elif defined(STM32F7)
|
|
#define DMA(d, s, c) { DMA_CODE(d, s, c), (dmaResource_t *)DMA ## d ## _Stream ## s, DMA_CHANNEL_ ## c }
|
|
#endif
|
|
|
|
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
|
|
#ifdef USE_SPI
|
|
// Everything including F405 and F446
|
|
#if defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx)
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_1, { DMA(2, 5, 3), DMA(2, 3, 3) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_1, { DMA(2, 2, 3), DMA(2, 0, 3) } },
|
|
#else
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_1, { DMA(2, 3, 3), DMA(2, 5, 3) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_1, { DMA(2, 0, 3), DMA(2, 2, 3) } },
|
|
#endif
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_2, { DMA(1, 4, 0) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_2, { DMA(1, 3, 0) } },
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_3, { DMA(1, 5, 0), DMA(1, 7, 0) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_3, { DMA(1, 0, 0), DMA(1, 2, 0) } },
|
|
|
|
#if defined(STM32F411xE) || defined(STM32F745xx) || defined(STM32F746xx) || defined(STM32F765xx) || defined(STM32F722xx)
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_4, { DMA(2, 1, 4), DMA(2, 4, 5) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_4, { DMA(2, 0, 4), DMA(2, 3, 5) } },
|
|
|
|
#ifdef USE_EXTENDED_SPI_DEVICE
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_5, { DMA(2, 6, 7) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_5, { DMA(2, 5, 7) } },
|
|
|
|
#if !defined(STM32F722xx)
|
|
{ DMA_PERIPH_SPI_SDO, SPIDEV_6, { DMA(2, 5, 1) } },
|
|
{ DMA_PERIPH_SPI_SDI, SPIDEV_6, { DMA(2, 6, 1) } },
|
|
#endif
|
|
#endif // USE_EXTENDED_SPI_DEVICE
|
|
#endif
|
|
#endif // USE_SPI
|
|
|
|
#ifdef USE_ADC
|
|
{ DMA_PERIPH_ADC, ADCDEV_1, { DMA(2, 0, 0), DMA(2, 4, 0) } },
|
|
{ DMA_PERIPH_ADC, ADCDEV_2, { DMA(2, 2, 1), DMA(2, 3, 1) } },
|
|
{ DMA_PERIPH_ADC, ADCDEV_3, { DMA(2, 0, 2), DMA(2, 1, 2) } },
|
|
#endif
|
|
|
|
#ifdef USE_SDCARD_SDIO
|
|
{ DMA_PERIPH_SDIO, 0, { DMA(2, 3, 4), DMA(2, 6, 4) } },
|
|
#endif
|
|
|
|
#ifdef USE_UART1
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_1, { DMA(2, 7, 4) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_1, { DMA(2, 5, 4), DMA(2, 2, 4) } },
|
|
#endif
|
|
#ifdef USE_UART2
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_2, { DMA(1, 6, 4) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_2, { DMA(1, 5, 4) } },
|
|
#endif
|
|
#ifdef USE_UART3
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_3, { DMA(1, 3, 4) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_3, { DMA(1, 1, 4) } },
|
|
#endif
|
|
#ifdef USE_UART4
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_4, { DMA(1, 4, 4) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_4, { DMA(1, 2, 4) } },
|
|
#endif
|
|
#ifdef USE_UART5
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_5, { DMA(1, 7, 4) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_5, { DMA(1, 0, 4) } },
|
|
#endif
|
|
#ifdef USE_UART6
|
|
{ DMA_PERIPH_UART_TX, UARTDEV_6, { DMA(2, 6, 5), DMA(2, 7, 5) } },
|
|
{ DMA_PERIPH_UART_RX, UARTDEV_6, { DMA(2, 1, 5), DMA(2, 2, 5) } },
|
|
#endif
|
|
};
|
|
|
|
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan)
|
|
|
|
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
|
// Generated from 'timer_def.h'
|
|
{ TIM1, TC(CH1), { DMA(2, 6, 0), DMA(2, 1, 6), DMA(2, 3, 6) } },
|
|
{ TIM1, TC(CH2), { DMA(2, 6, 0), DMA(2, 2, 6) } },
|
|
{ TIM1, TC(CH3), { DMA(2, 6, 0), DMA(2, 6, 6) } },
|
|
{ TIM1, TC(CH4), { DMA(2, 4, 6) } },
|
|
|
|
{ TIM2, TC(CH1), { DMA(1, 5, 3) } },
|
|
{ TIM2, TC(CH2), { DMA(1, 6, 3) } },
|
|
{ TIM2, TC(CH3), { DMA(1, 1, 3) } },
|
|
{ TIM2, TC(CH4), { DMA(1, 7, 3), DMA(1, 6, 3) } },
|
|
|
|
{ TIM3, TC(CH1), { DMA(1, 4, 5) } },
|
|
{ TIM3, TC(CH2), { DMA(1, 5, 5) } },
|
|
{ TIM3, TC(CH3), { DMA(1, 7, 5) } },
|
|
{ TIM3, TC(CH4), { DMA(1, 2, 5) } },
|
|
|
|
{ TIM4, TC(CH1), { DMA(1, 0, 2) } },
|
|
{ TIM4, TC(CH2), { DMA(1, 3, 2) } },
|
|
{ TIM4, TC(CH3), { DMA(1, 7, 2) } },
|
|
|
|
{ TIM5, TC(CH1), { DMA(1, 2, 6) } },
|
|
{ TIM5, TC(CH2), { DMA(1, 4, 6) } },
|
|
{ TIM5, TC(CH3), { DMA(1, 0, 6) } },
|
|
{ TIM5, TC(CH4), { DMA(1, 1, 6), DMA(1, 3, 6) } },
|
|
|
|
{ TIM8, TC(CH1), { DMA(2, 2, 0), DMA(2, 2, 7) } },
|
|
{ TIM8, TC(CH2), { DMA(2, 2, 0), DMA(2, 3, 7) } },
|
|
{ TIM8, TC(CH3), { DMA(2, 2, 0), DMA(2, 4, 7) } },
|
|
{ TIM8, TC(CH4), { DMA(2, 7, 7) } },
|
|
};
|
|
#undef TC
|
|
#undef DMA
|
|
#endif
|
|
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request)
|
|
{
|
|
// Setup request as channel
|
|
dmaSpec->channel = request;
|
|
|
|
// Insert DMA request into code
|
|
dmaCode_t code = dmaSpec->code;
|
|
dmaSpec->code = DMA_CODE(DMA_CODE_CONTROLLER(code), DMA_CODE_STREAM(code), dmaSpec->channel);
|
|
}
|
|
#endif
|
|
|
|
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
|
{
|
|
if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) {
|
|
return NULL;
|
|
}
|
|
|
|
for (const dmaPeripheralMapping_t *periph = dmaPeripheralMapping; periph < ARRAYEND(dmaPeripheralMapping) ; periph++) {
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
if (periph->device == device && periph->index == index) {
|
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];
|
|
dmaSetupRequest(dmaSpec, periph->dmaRequest);
|
|
return dmaSpec;
|
|
}
|
|
#else
|
|
if (periph->device == device && periph->index == index && periph->channelSpec[opt].ref) {
|
|
return &periph->channelSpec[opt];
|
|
}
|
|
#endif
|
|
}
|
|
|
|
return NULL;
|
|
}
|
|
|
|
dmaoptValue_t dmaoptByTag(ioTag_t ioTag)
|
|
{
|
|
#ifdef USE_TIMER_MGMT
|
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
|
if (timerIOConfig(i)->ioTag == ioTag) {
|
|
return timerIOConfig(i)->dmaopt;
|
|
}
|
|
}
|
|
#else
|
|
UNUSED(ioTag);
|
|
#endif
|
|
|
|
return DMA_OPT_UNUSED;
|
|
}
|
|
|
|
const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t channel, dmaoptValue_t dmaopt)
|
|
{
|
|
if (dmaopt < 0 || dmaopt >= MAX_TIMER_DMA_OPTIONS) {
|
|
return NULL;
|
|
}
|
|
|
|
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping) ; i++) {
|
|
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
if (timerMapping->tim == tim && timerMapping->channel == channel) {
|
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt];
|
|
dmaSetupRequest(dmaSpec, timerMapping->dmaRequest);
|
|
return dmaSpec;
|
|
}
|
|
#else
|
|
if (timerMapping->tim == tim && timerMapping->channel == channel && timerMapping->channelSpec[dmaopt].ref) {
|
|
return &timerMapping->channelSpec[dmaopt];
|
|
}
|
|
#endif
|
|
}
|
|
|
|
return NULL;
|
|
}
|
|
|
|
const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer)
|
|
{
|
|
if (!timer) {
|
|
return NULL;
|
|
}
|
|
|
|
dmaoptValue_t dmaopt = dmaoptByTag(timer->tag);
|
|
return dmaGetChannelSpecByTimerValue(timer->tim, timer->channel, dmaopt);
|
|
}
|
|
|
|
// dmaGetOptionByTimer is called by pgResetFn_timerIOConfig to find out dmaopt for pre-configured timer.
|
|
|
|
dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
|
|
{
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
|
|
if (timer->dmaRefConfigured == dmaChannelSpec[opt].ref) {
|
|
return (dmaoptValue_t)opt;
|
|
}
|
|
}
|
|
#else
|
|
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping); i++) {
|
|
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
|
|
if (timerMapping->tim == timer->tim && timerMapping->channel == timer->channel) {
|
|
for (unsigned j = 0; j < MAX_TIMER_DMA_OPTIONS; j++) {
|
|
const dmaChannelSpec_t *dma = &timerMapping->channelSpec[j];
|
|
if (dma->ref == timer->dmaRefConfigured
|
|
#if defined(STM32F4) || defined(STM32F7)
|
|
&& dma->channel == timer->dmaChannelConfigured
|
|
#endif
|
|
) {
|
|
return j;
|
|
}
|
|
}
|
|
}
|
|
}
|
|
#endif
|
|
|
|
return DMA_OPT_UNUSED;
|
|
}
|
|
|
|
#if defined(STM32H7) || defined(STM32G4)
|
|
// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
|
|
dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
|
|
{
|
|
for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
|
|
if (timer->dmaTimUPRef == dmaChannelSpec[opt].ref) {
|
|
return (dmaoptValue_t)opt;
|
|
}
|
|
}
|
|
|
|
return DMA_OPT_UNUSED;
|
|
}
|
|
#endif
|
|
|
|
#endif // USE_DMA_SPEC
|