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

Add AT32F435 I2C support (#12423)

This commit is contained in:
Steve Evans 2023-02-28 01:25:03 +00:00 committed by GitHub
parent 6a8c365b9c
commit 97487905ee
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
8 changed files with 307 additions and 216 deletions

View file

@ -48,3 +48,13 @@
#define SPI3_MOSI_PIN PC12
#define USE_FLASH_M25P16
#define I2C1_SCL_PIN PB8
#define I2C1_SDA_PIN PB9
#define I2C2_SCL_PIN PB10
#define I2C2_SDA_PIN PB11
#define BARO_I2C_INSTANCE I2C2
#define USE_BARO
#define USE_BARO_MS5611

View file

@ -36,6 +36,8 @@
#include "drivers/bus_i2c_impl.h"
#include "drivers/bus_i2c_timing.h"
#include "pg/pinio.h"
// Number of bits in I2C protocol phase
#define LEN_ADDR 7
#define LEN_RW 1
@ -140,29 +142,29 @@ void i2cInit(I2CDevice device)
// Init I2C peripheral
i2c_handle_type *pHandle = &pDev->handle;
memset(pHandle, 0, sizeof(*pHandle));
pHandle->i2cx = pDev->hardware->reg;
i2c_type *i2cx = (i2c_type *)pDev->hardware->reg;
pHandle->i2cx = i2cx;
crm_clocks_freq_type crm_clk_freq;
crm_clocks_freq_get(&crm_clk_freq);
uint32_t i2cPclk = crm_clk_freq.apb1_freq;
uint32_t I2Cx_CLKCTRL = i2cClockTIMINGR(i2cPclk, pDev->clockSpeed, 0);
i2c_reset( pHandle->i2cx);
i2c_config(pHandle);
i2c_init( pHandle->i2cx, 0x0f, I2Cx_CLKCTRL);
i2c_init(i2cx, 0x0f, I2Cx_CLKCTRL);
i2c_own_address1_set( pHandle->i2cx, I2C_ADDRESS_MODE_7BIT, 0x0);
i2c_own_address1_set(i2cx, I2C_ADDRESS_MODE_7BIT, 0x0);
nvic_irq_enable(hardware->er_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER));
nvic_irq_enable(hardware->ev_irq, NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV), NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV));
i2c_enable(pHandle->i2cx, TRUE);
i2c_enable(i2cx, TRUE);
}
static void i2cUnstick(IO_t scl, IO_t sda)

View file

@ -23,9 +23,13 @@
#if defined(AT32F435ZMT7)
#include "at32f435_437.h"
#include "at32f435_437_i2c.h"
#include "i2c_application.h"
typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState;
#define I2C_TypeDef i2c_type
#define I2C_HandleTypeDef i2c_handle_type
#define GPIO_TypeDef gpio_type
#define GPIO_InitTypeDef gpio_init_type
#define TIM_TypeDef tmr_type

View file

@ -56,13 +56,13 @@ void i2cHardwareConfigure(const i2cConfig_t *i2cConfig)
for (int pindex = 0 ; pindex < I2C_PIN_SEL_MAX ; pindex++) {
if (i2cConfig[device].ioTagScl == hardware->sclPins[pindex].ioTag) {
pDev->scl = IOGetByTag(i2cConfig[device].ioTagScl);
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
pDev->sclAF = hardware->sclPins[pindex].af;
#endif
}
if (i2cConfig[device].ioTagSda == hardware->sdaPins[pindex].ioTag) {
pDev->sda = IOGetByTag(i2cConfig[device].ioTagSda);
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
pDev->sdaAF = hardware->sdaPins[pindex].af;
#endif
}

View file

@ -32,12 +32,12 @@
typedef struct i2cPinDef_s {
ioTag_t ioTag;
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
uint8_t af;
#endif
} i2cPinDef_t;
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
#define I2CPINDEF(pin, af) { DEFIO_TAG_E(pin), af }
#else
#define I2CPINDEF(pin) { DEFIO_TAG_E(pin) }
@ -74,7 +74,7 @@ typedef struct i2cDevice_s {
I2C_TypeDef *reg;
IO_t scl;
IO_t sda;
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4)
#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4)
uint8_t sclAF;
uint8_t sdaAF;
#endif
@ -85,7 +85,7 @@ typedef struct i2cDevice_s {
#if defined(STM32F4)
i2cState_t state;
#endif
#ifdef USE_HAL_DRIVER
#if defined(USE_HAL_DRIVER) || defined(AT32F4)
I2C_HandleTypeDef handle;
#endif
} i2cDevice_t;

View file

@ -44,12 +44,13 @@
#define USE_SPI_DEVICE_3
#define USE_SPI_DMA_ENABLE_LATE
#define USE_GYRO_SPI_MPU6000
#define USE_ACC_SPI_MPU6000
#define USE_EXTI
#define USE_GYRO_EXTI
#define USE_I2C
#define USE_I2C_DEVICE_1
#define USE_I2C_DEVICE_2
#define USE_I2C_DEVICE_3
#define USE_USB_DETECT
#define USE_VCP
@ -76,8 +77,8 @@
#undef USE_OSD
#undef USE_BLACKBOX
#undef USE_SDCARD
#undef USE_BARO
#undef USE_MAG
//#undef USE_BARO
//#undef USE_MAG
#undef USE_SERIAL_4WAY_BLHELI_BOOTLOADER
#undef USE_SERIAL_4WAY_SK_BOOTLOADER

View file

@ -7,7 +7,6 @@ TARGET_MCU_FAMILY := AT32F4
STDPERIPH_DIR = $(ROOT)/lib/main/AT32F43x/drivers
STDPERIPH_SRC = \
$(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) \
$(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) \
EXCLUDES = at32f435_437_dvp.c \
at32f435_437_can.c \
@ -23,10 +22,13 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(SRC_DIR)/startup/at32 \
$(STDPERIPH_DIR)/inc \
$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support \
$(ROOT)/lib/main/AT32F43x/cmsis/cm4
$(ROOT)/lib/main/AT32F43x/cmsis/cm4 \
$(ROOT)/lib/main/AT32F43x/middlewares/i2c_application_library
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
TARGET_SRC := $(ROOT)/lib/main/AT32F43x/middlewares/i2c_application_library/i2c_application.c
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xM.ld
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
@ -34,7 +36,9 @@ DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32
MCU_COMMON_SRC = \
$(addprefix startup/at32/,$(notdir $(wildcard $(SRC_DIR)/startup/at32/*.c))) \
$(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c)))
$(addprefix drivers/at32/,$(notdir $(wildcard $(SRC_DIR)/drivers/at32/*.c))) \
drivers/bus_i2c_timing.c
MCU_EXCLUDES =