1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-25 17:25:20 +03:00

AT32 development, introduction of AT32F435 target (#12247)

* AT32F435: new target (#12159)
* AT32F435: New target (WIP)
* IO and Timer Updates
* Adding pseudonyms for the STM TypeDef items.
- implementation to follow
* Adding config_streamer support for AT32
* Implementation for IO
* Adding in Peripheral mapping from emsr.
* Warnings cleanup for AT drivers
* Getting things to the linking stage
* Add AT-START-F435 LEDs as default in AT32F435 as a temporary measure to aid bringup
* Remove tabs
* Enable selection of serial port to use for MSP
* Setup defaults for AT-START-F435 to use MSP on UART1
* Fix for most recent 4.5.0 Makefile changes
* Solve for sanity check.
* Add AT32F435 MCU type
* Fix compilation issue with SITL
* Merge conflict resolution
* Minor cleanup
* Adding line feed.

---------

Co-authored-by: Steve Evans <Steve@SCEvans.com>
This commit is contained in:
J Blackman 2023-01-31 11:31:23 +11:00 committed by GitHub
parent 8900a831e5
commit 74be33dfbc
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
58 changed files with 6256 additions and 84 deletions

View file

@ -22,6 +22,10 @@
#include "drivers/resource.h"
#if defined(USE_ATBSP_DRIVER)
#include "drivers/at32/dma_atbsp.h"
#endif
#define CACHE_LINE_SIZE 32
#define CACHE_LINE_MASK (CACHE_LINE_SIZE - 1)
@ -60,17 +64,16 @@ typedef struct dmaChannelDescriptor_s {
resourceOwner_t owner;
uint8_t resourceIndex;
uint32_t completeFlag;
} dmaChannelDescriptor_t;
#if defined(STM32F7)
//#define HAL_CLEANINVALIDATECACHE(addr, size) (SCB_CleanInvalidateDCache_by_Addr((uint32_t*)((uint32_t)addr & ~0x1f), ((uint32_t)(addr + size + 0x1f) & ~0x1f) - ((uint32_t)addr & ~0x1f)))
//#define HAL_CLEANCACHE(addr, size) (SCB_CleanDCache_by_Addr((uint32_t*)((uint32_t)addr & ~0x1f), ((uint32_t)(addr + size + 0x1f) & ~0x1f) - ((uint32_t)addr & ~0x1f)))
#if defined(USE_ATBSP_DRIVER)
dmamux_channel_type *dmamux;
#endif
} dmaChannelDescriptor_t;
#define DMA_IDENTIFIER_TO_INDEX(x) ((x) - 1)
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
#if defined(USE_ATBSP_DRIVER)
#elif defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
typedef enum {
DMA_NONE = 0,
@ -128,6 +131,8 @@ typedef enum {
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
#define DMA_IT_FEIF ((uint32_t)0x00000001)
void dmaMuxEnable(dmaIdentifier_e identifier, uint32_t dmaMuxId);
#else
#if defined(STM32G4)
@ -207,7 +212,6 @@ typedef enum {
#define DMA_IT_TCIF ((uint32_t)0x00000002)
#define DMA_IT_HTIF ((uint32_t)0x00000004)
#define DMA_IT_TEIF ((uint32_t)0x00000008)
#endif
// Macros to avoid direct register and register bit access
@ -239,6 +243,9 @@ typedef enum {
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
// Missing __HAL_DMA_SET_COUNTER in FW library V1.0.0
#define __HAL_DMA_SET_COUNTER(__HANDLE__, __COUNTER__) ((__HANDLE__)->Instance->CNDTR = (uint16_t)(__COUNTER__))
#elif defined(AT32F4)
#define DMA_CCR_EN 1
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->ctrl_bit.chen & DMA_CCR_EN)
#else
#define IS_DMA_ENABLED(reg) (((DMA_ARCH_TYPE *)(reg))->CCR & DMA_CCR_EN)
#define DMAx_SetMemoryAddress(reg, address) ((DMA_ARCH_TYPE *)(reg))->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail]
@ -257,7 +264,7 @@ uint32_t dmaGetChannel(const uint8_t channel);
// Wrapper macros to cast dmaResource_t back into DMA_ARCH_TYPE
//
#ifdef USE_HAL_DRIVER
#if defined(USE_HAL_DRIVER)
// We actually need these LL case only
@ -269,6 +276,8 @@ uint32_t dmaGetChannel(const uint8_t channel);
#define xLL_EX_DMA_SetDataLength(dmaResource, length) LL_EX_DMA_SetDataLength((DMA_ARCH_TYPE *)(dmaResource), length)
#define xLL_EX_DMA_EnableIT_TC(dmaResource) LL_EX_DMA_EnableIT_TC((DMA_ARCH_TYPE *)(dmaResource))
#elif defined(USE_ATBSP_DRIVER)
#else
#define xDMA_Init(dmaResource, initStruct) DMA_Init((DMA_ARCH_TYPE *)(dmaResource), initStruct)