mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-15 20:35:33 +03:00
REFACTOR: moving timer definitions to MCU locations. (#12397)
* REFACTOR: moving timer definitions to MCU locations. * Now that the MCU directory needs to be included in the search path for includes, no need for target.h entry if filenaming is consistent. * SITL needs the empty include.
This commit is contained in:
parent
c4ab98258e
commit
82566eb89a
40 changed files with 547 additions and 299 deletions
|
@ -0,0 +1,6 @@
|
||||||
|
#
|
||||||
|
# AT32F4 Make file include
|
||||||
|
#
|
||||||
|
|
||||||
|
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
|
$(ROOT)/src/main/drivers/at32
|
|
@ -94,6 +94,9 @@ endif
|
||||||
#CMSIS
|
#CMSIS
|
||||||
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx
|
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx
|
||||||
|
|
||||||
|
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
|
$(ROOT)/src/main/drivers/stm32
|
||||||
|
|
||||||
ifeq ($(PERIPH_DRIVER), HAL)
|
ifeq ($(PERIPH_DRIVER), HAL)
|
||||||
CMSIS_SRC :=
|
CMSIS_SRC :=
|
||||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
|
@ -155,6 +158,7 @@ MCU_COMMON_SRC = \
|
||||||
drivers/stm32/bus_i2c_stm32f4xx.c \
|
drivers/stm32/bus_i2c_stm32f4xx.c \
|
||||||
drivers/stm32/bus_spi_stdperiph.c \
|
drivers/stm32/bus_spi_stdperiph.c \
|
||||||
drivers/stm32/debug.c \
|
drivers/stm32/debug.c \
|
||||||
|
drivers/stm32/dma_reqmap_mcu.c \
|
||||||
drivers/stm32/dma_stm32f4xx.c \
|
drivers/stm32/dma_stm32f4xx.c \
|
||||||
drivers/stm32/dshot_bitbang.c \
|
drivers/stm32/dshot_bitbang.c \
|
||||||
drivers/stm32/dshot_bitbang_stdperiph.c \
|
drivers/stm32/dshot_bitbang_stdperiph.c \
|
||||||
|
|
|
@ -108,6 +108,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(USBMSC_DIR)/Inc \
|
$(USBMSC_DIR)/Inc \
|
||||||
$(CMSIS_DIR)/Core/Include \
|
$(CMSIS_DIR)/Core/Include \
|
||||||
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
|
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
|
||||||
|
$(ROOT)/src/main/drivers/stm32 \
|
||||||
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
||||||
|
|
||||||
#Flags
|
#Flags
|
||||||
|
@ -165,6 +166,7 @@ MCU_COMMON_SRC = \
|
||||||
drivers/stm32/bus_i2c_hal.c \
|
drivers/stm32/bus_i2c_hal.c \
|
||||||
drivers/stm32/bus_spi_ll.c \
|
drivers/stm32/bus_spi_ll.c \
|
||||||
drivers/stm32/debug.c \
|
drivers/stm32/debug.c \
|
||||||
|
drivers/stm32/dma_reqmap_mcu.c \
|
||||||
drivers/stm32/dma_stm32f7xx.c \
|
drivers/stm32/dma_stm32f7xx.c \
|
||||||
drivers/stm32/dshot_bitbang_ll.c \
|
drivers/stm32/dshot_bitbang_ll.c \
|
||||||
drivers/stm32/dshot_bitbang.c \
|
drivers/stm32/dshot_bitbang.c \
|
||||||
|
|
|
@ -111,6 +111,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(USBMSC_DIR)/Inc \
|
$(USBMSC_DIR)/Inc \
|
||||||
$(CMSIS_DIR)/Core/Include \
|
$(CMSIS_DIR)/Core/Include \
|
||||||
$(ROOT)/lib/main/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \
|
$(ROOT)/lib/main/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \
|
||||||
|
$(ROOT)/src/main/drivers/stm32 \
|
||||||
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
||||||
|
|
||||||
#Flags
|
#Flags
|
||||||
|
@ -151,6 +152,7 @@ MCU_COMMON_SRC = \
|
||||||
drivers/stm32/bus_i2c_hal.c \
|
drivers/stm32/bus_i2c_hal.c \
|
||||||
drivers/stm32/bus_spi_ll.c \
|
drivers/stm32/bus_spi_ll.c \
|
||||||
drivers/stm32/debug.c \
|
drivers/stm32/debug.c \
|
||||||
|
drivers/stm32/dma_reqmap_mcu.c \
|
||||||
drivers/stm32/dma_stm32g4xx.c \
|
drivers/stm32/dma_stm32g4xx.c \
|
||||||
drivers/stm32/dshot_bitbang_ll.c \
|
drivers/stm32/dshot_bitbang_ll.c \
|
||||||
drivers/stm32/dshot_bitbang.c \
|
drivers/stm32/dshot_bitbang.c \
|
||||||
|
|
|
@ -131,6 +131,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||||
$(USBMSC_DIR)/Inc \
|
$(USBMSC_DIR)/Inc \
|
||||||
$(CMSIS_DIR)/Core/Include \
|
$(CMSIS_DIR)/Core/Include \
|
||||||
$(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \
|
$(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \
|
||||||
|
$(ROOT)/src/main/drivers/stm32 \
|
||||||
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
$(ROOT)/src/main/drivers/stm32/vcp_hal
|
||||||
|
|
||||||
#Flags
|
#Flags
|
||||||
|
@ -307,6 +308,7 @@ MCU_COMMON_SRC = \
|
||||||
drivers/stm32/bus_quadspi_hal.c \
|
drivers/stm32/bus_quadspi_hal.c \
|
||||||
drivers/stm32/bus_octospi_stm32h7xx.c \
|
drivers/stm32/bus_octospi_stm32h7xx.c \
|
||||||
drivers/stm32/debug.c \
|
drivers/stm32/debug.c \
|
||||||
|
drivers/stm32/dma_reqmap_mcu.c \
|
||||||
drivers/stm32/dma_stm32h7xx.c \
|
drivers/stm32/dma_stm32h7xx.c \
|
||||||
drivers/stm32/dshot_bitbang_ll.c \
|
drivers/stm32/dshot_bitbang_ll.c \
|
||||||
drivers/stm32/dshot_bitbang.c \
|
drivers/stm32/dshot_bitbang.c \
|
||||||
|
|
|
@ -29,7 +29,6 @@ COMMON_SRC = \
|
||||||
drivers/display.c \
|
drivers/display.c \
|
||||||
drivers/display_canvas.c \
|
drivers/display_canvas.c \
|
||||||
drivers/dma_common.c \
|
drivers/dma_common.c \
|
||||||
drivers/dma_reqmap.c \
|
|
||||||
drivers/io.c \
|
drivers/io.c \
|
||||||
drivers/light_led.c \
|
drivers/light_led.c \
|
||||||
drivers/mco.c \
|
drivers/mco.c \
|
||||||
|
|
286
src/main/drivers/at32/dma_reqmap_mcu.c
Normal file
286
src/main/drivers/at32/dma_reqmap_mcu.c
Normal file
|
@ -0,0 +1,286 @@
|
||||||
|
/*
|
||||||
|
* 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 "pg/timerio.h"
|
||||||
|
|
||||||
|
typedef struct dmaPeripheralMapping_s {
|
||||||
|
dmaPeripheral_e device;
|
||||||
|
uint8_t index;
|
||||||
|
uint8_t dmaRequest;
|
||||||
|
} dmaPeripheralMapping_t;
|
||||||
|
|
||||||
|
typedef struct dmaTimerMapping_s {
|
||||||
|
TIM_TypeDef *tim;
|
||||||
|
uint8_t channel;
|
||||||
|
uint8_t dmaRequest;
|
||||||
|
} dmaTimerMapping_t;
|
||||||
|
|
||||||
|
#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, DMAMUX_DMAREQ_ID_ ## TMR ## timno ## _OVERFLOW }
|
||||||
|
|
||||||
|
#define DMA_REQUEST_UART1_RX DMAMUX_DMAREQ_ID_USART1_RX
|
||||||
|
#define DMA_REQUEST_UART1_TX DMAMUX_DMAREQ_ID_USART1_TX
|
||||||
|
#define DMA_REQUEST_UART2_RX DMAMUX_DMAREQ_ID_USART2_RX
|
||||||
|
#define DMA_REQUEST_UART2_TX DMAMUX_DMAREQ_ID_USART2_TX
|
||||||
|
#define DMA_REQUEST_UART3_RX DMAMUX_DMAREQ_ID_USART3_RX
|
||||||
|
#define DMA_REQUEST_UART3_TX DMAMUX_DMAREQ_ID_USART3_TX
|
||||||
|
#define DMA_REQUEST_UART4_RX DMAMUX_DMAREQ_ID_UART4_RX
|
||||||
|
#define DMA_REQUEST_UART4_TX DMAMUX_DMAREQ_ID_UART4_TX
|
||||||
|
#define DMA_REQUEST_UART5_RX DMAMUX_DMAREQ_ID_UART5_RX
|
||||||
|
#define DMA_REQUEST_UART5_TX DMAMUX_DMAREQ_ID_UART5_TX
|
||||||
|
|
||||||
|
#define DMA_REQUEST_UART6_RX DMAMUX_DMAREQ_ID_USART6_RX
|
||||||
|
#define DMA_REQUEST_UART6_TX DMAMUX_DMAREQ_ID_USART6_TX
|
||||||
|
|
||||||
|
// Resolve our preference for MOSI/MISO rather than TX/RX
|
||||||
|
#define DMA_REQUEST_SPI1_MOSI DMAMUX_DMAREQ_ID_SPI1_TX
|
||||||
|
#define DMA_REQUEST_SPI1_MISO DMAMUX_DMAREQ_ID_SPI1_RX
|
||||||
|
#define DMA_REQUEST_SPI2_MOSI DMAMUX_DMAREQ_ID_SPI2_TX
|
||||||
|
#define DMA_REQUEST_SPI2_MISO DMAMUX_DMAREQ_ID_SPI2_RX
|
||||||
|
#define DMA_REQUEST_SPI3_MOSI DMAMUX_DMAREQ_ID_SPI3_TX
|
||||||
|
#define DMA_REQUEST_SPI3_MISO DMAMUX_DMAREQ_ID_SPI3_RX
|
||||||
|
#define DMA_REQUEST_SPI4_MOSI DMAMUX_DMAREQ_ID_SPI4_TX
|
||||||
|
#define DMA_REQUEST_SPI4_MISO DMAMUX_DMAREQ_ID_SPI4_RX
|
||||||
|
|
||||||
|
#define DMA_REQUEST_ADC1 DMAMUX_DMAREQ_ID_ADC1
|
||||||
|
#define DMA_REQUEST_ADC2 DMAMUX_DMAREQ_ID_ADC2
|
||||||
|
#define DMA_REQUEST_ADC3 DMAMUX_DMAREQ_ID_ADC3
|
||||||
|
|
||||||
|
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
|
||||||
|
#ifdef USE_SPI
|
||||||
|
REQMAP_DIR(SPI, 1, MOSI),
|
||||||
|
REQMAP_DIR(SPI, 1, MISO),
|
||||||
|
REQMAP_DIR(SPI, 2, MOSI),
|
||||||
|
REQMAP_DIR(SPI, 2, MISO),
|
||||||
|
REQMAP_DIR(SPI, 3, MOSI),
|
||||||
|
REQMAP_DIR(SPI, 3, MISO),
|
||||||
|
REQMAP_DIR(SPI, 4, MOSI),
|
||||||
|
REQMAP_DIR(SPI, 4, MISO),
|
||||||
|
#endif // USE_SPI
|
||||||
|
|
||||||
|
#ifdef USE_ADC
|
||||||
|
REQMAP(ADC, 1),
|
||||||
|
REQMAP(ADC, 2),
|
||||||
|
REQMAP(ADC, 3),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART
|
||||||
|
REQMAP_DIR(UART, 1, TX),
|
||||||
|
REQMAP_DIR(UART, 1, RX),
|
||||||
|
REQMAP_DIR(UART, 2, TX),
|
||||||
|
REQMAP_DIR(UART, 2, RX),
|
||||||
|
REQMAP_DIR(UART, 3, TX),
|
||||||
|
REQMAP_DIR(UART, 3, RX),
|
||||||
|
REQMAP_DIR(UART, 4, TX),
|
||||||
|
REQMAP_DIR(UART, 4, RX),
|
||||||
|
REQMAP_DIR(UART, 5, TX),
|
||||||
|
REQMAP_DIR(UART, 5, RX),
|
||||||
|
REQMAP_DIR(UART, 6, TX),
|
||||||
|
REQMAP_DIR(UART, 6, RX),
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_TIMER
|
||||||
|
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, 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), DMAMUX_DMAREQ_ID_ ## tim ## _ ## chan }
|
||||||
|
|
||||||
|
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
||||||
|
REQMAP_TIM(TMR1, CH1),
|
||||||
|
REQMAP_TIM(TMR1, CH2),
|
||||||
|
REQMAP_TIM(TMR1, CH3),
|
||||||
|
REQMAP_TIM(TMR1, CH4),
|
||||||
|
REQMAP_TIM(TMR2, CH1),
|
||||||
|
REQMAP_TIM(TMR2, CH2),
|
||||||
|
REQMAP_TIM(TMR2, CH3),
|
||||||
|
REQMAP_TIM(TMR2, CH4),
|
||||||
|
REQMAP_TIM(TMR3, CH1),
|
||||||
|
REQMAP_TIM(TMR3, CH2),
|
||||||
|
REQMAP_TIM(TMR3, CH3),
|
||||||
|
REQMAP_TIM(TMR3, CH4),
|
||||||
|
REQMAP_TIM(TMR4, CH1),
|
||||||
|
REQMAP_TIM(TMR4, CH2),
|
||||||
|
REQMAP_TIM(TMR4, CH3),
|
||||||
|
REQMAP_TIM(TMR4, CH4),
|
||||||
|
REQMAP_TIM(TMR5, CH1),
|
||||||
|
REQMAP_TIM(TMR5, CH2),
|
||||||
|
REQMAP_TIM(TMR5, CH3),
|
||||||
|
REQMAP_TIM(TMR5, CH4),
|
||||||
|
REQMAP_TIM(TMR8, CH1),
|
||||||
|
REQMAP_TIM(TMR8, CH2),
|
||||||
|
REQMAP_TIM(TMR8, CH3),
|
||||||
|
REQMAP_TIM(TMR8, CH4),
|
||||||
|
REQMAP_TIM(TMR20, CH1),
|
||||||
|
REQMAP_TIM(TMR20, CH2),
|
||||||
|
REQMAP_TIM(TMR20, CH3),
|
||||||
|
REQMAP_TIM(TMR20, CH4),
|
||||||
|
// XXX Check non-CH1 for TIM15,16,17 and 20
|
||||||
|
};
|
||||||
|
|
||||||
|
#undef TC
|
||||||
|
#undef REQMAP_TIM
|
||||||
|
|
||||||
|
#define DMA(d, c) { DMA_CODE(d, 0, c), (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(2, 1),
|
||||||
|
DMA(2, 2),
|
||||||
|
DMA(2, 3),
|
||||||
|
DMA(2, 4),
|
||||||
|
DMA(2, 5),
|
||||||
|
DMA(2, 6),
|
||||||
|
DMA(2, 7),
|
||||||
|
};
|
||||||
|
|
||||||
|
#undef DMA
|
||||||
|
|
||||||
|
static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request)
|
||||||
|
{
|
||||||
|
dmaSpec->dmaMuxId = request;
|
||||||
|
dmaCode_t code = dmaSpec->code;
|
||||||
|
dmaSpec->code = DMA_CODE(DMA_CODE_CONTROLLER(code), DMA_CODE_STREAM(code), dmaSpec->dmaMuxId);
|
||||||
|
}
|
||||||
|
|
||||||
|
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
||||||
|
{
|
||||||
|
if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) {
|
||||||
|
const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i];
|
||||||
|
if (periph->device == device && periph->index == index) {
|
||||||
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];
|
||||||
|
dmaSetupRequest(dmaSpec, periph->dmaRequest);
|
||||||
|
return dmaSpec;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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 (timerMapping->tim == tim && timerMapping->channel == channel) {
|
||||||
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt];
|
||||||
|
dmaSetupRequest(dmaSpec, timerMapping->dmaRequest);
|
||||||
|
return dmaSpec;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
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)
|
||||||
|
{
|
||||||
|
for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
|
||||||
|
if (timer->dmaRefConfigured == dmaChannelSpec[opt].ref) {
|
||||||
|
return (dmaoptValue_t)opt;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return DMA_OPT_UNUSED;
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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 // USE_DMA_SPEC
|
27
src/main/drivers/at32/dma_reqmap_mcu.h
Normal file
27
src/main/drivers/at32/dma_reqmap_mcu.h
Normal 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
|
|
@ -24,10 +24,9 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "timer_def.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/timer_def.h"
|
|
||||||
|
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
|
|
|
@ -1,19 +1,20 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight and Betaflight.
|
* This file is part of Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight and Betaflight are free software. You can redistribute
|
* Betaflight is free software. You can redistribute this software
|
||||||
* this software and/or modify this software under the terms of the
|
* and/or modify this software under the terms of the GNU General
|
||||||
* GNU General Public License as published by the Free Software
|
* Public License as published by the Free Software Foundation,
|
||||||
* Foundation, either version 3 of the License, or (at your option)
|
* either version 3 of the License, or (at your option) any later
|
||||||
* any later version.
|
* 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.
|
||||||
*
|
*
|
||||||
* 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.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public
|
||||||
* along with this software.
|
* License along with this software.
|
||||||
*
|
*
|
||||||
* If not, see <http://www.gnu.org/licenses/>.
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
|
@ -25,15 +25,17 @@
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
|
|
||||||
|
#include "dma_reqmap_mcu.h"
|
||||||
|
|
||||||
typedef uint16_t dmaCode_t;
|
typedef uint16_t dmaCode_t;
|
||||||
|
|
||||||
typedef struct dmaChannelSpec_s {
|
typedef struct dmaChannelSpec_s {
|
||||||
dmaCode_t code;
|
dmaCode_t code;
|
||||||
dmaResource_t *ref;
|
dmaResource_t *ref;
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
|
#if defined(USE_DMA_MUX)
|
||||||
uint32_t channel;
|
|
||||||
#elif defined(AT32F4)
|
|
||||||
uint32_t dmaMuxId;
|
uint32_t dmaMuxId;
|
||||||
|
#else
|
||||||
|
uint32_t channel;
|
||||||
#endif
|
#endif
|
||||||
} dmaChannelSpec_t;
|
} dmaChannelSpec_t;
|
||||||
|
|
||||||
|
@ -57,17 +59,6 @@ typedef int8_t dmaoptValue_t;
|
||||||
|
|
||||||
#define DMA_OPT_UNUSED (-1)
|
#define DMA_OPT_UNUSED (-1)
|
||||||
|
|
||||||
#if defined(STM32H7) || defined(STM32G4)
|
|
||||||
#define MAX_PERIPHERAL_DMA_OPTIONS 16
|
|
||||||
#define MAX_TIMER_DMA_OPTIONS 16
|
|
||||||
#elif defined(AT32F4)
|
|
||||||
#define MAX_PERIPHERAL_DMA_OPTIONS 14
|
|
||||||
#define MAX_TIMER_DMA_OPTIONS 22
|
|
||||||
#else
|
|
||||||
#define MAX_PERIPHERAL_DMA_OPTIONS 2
|
|
||||||
#define MAX_TIMER_DMA_OPTIONS 3
|
|
||||||
#endif
|
|
||||||
|
|
||||||
struct timerHardware_s;
|
struct timerHardware_s;
|
||||||
|
|
||||||
dmaoptValue_t dmaoptByTag(ioTag_t ioTag);
|
dmaoptValue_t dmaoptByTag(ioTag_t ioTag);
|
||||||
|
|
|
@ -24,20 +24,19 @@
|
||||||
|
|
||||||
#ifdef USE_DMA_SPEC
|
#ifdef USE_DMA_SPEC
|
||||||
|
|
||||||
|
#include "timer_def.h"
|
||||||
#include "drivers/adc.h"
|
#include "drivers/adc.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/dma_reqmap.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "drivers/serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "drivers/timer_def.h"
|
|
||||||
|
|
||||||
#include "pg/timerio.h"
|
#include "pg/timerio.h"
|
||||||
|
|
||||||
#include "dma_reqmap.h"
|
|
||||||
|
|
||||||
typedef struct dmaPeripheralMapping_s {
|
typedef struct dmaPeripheralMapping_s {
|
||||||
dmaPeripheral_e device;
|
dmaPeripheral_e device;
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
uint8_t dmaRequest;
|
uint8_t dmaRequest;
|
||||||
#else
|
#else
|
||||||
dmaChannelSpec_t channelSpec[MAX_PERIPHERAL_DMA_OPTIONS];
|
dmaChannelSpec_t channelSpec[MAX_PERIPHERAL_DMA_OPTIONS];
|
||||||
|
@ -47,161 +46,13 @@ typedef struct dmaPeripheralMapping_s {
|
||||||
typedef struct dmaTimerMapping_s {
|
typedef struct dmaTimerMapping_s {
|
||||||
TIM_TypeDef *tim;
|
TIM_TypeDef *tim;
|
||||||
uint8_t channel;
|
uint8_t channel;
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
uint8_t dmaRequest;
|
uint8_t dmaRequest;
|
||||||
#else
|
#else
|
||||||
dmaChannelSpec_t channelSpec[MAX_TIMER_DMA_OPTIONS];
|
dmaChannelSpec_t channelSpec[MAX_TIMER_DMA_OPTIONS];
|
||||||
#endif
|
#endif
|
||||||
} dmaTimerMapping_t;
|
} dmaTimerMapping_t;
|
||||||
|
|
||||||
#if defined(AT32F43x)
|
|
||||||
|
|
||||||
#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, DMAMUX_DMAREQ_ID_ ## TMR ## timno ## _OVERFLOW }
|
|
||||||
|
|
||||||
#define DMA_REQUEST_UART1_RX DMAMUX_DMAREQ_ID_USART1_RX
|
|
||||||
#define DMA_REQUEST_UART1_TX DMAMUX_DMAREQ_ID_USART1_TX
|
|
||||||
#define DMA_REQUEST_UART2_RX DMAMUX_DMAREQ_ID_USART2_RX
|
|
||||||
#define DMA_REQUEST_UART2_TX DMAMUX_DMAREQ_ID_USART2_TX
|
|
||||||
#define DMA_REQUEST_UART3_RX DMAMUX_DMAREQ_ID_USART3_RX
|
|
||||||
#define DMA_REQUEST_UART3_TX DMAMUX_DMAREQ_ID_USART3_TX
|
|
||||||
#define DMA_REQUEST_UART4_RX DMAMUX_DMAREQ_ID_UART4_RX
|
|
||||||
#define DMA_REQUEST_UART4_TX DMAMUX_DMAREQ_ID_UART4_TX
|
|
||||||
#define DMA_REQUEST_UART5_RX DMAMUX_DMAREQ_ID_UART5_RX
|
|
||||||
#define DMA_REQUEST_UART5_TX DMAMUX_DMAREQ_ID_UART5_TX
|
|
||||||
|
|
||||||
#define DMA_REQUEST_UART6_RX DMAMUX_DMAREQ_ID_USART6_RX
|
|
||||||
#define DMA_REQUEST_UART6_TX DMAMUX_DMAREQ_ID_USART6_TX
|
|
||||||
|
|
||||||
// Resolve our preference for MOSI/MISO rather than TX/RX
|
|
||||||
#define DMA_REQUEST_SPI1_MOSI DMAMUX_DMAREQ_ID_SPI1_TX
|
|
||||||
#define DMA_REQUEST_SPI1_MISO DMAMUX_DMAREQ_ID_SPI1_RX
|
|
||||||
#define DMA_REQUEST_SPI2_MOSI DMAMUX_DMAREQ_ID_SPI2_TX
|
|
||||||
#define DMA_REQUEST_SPI2_MISO DMAMUX_DMAREQ_ID_SPI2_RX
|
|
||||||
#define DMA_REQUEST_SPI3_MOSI DMAMUX_DMAREQ_ID_SPI3_TX
|
|
||||||
#define DMA_REQUEST_SPI3_MISO DMAMUX_DMAREQ_ID_SPI3_RX
|
|
||||||
#define DMA_REQUEST_SPI4_MOSI DMAMUX_DMAREQ_ID_SPI4_TX
|
|
||||||
#define DMA_REQUEST_SPI4_MISO DMAMUX_DMAREQ_ID_SPI4_RX
|
|
||||||
|
|
||||||
#define DMA_REQUEST_ADC1 DMAMUX_DMAREQ_ID_ADC1
|
|
||||||
#define DMA_REQUEST_ADC2 DMAMUX_DMAREQ_ID_ADC2
|
|
||||||
#define DMA_REQUEST_ADC3 DMAMUX_DMAREQ_ID_ADC3
|
|
||||||
|
|
||||||
static const dmaPeripheralMapping_t dmaPeripheralMapping[] = {
|
|
||||||
#ifdef USE_SPI
|
|
||||||
REQMAP_DIR(SPI, 1, MOSI),
|
|
||||||
REQMAP_DIR(SPI, 1, MISO),
|
|
||||||
REQMAP_DIR(SPI, 2, MOSI),
|
|
||||||
REQMAP_DIR(SPI, 2, MISO),
|
|
||||||
REQMAP_DIR(SPI, 3, MOSI),
|
|
||||||
REQMAP_DIR(SPI, 3, MISO),
|
|
||||||
REQMAP_DIR(SPI, 4, MOSI),
|
|
||||||
REQMAP_DIR(SPI, 4, MISO),
|
|
||||||
#endif // USE_SPI
|
|
||||||
|
|
||||||
#ifdef USE_ADC
|
|
||||||
REQMAP(ADC, 1),
|
|
||||||
REQMAP(ADC, 2),
|
|
||||||
REQMAP(ADC, 3),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART
|
|
||||||
REQMAP_DIR(UART, 1, TX),
|
|
||||||
REQMAP_DIR(UART, 1, RX),
|
|
||||||
REQMAP_DIR(UART, 2, TX),
|
|
||||||
REQMAP_DIR(UART, 2, RX),
|
|
||||||
REQMAP_DIR(UART, 3, TX),
|
|
||||||
REQMAP_DIR(UART, 3, RX),
|
|
||||||
REQMAP_DIR(UART, 4, TX),
|
|
||||||
REQMAP_DIR(UART, 4, RX),
|
|
||||||
REQMAP_DIR(UART, 5, TX),
|
|
||||||
REQMAP_DIR(UART, 5, RX),
|
|
||||||
REQMAP_DIR(UART, 6, TX),
|
|
||||||
REQMAP_DIR(UART, 6, RX),
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_TIMER
|
|
||||||
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, 20),
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
#undef REQMAP_TIMUP
|
|
||||||
#undef REQMAP
|
|
||||||
#undef REQMAP_SGL
|
|
||||||
#undef REQMAP_DIR
|
|
||||||
|
|
||||||
#define TC(chan) DEF_TIM_CHANNEL(CH_ ## chan) //Tc 还不能映射
|
|
||||||
|
|
||||||
#define REQMAP_TIM(tim, chan) { tim, TC(chan), DMAMUX_DMAREQ_ID_ ## tim ## _ ## chan }
|
|
||||||
|
|
||||||
static const dmaTimerMapping_t dmaTimerMapping[] = {
|
|
||||||
REQMAP_TIM(TMR1, CH1),
|
|
||||||
REQMAP_TIM(TMR1, CH2),
|
|
||||||
REQMAP_TIM(TMR1, CH3),
|
|
||||||
REQMAP_TIM(TMR1, CH4),
|
|
||||||
REQMAP_TIM(TMR2, CH1),
|
|
||||||
REQMAP_TIM(TMR2, CH2),
|
|
||||||
REQMAP_TIM(TMR2, CH3),
|
|
||||||
REQMAP_TIM(TMR2, CH4),
|
|
||||||
REQMAP_TIM(TMR3, CH1),
|
|
||||||
REQMAP_TIM(TMR3, CH2),
|
|
||||||
REQMAP_TIM(TMR3, CH3),
|
|
||||||
REQMAP_TIM(TMR3, CH4),
|
|
||||||
REQMAP_TIM(TMR4, CH1),
|
|
||||||
REQMAP_TIM(TMR4, CH2),
|
|
||||||
REQMAP_TIM(TMR4, CH3),
|
|
||||||
REQMAP_TIM(TMR4, CH4),
|
|
||||||
REQMAP_TIM(TMR5, CH1),
|
|
||||||
REQMAP_TIM(TMR5, CH2),
|
|
||||||
REQMAP_TIM(TMR5, CH3),
|
|
||||||
REQMAP_TIM(TMR5, CH4),
|
|
||||||
REQMAP_TIM(TMR8, CH1),
|
|
||||||
REQMAP_TIM(TMR8, CH2),
|
|
||||||
REQMAP_TIM(TMR8, CH3),
|
|
||||||
REQMAP_TIM(TMR8, CH4),
|
|
||||||
REQMAP_TIM(TMR20, CH1),
|
|
||||||
REQMAP_TIM(TMR20, CH2),
|
|
||||||
REQMAP_TIM(TMR20, CH3),
|
|
||||||
REQMAP_TIM(TMR20, CH4),
|
|
||||||
// XXX Check non-CH1 for TIM15,16,17 and 20
|
|
||||||
};
|
|
||||||
|
|
||||||
#undef TC
|
|
||||||
#undef REQMAP_TIM
|
|
||||||
|
|
||||||
#define DMA(d, c) { DMA_CODE(d, 0, c), (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(2, 1),
|
|
||||||
DMA(2, 2),
|
|
||||||
DMA(2, 3),
|
|
||||||
DMA(2, 4),
|
|
||||||
DMA(2, 5),
|
|
||||||
DMA(2, 6),
|
|
||||||
DMA(2, 7),
|
|
||||||
};
|
|
||||||
|
|
||||||
#undef DMA
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(STM32G4)
|
#if defined(STM32G4)
|
||||||
|
|
||||||
#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph }
|
#define REQMAP_SGL(periph) { DMA_PERIPH_ ## periph, 0, DMA_REQUEST_ ## periph }
|
||||||
|
@ -628,15 +479,6 @@ static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(AT32F4)
|
|
||||||
static void dmaSetupRequest(dmaChannelSpec_t *dmaSpec, uint8_t request)
|
|
||||||
{
|
|
||||||
dmaSpec->dmaMuxId = request;
|
|
||||||
dmaCode_t code = dmaSpec->code;
|
|
||||||
dmaSpec->code = DMA_CODE(DMA_CODE_CONTROLLER(code), DMA_CODE_STREAM(code), dmaSpec->dmaMuxId);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, uint8_t index, int8_t opt)
|
||||||
{
|
{
|
||||||
if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) {
|
if (opt < 0 || opt >= MAX_PERIPHERAL_DMA_OPTIONS) {
|
||||||
|
@ -645,7 +487,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByPeripheral(dmaPeripheral_e device, ui
|
||||||
|
|
||||||
for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) {
|
for (unsigned i = 0 ; i < ARRAYLEN(dmaPeripheralMapping) ; i++) {
|
||||||
const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i];
|
const dmaPeripheralMapping_t *periph = &dmaPeripheralMapping[i];
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
if (periph->device == device && periph->index == index) {
|
if (periph->device == device && periph->index == index) {
|
||||||
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[opt];
|
||||||
dmaSetupRequest(dmaSpec, periph->dmaRequest);
|
dmaSetupRequest(dmaSpec, periph->dmaRequest);
|
||||||
|
@ -684,7 +526,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByTimerValue(TIM_TypeDef *tim, uint8_t
|
||||||
|
|
||||||
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping) ; i++) {
|
for (unsigned i = 0 ; i < ARRAYLEN(dmaTimerMapping) ; i++) {
|
||||||
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
|
const dmaTimerMapping_t *timerMapping = &dmaTimerMapping[i];
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
if (timerMapping->tim == tim && timerMapping->channel == channel) {
|
if (timerMapping->tim == tim && timerMapping->channel == channel) {
|
||||||
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt];
|
dmaChannelSpec_t *dmaSpec = &dmaChannelSpec[dmaopt];
|
||||||
dmaSetupRequest(dmaSpec, timerMapping->dmaRequest);
|
dmaSetupRequest(dmaSpec, timerMapping->dmaRequest);
|
||||||
|
@ -714,7 +556,7 @@ const dmaChannelSpec_t *dmaGetChannelSpecByTimer(const timerHardware_t *timer)
|
||||||
|
|
||||||
dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
|
dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
|
||||||
{
|
{
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
|
for (unsigned opt = 0; opt < ARRAYLEN(dmaChannelSpec); opt++) {
|
||||||
if (timer->dmaRefConfigured == dmaChannelSpec[opt].ref) {
|
if (timer->dmaRefConfigured == dmaChannelSpec[opt].ref) {
|
||||||
return (dmaoptValue_t)opt;
|
return (dmaoptValue_t)opt;
|
||||||
|
@ -741,7 +583,7 @@ dmaoptValue_t dmaGetOptionByTimer(const timerHardware_t *timer)
|
||||||
return DMA_OPT_UNUSED;
|
return DMA_OPT_UNUSED;
|
||||||
}
|
}
|
||||||
|
|
||||||
#if defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
|
// A variant of dmaGetOptionByTimer that looks for matching dmaTimUPRef
|
||||||
dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
|
dmaoptValue_t dmaGetUpOptionByTimer(const timerHardware_t *timer)
|
||||||
{
|
{
|
30
src/main/drivers/stm32/dma_reqmap_mcu.h
Normal file
30
src/main/drivers/stm32/dma_reqmap_mcu.h
Normal file
|
@ -0,0 +1,30 @@
|
||||||
|
/*
|
||||||
|
* 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
|
||||||
|
|
||||||
|
#if defined(STM32H7) || defined(STM32G4)
|
||||||
|
#define MAX_PERIPHERAL_DMA_OPTIONS 16
|
||||||
|
#define MAX_TIMER_DMA_OPTIONS 16
|
||||||
|
#else
|
||||||
|
#define MAX_PERIPHERAL_DMA_OPTIONS 2
|
||||||
|
#define MAX_TIMER_DMA_OPTIONS 3
|
||||||
|
#endif
|
|
@ -1124,3 +1124,39 @@
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#if defined(STM32F7)
|
||||||
|
|
||||||
|
#define FULL_TIMER_CHANNEL_COUNT 78
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12) | TIM_N(13) | TIM_N(14) )
|
||||||
|
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
||||||
|
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
|
||||||
|
#if defined(STM32F411xE)
|
||||||
|
#define FULL_TIMER_CHANNEL_COUNT 59
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(9) | TIM_N(10) | TIM_N(11) )
|
||||||
|
#define HARDWARE_TIMER_DEFINITION_COUNT 10
|
||||||
|
|
||||||
|
#else
|
||||||
|
|
||||||
|
#define FULL_TIMER_CHANNEL_COUNT 78
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12) | TIM_N(13) | TIM_N(14) )
|
||||||
|
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
||||||
|
|
||||||
|
#endif //STM32F411xE
|
||||||
|
|
||||||
|
#elif defined(STM32H7)
|
||||||
|
|
||||||
|
#define FULL_TIMER_CHANNEL_COUNT 87
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(12) | TIM_N(13) | TIM_N(14) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
||||||
|
#define HARDWARE_TIMER_DEFINITION_COUNT 17
|
||||||
|
#define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(6) | BIT(7) | BIT(8) | BIT(15) | BIT(16) | BIT(17) )
|
||||||
|
|
||||||
|
#elif defined(STM32G4)
|
||||||
|
|
||||||
|
#define FULL_TIMER_CHANNEL_COUNT 93 // XXX Need review
|
||||||
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) | TIM_N(20) )
|
||||||
|
#define HARDWARE_TIMER_DEFINITION_COUNT 12
|
||||||
|
#define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(6) | BIT(7) | BIT(8) | BIT(15) | BIT(16) | BIT(17) | BIT(20))
|
||||||
|
|
||||||
|
#endif
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "stm32f4xx.h"
|
#include "stm32f4xx.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "stm32f7xx.h"
|
#include "stm32f7xx.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "stm32g4xx.h"
|
#include "stm32g4xx.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
|
@ -26,7 +26,7 @@
|
||||||
|
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "stm32h7xx.h"
|
#include "stm32h7xx.h"
|
||||||
#include "drivers/rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
|
@ -27,11 +27,8 @@
|
||||||
#include "drivers/io_types.h"
|
#include "drivers/io_types.h"
|
||||||
#include "drivers/rcc_types.h"
|
#include "drivers/rcc_types.h"
|
||||||
#include "drivers/resource.h"
|
#include "drivers/resource.h"
|
||||||
#if defined(USE_ATBSP_DRIVER)
|
|
||||||
#include "drivers/at32/timer_def_at32.h"
|
#include "timer_def.h"
|
||||||
#else
|
|
||||||
#include "drivers/timer_def.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "pg/timerio.h"
|
#include "pg/timerio.h"
|
||||||
|
|
||||||
|
@ -86,27 +83,19 @@ typedef struct timerHardware_s {
|
||||||
uint8_t channel;
|
uint8_t channel;
|
||||||
timerUsageFlag_e usageFlags;
|
timerUsageFlag_e usageFlags;
|
||||||
uint8_t output;
|
uint8_t output;
|
||||||
#if defined(USE_TIMER_AF)
|
|
||||||
uint8_t alternateFunction;
|
uint8_t alternateFunction;
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_TIMER_DMA)
|
#if defined(USE_TIMER_DMA)
|
||||||
|
|
||||||
#if defined(USE_DMA_SPEC)
|
#if defined(USE_DMA_SPEC)
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
|
||||||
dmaResource_t *dmaRefConfigured;
|
dmaResource_t *dmaRefConfigured;
|
||||||
uint32_t dmaChannelConfigured;
|
uint32_t dmaChannelConfigured;
|
||||||
#endif
|
|
||||||
#else // USE_DMA_SPEC
|
#else // USE_DMA_SPEC
|
||||||
dmaResource_t *dmaRef;
|
dmaResource_t *dmaRef;
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
|
||||||
uint32_t dmaChannel; // XXX Can be much smaller (e.g. uint8_t)
|
uint32_t dmaChannel; // XXX Can be much smaller (e.g. uint8_t)
|
||||||
#endif
|
|
||||||
#endif // USE_DMA_SPEC
|
#endif // USE_DMA_SPEC
|
||||||
dmaResource_t *dmaTimUPRef;
|
dmaResource_t *dmaTimUPRef;
|
||||||
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
|
|
||||||
uint32_t dmaTimUPChannel;
|
uint32_t dmaTimUPChannel;
|
||||||
#endif
|
|
||||||
uint8_t dmaTimUPIrqHandler;
|
uint8_t dmaTimUPIrqHandler;
|
||||||
#endif
|
#endif
|
||||||
} timerHardware_t;
|
} timerHardware_t;
|
||||||
|
@ -117,77 +106,13 @@ typedef enum {
|
||||||
TIMER_OUTPUT_N_CHANNEL = (1 << 1),
|
TIMER_OUTPUT_N_CHANNEL = (1 << 1),
|
||||||
} timerFlag_e;
|
} timerFlag_e;
|
||||||
|
|
||||||
#if defined(STM32F411xE)
|
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 10
|
|
||||||
#elif defined(STM32F4)
|
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
|
||||||
#elif defined(STM32F7)
|
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 14
|
|
||||||
#elif defined(STM32H7)
|
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 17
|
|
||||||
#define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(6) | BIT(7) | BIT(8) | BIT(15) | BIT(16) | BIT(17) )
|
|
||||||
#elif defined(STM32G4)
|
|
||||||
#define HARDWARE_TIMER_DEFINITION_COUNT 12
|
|
||||||
#define TIMUP_TIMERS ( BIT(1) | BIT(2) | BIT(3) | BIT(4) | BIT(5) | BIT(6) | BIT(7) | BIT(8) | BIT(15) | BIT(16) | BIT(17) | BIT(20))
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define MHZ_TO_HZ(x) ((x) * 1000000)
|
#define MHZ_TO_HZ(x) ((x) * 1000000)
|
||||||
|
|
||||||
#if defined(USE_TIMER_MGMT)
|
|
||||||
#if defined(STM32F4)
|
|
||||||
|
|
||||||
#if defined(STM32F411xE)
|
|
||||||
#define FULL_TIMER_CHANNEL_COUNT 59
|
|
||||||
#else
|
|
||||||
#define FULL_TIMER_CHANNEL_COUNT 78
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#elif defined(STM32F7)
|
|
||||||
|
|
||||||
#define FULL_TIMER_CHANNEL_COUNT 78
|
|
||||||
|
|
||||||
#elif defined(STM32H7)
|
|
||||||
|
|
||||||
#define FULL_TIMER_CHANNEL_COUNT 87
|
|
||||||
|
|
||||||
#elif defined(STM32G4)
|
|
||||||
|
|
||||||
#define FULL_TIMER_CHANNEL_COUNT 93 // XXX Need review
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
extern const timerHardware_t fullTimerHardware[];
|
extern const timerHardware_t fullTimerHardware[];
|
||||||
|
|
||||||
#define TIMER_CHANNEL_COUNT FULL_TIMER_CHANNEL_COUNT
|
#define TIMER_CHANNEL_COUNT FULL_TIMER_CHANNEL_COUNT
|
||||||
#define TIMER_HARDWARE fullTimerHardware
|
#define TIMER_HARDWARE fullTimerHardware
|
||||||
|
|
||||||
#if defined(STM32F7) || defined(STM32F4)
|
|
||||||
|
|
||||||
#if defined(STM32F411xE)
|
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(9) | TIM_N(10) | TIM_N(11) )
|
|
||||||
#else
|
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11) | TIM_N(12) | TIM_N(13) | TIM_N(14) )
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#elif defined(STM32H7)
|
|
||||||
|
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(12) | TIM_N(13) | TIM_N(14) | TIM_N(15) | TIM_N(16) | TIM_N(17) )
|
|
||||||
|
|
||||||
#elif defined(STM32G4)
|
|
||||||
|
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(6) | TIM_N(7) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) | TIM_N(20) )
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
#ifdef USABLE_TIMER_CHANNEL_COUNT
|
|
||||||
#define TIMER_CHANNEL_COUNT USABLE_TIMER_CHANNEL_COUNT
|
|
||||||
#define TIMER_HARDWARE timerHardware
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif // USE_TIMER_MGMT
|
|
||||||
|
|
||||||
extern const timerDef_t timerDefinitions[];
|
extern const timerDef_t timerDefinitions[];
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
|
@ -32,6 +32,9 @@
|
||||||
#include "config.h"
|
#include "config.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
// MCU specific platform from drivers/XX
|
||||||
|
#include "platform_mcu.h"
|
||||||
|
|
||||||
#include "target.h"
|
#include "target.h"
|
||||||
#include "target/common_post.h"
|
#include "target/common_post.h"
|
||||||
#include "target/common_defaults_post.h"
|
#include "target/common_defaults_post.h"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/at32/platform_at32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "A435"
|
#define TARGET_BOARD_IDENTIFIER "A435"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight AT32F435"
|
#define USBD_PRODUCT_STRING "Betaflight AT32F435"
|
||||||
|
|
22
src/main/target/SITL/dma_reqmap_mcu.h
Normal file
22
src/main/target/SITL/dma_reqmap_mcu.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* 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
|
22
src/main/target/SITL/platform_mcu.h
Normal file
22
src/main/target/SITL/platform_mcu.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* 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
|
|
@ -39,7 +39,7 @@
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "drivers/accgyro/accgyro_fake.h"
|
#include "drivers/accgyro/accgyro_fake.h"
|
||||||
#include "drivers/barometer/barometer_fake.h"
|
#include "drivers/barometer/barometer_fake.h"
|
||||||
|
@ -92,6 +92,7 @@ int targetParseArgs(int argc, char * argv[])
|
||||||
simulator_ip, PORT_PWM, simulator_ip, PORT_PWM_RAW);
|
simulator_ip, PORT_PWM, simulator_ip, PORT_PWM_RAW);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y);
|
int timeval_sub(struct timespec *result, struct timespec *x, struct timespec *y);
|
||||||
|
|
||||||
int lockMainPID(void)
|
int lockMainPID(void)
|
||||||
|
@ -102,10 +103,12 @@ int lockMainPID(void)
|
||||||
#define RAD2DEG (180.0 / M_PI)
|
#define RAD2DEG (180.0 / M_PI)
|
||||||
#define ACC_SCALE (256 / 9.80665)
|
#define ACC_SCALE (256 / 9.80665)
|
||||||
#define GYRO_SCALE (16.4)
|
#define GYRO_SCALE (16.4)
|
||||||
|
|
||||||
void sendMotorUpdate(void)
|
void sendMotorUpdate(void)
|
||||||
{
|
{
|
||||||
udpSend(&pwmLink, &pwmPkt, sizeof(servo_packet));
|
udpSend(&pwmLink, &pwmPkt, sizeof(servo_packet));
|
||||||
}
|
}
|
||||||
|
|
||||||
void updateState(const fdm_packet* pkt)
|
void updateState(const fdm_packet* pkt)
|
||||||
{
|
{
|
||||||
static double last_timestamp = 0; // in seconds
|
static double last_timestamp = 0; // in seconds
|
||||||
|
|
22
src/main/target/SITL/timer_def.h
Normal file
22
src/main/target/SITL/timer_def.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* 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
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "S405"
|
#define TARGET_BOARD_IDENTIFIER "S405"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32F405"
|
#define USBD_PRODUCT_STRING "Betaflight STM32F405"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "S411"
|
#define TARGET_BOARD_IDENTIFIER "S411"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32F411"
|
#define USBD_PRODUCT_STRING "Betaflight STM32F411"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "S745"
|
#define TARGET_BOARD_IDENTIFIER "S745"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32F745"
|
#define USBD_PRODUCT_STRING "Betaflight STM32F745"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "S7X2"
|
#define TARGET_BOARD_IDENTIFIER "S7X2"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32F7x2"
|
#define USBD_PRODUCT_STRING "Betaflight STM32F7x2"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "SG47"
|
#define TARGET_BOARD_IDENTIFIER "SG47"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32G47x"
|
#define USBD_PRODUCT_STRING "Betaflight STM32G47x"
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#ifndef TARGET_BOARD_IDENTIFIER
|
#ifndef TARGET_BOARD_IDENTIFIER
|
||||||
#define TARGET_BOARD_IDENTIFIER "SH72"
|
#define TARGET_BOARD_IDENTIFIER "SH72"
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -35,8 +35,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#ifndef TARGET_BOARD_IDENTIFIER
|
#ifndef TARGET_BOARD_IDENTIFIER
|
||||||
#define TARGET_BOARD_IDENTIFIER "S730"
|
#define TARGET_BOARD_IDENTIFIER "S730"
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -20,8 +20,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#define TARGET_BOARD_IDENTIFIER "SH74"
|
#define TARGET_BOARD_IDENTIFIER "SH74"
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "Betaflight STM32H743"
|
#define USBD_PRODUCT_STRING "Betaflight STM32H743"
|
||||||
|
|
|
@ -35,8 +35,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "drivers/stm32/platform_stm32.h"
|
|
||||||
|
|
||||||
#ifndef TARGET_BOARD_IDENTIFIER
|
#ifndef TARGET_BOARD_IDENTIFIER
|
||||||
#define TARGET_BOARD_IDENTIFIER "S750"
|
#define TARGET_BOARD_IDENTIFIER "S750"
|
||||||
#endif
|
#endif
|
||||||
|
|
22
src/test/unit/dma_reqmap_mcu.h
Normal file
22
src/test/unit/dma_reqmap_mcu.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* 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
|
|
@ -36,7 +36,7 @@ extern "C" {
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/light_ws2811strip.h"
|
#include "drivers/light_ws2811strip.h"
|
||||||
#include "drivers/timer.h"
|
#include "drivers/timer.h"
|
||||||
#include "drivers/timer_def.h"
|
#include "timer_def.h"
|
||||||
|
|
||||||
#include "config/config.h"
|
#include "config/config.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
22
src/test/unit/timer_def.h
Normal file
22
src/test/unit/timer_def.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* 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
|
Loading…
Add table
Add a link
Reference in a new issue