diff --git a/src/main/build/debug_pin.c b/src/main/build/debug_pin.c index c3017a00f0..d590d64fb6 100644 --- a/src/main/build/debug_pin.c +++ b/src/main/build/debug_pin.c @@ -28,7 +28,11 @@ #include "debug_pin.h" typedef struct dbgPinState_s { +#if defined(AT32F43x) + gpio_type * gpio; +#else GPIO_TypeDef *gpio; +#endif uint32_t setBSRR; uint32_t resetBSRR; } dbgPinState_t; @@ -73,6 +77,8 @@ void dbgPinHi(int index) if (dbgPinState->gpio) { #if defined(STM32F7) || defined(STM32H7) dbgPinState->gpio->BSRR = dbgPinState->setBSRR; +#elif defined(AT32F43x) + dbgPinState->gpio->scr = dbgPinState->setBSRR; #else dbgPinState->gpio->BSRRL = dbgPinState->setBSRR; #endif @@ -93,7 +99,9 @@ void dbgPinLo(int index) if (dbgPinState->gpio) { #if defined(STM32F7) || defined(STM32H7) - dbgPinState->gpio->BSRR = dbgPinState->resetBSRR; + dbgPinState->gpio->BSRR = dbgPinState->resetBSRR; +#elif defined(AT32F43x) + dbgPinState->gpio->scr = dbgPinState->resetBSRR; #else dbgPinState->gpio->BSRRL = dbgPinState->resetBSRR; #endif diff --git a/src/main/drivers/bus_i2c_atbsp.c b/src/main/drivers/bus_i2c_atbsp.c index 40145ef258..af98cf4174 100644 --- a/src/main/drivers/bus_i2c_atbsp.c +++ b/src/main/drivers/bus_i2c_atbsp.c @@ -37,7 +37,8 @@ #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" -#define I2C_TIMEOUT 0xff +//#define I2C_TIMEOUT 0x3FFFFF +#define I2C_TIMEOUT 0x8700 //about 120 us at 288 mhz #ifdef USE_I2C_DEVICE_1 void I2C1_ERR_IRQHandler(void) @@ -119,9 +120,32 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) i2c_status_type status; if (reg_ == 0xFF) - status = i2c_master_transmit(pHandle ,addr_ << 1 , &data, 1, I2C_TIMEOUT); // addr_ << 1 + { + status = i2c_master_transmit(pHandle ,addr_ << 1 , &data, 1, I2C_TIMEOUT); // addr_ << 1 + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + } + else + { status = i2c_memory_write(pHandle ,I2C_MEM_ADDR_WIDIH_8,addr_ << 1 , reg_, &data, 1, I2C_TIMEOUT_US); // addr_ << 1 + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + } if (status != I2C_OK) return i2cHandleHardwareFailure(device); @@ -145,6 +169,19 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, //i2c_memory_write_int(i2c_handle_type* hi2c, uint16_t address, uint16_t mem_address, uint8_t* pdata, uint16_t size, uint32_t timeout) status = i2c_memory_write_int(pHandle ,I2C_MEM_ADDR_WIDIH_8,addr_ << 1, reg_,data, len_,I2C_TIMEOUT); + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + else + { + /* wait for the communication to end */ + } + if (status == I2C_ERR_STEP_1) {//BUSY return false; } @@ -180,9 +217,33 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t i2c_status_type status; if (reg_ == 0xFF)//任意地址 + { status = i2c_master_receive(pHandle ,addr_ << 1 , buf, len, I2C_TIMEOUT); + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + } + else - status = i2c_memory_read(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, buf, len, I2C_TIMEOUT); + { + status = i2c_memory_read(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, buf, len, I2C_TIMEOUT); + + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + } + if (status != I2C_OK) { return i2cHandleHardwareFailure(device); @@ -215,6 +276,21 @@ bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, u status = i2c_memory_read_int(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_,buf, len,I2C_TIMEOUT); + if(status != I2C_OK) + { + /* wait for the stop flag to be set */ + i2c_wait_flag(pHandle, I2C_STOPF_FLAG, I2C_EVENT_CHECK_NONE, I2C_TIMEOUT); + + /* clear stop flag */ + i2c_flag_clear(pHandle->i2cx, I2C_STOPF_FLAG); + } + else + { + /* wait for the communication to end */ + i2c_wait_end(pHandle->i2cx, I2C_TIMEOUT); + } + + if (status == I2C_ERR_STEP_1) {//busy return false; } diff --git a/src/main/drivers/bus_i2c_atbsp_init.c b/src/main/drivers/bus_i2c_atbsp_init.c index 047bc46e4f..8c013bcf24 100644 --- a/src/main/drivers/bus_i2c_atbsp_init.c +++ b/src/main/drivers/bus_i2c_atbsp_init.c @@ -173,7 +173,7 @@ void i2cInit(I2CDevice device) // HAL_I2C_Init(pHandle); i2c_reset( pHandle->i2cx); /* config i2c */ - i2c_init( pHandle->i2cx, 0, I2Cx_CLKCTRL); + i2c_init( pHandle->i2cx, 0x0f, I2Cx_CLKCTRL); i2c_own_address1_set( pHandle->i2cx, I2C_ADDRESS_MODE_7BIT, 0x0); diff --git a/src/main/target/AT32F437DEV/target.c b/src/main/target/AT32F437DEV/target.c index 51ae26cee0..4bc45630ca 100644 --- a/src/main/target/AT32F437DEV/target.c +++ b/src/main/target/AT32F437DEV/target.c @@ -27,6 +27,8 @@ #include "drivers/timer.h" #include "drivers/timer_def.h" +#include "build/debug_pin.h" + const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TMR2, CH3, PB10, TIM_USE_ANY |TIM_USE_LED, 0,13,0), // PWM1 - OUT1 MCO1 DMA1 CH2 DEF_TIM(TMR2, CH4, PB11, TIM_USE_ANY |TIM_USE_BEEPER, 0,12,0), // PWM2 - OUT1 DMA1 CH6 @@ -41,3 +43,10 @@ DEF_TIM(TMR4, CH4, PB9, TIM_USE_MOTOR, 0,3,0), // motor4 DMA2 CH4 }; + + + dbgPin_t dbgPins[DEBUG_PIN_COUNT] = { + { .tag = IO_TAG(PE0) }, + { .tag = IO_TAG(PE1) }, + { .tag = IO_TAG(PE2) }, + }; diff --git a/src/main/target/AT32F437DEV/target.h b/src/main/target/AT32F437DEV/target.h index 45f2039f21..bc80dcd3da 100644 --- a/src/main/target/AT32F437DEV/target.h +++ b/src/main/target/AT32F437DEV/target.h @@ -38,6 +38,10 @@ * PA10 OTG1 */ +//debug +#define USE_DEBUG_PIN +#define DEBUG_PIN_COUNT 3 + //buttons #define USE_BUTTONS #define BUTTON_A_PIN PD2 @@ -235,7 +239,7 @@ #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE BIT(2) +#define TARGET_IO_PORTE 0xffff #define USABLE_TIMER_CHANNEL_COUNT 28 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(20) )