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

Adding common source location in ./src/platform (#14044)

* Adding common source location in ./src/platform

To enable the continued clean up of multiple files still in ./src/main/driver (more PRs to follow) that are specifically for AT32, APM32 and STM32

Source will be moved to MCU_COMMON_SRC where it is specifically for that MCU (or variant). The test will be to ensure no files in the MCU_EXCLUDES for SITL.

* Use of +=
This commit is contained in:
Jay Blackman 2024-11-26 07:16:45 +11:00 committed by GitHub
parent 63514c2b54
commit 53d44aa1b1
No known key found for this signature in database
GPG key ID: B5690EEEBB952194
27 changed files with 264 additions and 127 deletions

View file

@ -138,7 +138,7 @@ CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS)) $(f
TARGET_PLATFORM := $(notdir $(patsubst %/,%,$(subst target/$(TARGET)/,, $(dir $(wildcard $(PLATFORM_DIR)/*/target/$(TARGET)/target.mk)))))
TARGET_PLATFORM_DIR := $(PLATFORM_DIR)/$(TARGET_PLATFORM)
LINKER_DIR := $(TARGET_PLATFORM_DIR)/link
VPATH := $(VPATH):$(TARGET_PLATFORM_DIR):$(TARGET_PLATFORM_DIR)/startup
VPATH := $(VPATH):$(TARGET_PLATFORM_DIR):$(TARGET_PLATFORM_DIR)/startup:$(PLATFORM_DIR)/common
include $(TARGET_PLATFORM_DIR)/target/$(TARGET)/target.mk

View file

@ -188,7 +188,7 @@ typedef struct {
\brief Read MPU Type Register
\return Number of MPU regions
*/
__STATIC_INLINE uint32_t ARM_MPU_TYPE()
__STATIC_INLINE uint32_t ARM_MPU_TYPE(void)
{
return ((MPU->TYPE) >> 8);
}

View file

@ -117,7 +117,6 @@ COMMON_SRC = \
drivers/serial_uart_hw.c \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
drivers/timer_common.c \
drivers/transponder_ir_arcitimer.c \
drivers/transponder_ir_ilap.c \
@ -440,7 +439,6 @@ SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
drivers/rcc.c \
drivers/serial.c \
drivers/serial_uart.c \
drivers/system.c \
drivers/timer.c \
fc/core.c \
fc/tasks.c \

View file

@ -64,7 +64,7 @@ typedef struct busDevice_s {
uint8_t deviceCount;
dmaChannelDescriptor_t *dmaTx;
dmaChannelDescriptor_t *dmaRx;
#ifndef UNIT_TEST
#ifdef USE_DMA
// Use a reference here as this saves RAM for unused descriptors
#if defined(USE_FULL_LL_DRIVER)
LL_DMA_InitTypeDef *initTx;
@ -73,7 +73,7 @@ typedef struct busDevice_s {
DMA_InitTypeDef *initTx;
DMA_InitTypeDef *initRx;
#endif
#endif // UNIT_TEST
#endif // USE_DMA
volatile struct busSegment_s* volatile curSegment;
bool initSegment;
} busDevice_t;
@ -94,7 +94,7 @@ typedef struct extDevice_s {
uint8_t address;
} mpuSlave;
} busType_u;
#ifndef UNIT_TEST
#ifdef USE_DMA
// Cache the init structure for the next DMA transfer to reduce inter-segment delay
#if defined(USE_FULL_LL_DRIVER)
LL_DMA_InitTypeDef initTx;
@ -103,7 +103,7 @@ typedef struct extDevice_s {
DMA_InitTypeDef initTx;
DMA_InitTypeDef initRx;
#endif
#endif // UNIT_TEST
#endif // USE_DMA
// Support disabling DMA on a per device basis
bool useDMA;
// Per device buffer reference if needed

View file

@ -25,7 +25,9 @@
#include "drivers/dma.h"
#include "drivers/timer.h"
#ifdef USE_DMA
#include "dma_reqmap_mcu.h"
#endif
typedef uint16_t dmaCode_t;

View file

@ -147,8 +147,9 @@ MMFLASH_CODE_NOINLINE static bool flashOctoSpiInit(const flashConfig_t *flashCon
#endif
for (uint8_t offset = 0; offset <= 1 && !detected; offset++) {
#if defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25N02K) || defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25M02G)
uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]);
#endif
if (offset == 0) {
#if defined(USE_FLASH_W25Q128FV)
@ -364,6 +365,10 @@ bool flashDeviceInit(const flashConfig_t *flashConfig)
{
bool haveFlash = false;
#if !defined(USE_FLASH_SPI) && !defined(USE_FLASH_QUADSPI) && !defined(USE_FLASH_OCTOSPI)
UNUSED(flashConfig);
#endif
#ifdef USE_FLASH_SPI
bool useSpi = (SPI_CFG_TO_DEV(flashConfig->spiDevice) != SPIINVALID);

View file

@ -36,101 +36,6 @@
// expand pinid to to ioTag_t
#define IO_TAG(pinid) DEFIO_TAG(pinid)
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
// speed is packed between modebits 4 and 1,
// 7 6 5 4 3 2 1 0
// 0 <pupd-1> <pupd-0> <mode-4> <speed-1> <speed-0> <mode-1> <mode-0>
// mode-4 is equivalent to STM32F4 otype (pushpull/od)
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_HIGH, GPIO_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_HIGH, GPIO_PULLUP)
#elif defined(STM32F4)
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_UP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP)
#elif defined(AT32F4)
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE ) // TODO
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP )
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_STRONGER , GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_DOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_NONE)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#elif defined(APM32F4)
//speed is packed inside modebits 5 and 2,
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_HIGH, GPIO_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_HIGH, GPIO_PULLUP)
#elif defined(UNIT_TEST) || defined(SIMULATOR_BUILD)
#define IOCFG_OUT_PP 0
#define IOCFG_OUT_OD 0
#define IOCFG_AF_PP 0
#define IOCFG_AF_OD 0
#define IOCFG_IPD 0
#define IOCFG_IPU 0
#define IOCFG_IN_FLOATING 0
#else
# warning "Unknown TARGET"
#endif
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4)
// Expose these for EXTIConfig
#define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03)
#define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03)
#define IO_CONFIG_GET_OTYPE(cfg) (((cfg) >> 4) & 0x01)
#define IO_CONFIG_GET_PULL(cfg) (((cfg) >> 5) & 0x03)
#endif
// declare available IO pins. Available pins are specified per target
#include "io_def.h"

View file

@ -71,19 +71,14 @@ int32_t clockCyclesTo10thMicros(int32_t clockCycles);
int32_t clockCyclesTo100thMicros(int32_t clockCycles);
uint32_t clockMicrosToCycles(uint32_t micros);
uint32_t getCycleCounter(void);
#if defined(STM32H7) || defined(STM32G4)
void systemProcessResetReason(void);
#endif
// memory
void memoryMappedModeInit(void);
bool isMemoryMappedModeEnabledOnBoot(void);
void initialiseMemorySections(void);
#ifdef STM32H7
void initialiseD2MemorySections(void);
void systemResetWithoutDisablingCaches(void);
#endif
void enableGPIOPowerUsageAndNoiseReductions(void);
// current crystal frequency - 8 or 12MHz

View file

@ -28,7 +28,9 @@
#include "drivers/rcc_types.h"
#include "drivers/resource.h"
#ifdef USE_TIMER
#include "timer_def.h"
#endif
#include "pg/timerio.h"

View file

@ -32,7 +32,7 @@
#include "target/common_pre.h"
// MCU specific platform from drivers/XX
// MCU specific platform from platform/X
#include "platform_mcu.h"
#include "target.h"

View file

@ -148,6 +148,7 @@ $(error TARGET_MCU [$(TARGET_MCU)] is not supported)
endif
MCU_COMMON_SRC = \
stm32/system.c \
startup/system_apm32f4xx.c \
drivers/inverter.c \
drivers/dshot_bitbang_decode.c \
@ -195,5 +196,8 @@ MSC_SRC = \
msc/usbd_storage_sd_spi.c \
msc/usbd_storage_sdio.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 -DUSE_FULL_DDL_DRIVER

View file

@ -147,3 +147,28 @@
#define USE_TIMER_MGMT
#define USE_TIMER_AF
#if defined(APM32F4)
//speed is packed inside modebits 5 and 2,
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_HIGH, GPIO_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_HIGH, GPIO_PULLUP)
#define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03)
#define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03)
#define IO_CONFIG_GET_OTYPE(cfg) (((cfg) >> 4) & 0x01)
#define IO_CONFIG_GET_PULL(cfg) (((cfg) >> 5) & 0x03)
#endif

View file

@ -80,6 +80,7 @@ ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE
MCU_COMMON_SRC = \
stm32/system.c \
startup/at32f435_437_clock.c \
startup/system_at32f435_437.c \
adc_at32f43x.c \
@ -118,4 +119,7 @@ MCU_COMMON_SRC = \
msc/emfat.c \
msc/emfat_file.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
MCU_EXCLUDES =

View file

@ -104,3 +104,27 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define USE_RPM_FILTER
#define USE_DYN_IDLE
#define USE_DYN_NOTCH_FILTER
#if defined(AT32F4)
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE ) // TODO
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP )
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_STRONGER , GPIO_OUTPUT_PUSH_PULL, GPIO_PULL_NONE)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_NONE)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_DOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_PUSH_PULL , GPIO_PULL_UP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_MODERATE, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_NONE)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT , GPIO_DRIVE_STRENGTH_MODERATE, 0, GPIO_PULL_UP)
#define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03)
#define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03)
#define IO_CONFIG_GET_OTYPE(cfg) (((cfg) >> 4) & 0x01)
#define IO_CONFIG_GET_PULL(cfg) (((cfg) >> 5) & 0x03)
#endif

View file

@ -20,3 +20,48 @@
*/
#pragma once
#if defined(RP2350)
#include "RP2350.h"
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define I2C_TypeDef I2C0_Type
//#define I2C_HandleTypeDef
#define GPIO_TypeDef IO_BANK0_Type
//#define GPIO_InitTypeDef
#define TIM_TypeDef TIMER0_Type
//#define TIM_OCInitTypeDef
#define DMA_TypeDef DMA_Type
//#define DMA_InitTypeDef
//#define DMA_Channel_TypeDef
#define SPI_TypeDef SPI0_Type
#define ADC_TypeDef ADC_Type
#define USART_TypeDef UART0_Type
#define TIM_OCInitTypeDef TIMER0_Type
#define TIM_ICInitTypeDef TIMER0_Type
//#define TIM_OCStructInit
//#define TIM_Cmd
//#define TIM_CtrlPWMOutputs
//#define TIM_TimeBaseInit
//#define TIM_ARRPreloadConfig
//#define SystemCoreClock
//#define EXTI_TypeDef
//#define EXTI_InitTypeDef
#endif
#define DEFAULT_CPU_OVERCLOCK 0
#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz
#define SCHEDULER_DELAY_LIMIT 10
#define IOCFG_OUT_PP 0
#define IOCFG_OUT_OD 0
#define IOCFG_AF_PP 0
#define IOCFG_AF_OD 0
#define IOCFG_IPD 0
#define IOCFG_IPU 0
#define IOCFG_IN_FLOATING 0

View file

@ -20,3 +20,50 @@
*/
#pragma once
#ifndef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "R235"
#endif
#ifndef USBD_PRODUCT_STRING
#define USBD_PRODUCT_STRING "Betaflight RP2350"
#endif
#undef USE_DMA
#undef USE_FLASH
#undef USE_FLASH_CHIP
#undef USE_TIMER
#undef USE_SPI
#undef USE_I2C
#undef USE_UART
#undef USE_DSHOT
#undef USE_RCC
#define GPIOA_BASE ((intptr_t)0x0001)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0xffff
#undef USE_FLASH
#undef USE_FLASH_CHIP
#undef USE_FLASH_M25P16
#undef USE_FLASH_W25N01G
#undef USE_FLASH_W25N02K
#undef USE_FLASH_W25M
#undef USE_FLASH_W25M512
#undef USE_FLASH_W25M02G
#undef USE_FLASH_W25Q128FV
#undef USE_FLASH_PY25Q128HA
#undef USE_FLASH_W25Q64FV
#define FLASH_PAGE_SIZE 0x1000
#define CONFIG_IN_RAM
#define U_ID_0 0
#define U_ID_1 1
#define U_ID_2 2

View file

@ -26,8 +26,6 @@ MCU_EXCLUDES = \
drivers/bus_spi_pinconfig.c \
drivers/dma.c \
drivers/pwm_output.c \
drivers/timer.c \
drivers/system.c \
drivers/rcc.c \
drivers/serial_escserial.c \
drivers/serial_pinconfig.c \

View file

@ -20,3 +20,11 @@
*/
#pragma once
#define IOCFG_OUT_PP 0
#define IOCFG_OUT_OD 0
#define IOCFG_AF_PP 0
#define IOCFG_AF_OD 0
#define IOCFG_IPD 0
#define IOCFG_IPU 0
#define IOCFG_IN_FLOATING 0

View file

@ -173,6 +173,7 @@ endif
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32
MCU_COMMON_SRC = \
stm32/system.c \
drivers/accgyro/accgyro_mpu.c \
drivers/dshot_bitbang_decode.c \
drivers/inverter.c \
@ -203,6 +204,9 @@ MCU_COMMON_SRC = \
camera_control_stm32.c \
startup/system_stm32f4xx.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
ifeq ($(PERIPH_DRIVER), HAL)
VCP_SRC = \
vcp_hal/usbd_desc.c \

View file

@ -141,6 +141,7 @@ VCP_SRC = \
drivers/usb_io.c
MCU_COMMON_SRC = \
stm32/system.c \
drivers/accgyro/accgyro_mpu.c \
drivers/bus_i2c_timing.c \
drivers/dshot_bitbang_decode.c \
@ -185,5 +186,8 @@ MSC_SRC = \
msc/usbd_storage_sdio.c \
msc/usbd_storage_sd_spi.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7

View file

@ -118,6 +118,7 @@ VCP_SRC = \
drivers/usb_io.c
MCU_COMMON_SRC = \
stm32/system.c \
drivers/accgyro/accgyro_mpu.c \
drivers/bus_i2c_timing.c \
drivers/dshot_bitbang_decode.c \
@ -163,5 +164,8 @@ MSC_SRC = \
msc/usbd_storage_sdio.c \
msc/usbd_storage_sd_spi.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4

View file

@ -149,6 +149,7 @@ VCP_SRC =
drivers/usb_io.c
MCU_COMMON_SRC = \
stm32/system.c \
drivers/bus_i2c_timing.c \
drivers/bus_quadspi.c \
drivers/dshot_bitbang_decode.c \
@ -197,5 +198,8 @@ MSC_SRC =
msc/usbd_storage_sd_spi.c \
msc/usbd_storage_sdio.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7

View file

@ -264,6 +264,7 @@ VCP_SRC = \
drivers/usb_io.c
MCU_COMMON_SRC = \
stm32/system.c \
drivers/bus_i2c_timing.c \
drivers/bus_quadspi.c \
drivers/dshot_bitbang_decode.c \
@ -312,5 +313,8 @@ MSC_SRC = \
msc/usbd_storage_sd_spi.c \
msc/usbd_storage_sdio.c
SPEED_OPTIMISED_SRC += \
stm32/system.c
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7

View file

@ -252,3 +252,52 @@ extern uint8_t _dmaram_end__;
#define USE_TIMER_MGMT
#define USE_TIMER_AF
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
// speed is packed between modebits 4 and 1,
// 7 6 5 4 3 2 1 0
// 0 <pupd-1> <pupd-0> <mode-4> <speed-1> <speed-0> <mode-1> <mode-0>
// mode-4 is equivalent to STM32F4 otype (pushpull/od)
#define IO_CONFIG(mode, speed, pupd) ((mode) | ((speed) << 2) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_MODE_OUTPUT_PP, GPIO_SPEED_FREQ_HIGH, GPIO_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_MODE_OUTPUT_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLDOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_PULLUP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_LOW, GPIO_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_MODE_INPUT, GPIO_SPEED_FREQ_HIGH, GPIO_PULLUP)
#elif defined(STM32F4)
#define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
#define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
#define IOCFG_OUT_PP_UP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_UP)
#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define IOCFG_AF_PP_UP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_UP)
#define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
#define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
#define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
#define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
#define IOCFG_IPU_25 IO_CONFIG(GPIO_Mode_IN, GPIO_Speed_25MHz, 0, GPIO_PuPd_UP)
#endif
#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4)
#define IO_CONFIG_GET_MODE(cfg) (((cfg) >> 0) & 0x03)
#define IO_CONFIG_GET_SPEED(cfg) (((cfg) >> 2) & 0x03)
#define IO_CONFIG_GET_OTYPE(cfg) (((cfg) >> 4) & 0x01)
#define IO_CONFIG_GET_PULL(cfg) (((cfg) >> 5) & 0x03)
#endif

View file

@ -707,6 +707,18 @@ void CRS_IRQHandler(void)
}
#endif
void initialiseD2MemorySections(void)
{
/* Load DMA_DATA variable intializers into D2 RAM */
extern uint8_t _sdmaram_bss;
extern uint8_t _edmaram_bss;
extern uint8_t _sdmaram_data;
extern uint8_t _edmaram_data;
extern uint8_t _sdmaram_idata;
bzero(&_sdmaram_bss, (size_t) (&_edmaram_bss - &_sdmaram_bss));
memcpy(&_sdmaram_data, &_sdmaram_idata, (size_t) (&_edmaram_data - &_sdmaram_data));
}
void SystemInit (void)
{
memProtReset();

View file

@ -32,7 +32,7 @@
#include "drivers/resource.h"
#include "drivers/sound_beeper.h"
#include "system.h"
#include "drivers/system.h"
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7) || defined(AT32F4) || defined(APM32F4)
// See "RM CoreSight Architecture Specification"
@ -311,20 +311,6 @@ void initialiseMemorySections(void)
}
#ifdef STM32H7
void initialiseD2MemorySections(void)
{
/* Load DMA_DATA variable intializers into D2 RAM */
extern uint8_t _sdmaram_bss;
extern uint8_t _edmaram_bss;
extern uint8_t _sdmaram_data;
extern uint8_t _edmaram_data;
extern uint8_t _sdmaram_idata;
bzero(&_sdmaram_bss, (size_t) (&_edmaram_bss - &_sdmaram_bss));
memcpy(&_sdmaram_data, &_sdmaram_idata, (size_t) (&_edmaram_data - &_sdmaram_data));
}
#endif
static void unusedPinInit(IO_t io)
{
if (IOGetOwner(io) == OWNER_FREE) {

View file

@ -22,6 +22,14 @@
#define USE_PARAMETER_GROUPS
#define IOCFG_OUT_PP 0
#define IOCFG_OUT_OD 0
#define IOCFG_AF_PP 0
#define IOCFG_AF_OD 0
#define IOCFG_IPD 0
#define IOCFG_IPU 0
#define IOCFG_IN_FLOATING 0
#define U_ID_0 0
#define U_ID_1 1
#define U_ID_2 2