调小i2c超时时间,避免无i2c 设备卡死初始化
This commit is contained in:
parent
3654c3a097
commit
61341f17ca
|
@ -37,6 +37,7 @@
|
|||
#include "drivers/bus_i2c.h"
|
||||
#include "drivers/bus_i2c_impl.h"
|
||||
|
||||
#define I2C_TIMEOUT 0xff
|
||||
|
||||
#ifdef USE_I2C_DEVICE_1
|
||||
void I2C1_ERR_IRQHandler(void)
|
||||
|
@ -118,10 +119,9 @@ 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_US); // addr_ << 1
|
||||
status = i2c_master_transmit(pHandle ,addr_ << 1 , &data, 1, I2C_TIMEOUT); // addr_ << 1
|
||||
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)
|
||||
return i2cHandleHardwareFailure(device);
|
||||
|
||||
|
@ -143,7 +143,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_,
|
|||
|
||||
i2c_status_type status;
|
||||
//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_US);
|
||||
status = i2c_memory_write_int(pHandle ,I2C_MEM_ADDR_WIDIH_8,addr_ << 1, reg_,data, len_,I2C_TIMEOUT);
|
||||
|
||||
if (status == I2C_ERR_STEP_1) {//BUSY
|
||||
return false;
|
||||
|
@ -180,9 +180,9 @@ 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_US);
|
||||
status = i2c_master_receive(pHandle ,addr_ << 1 , buf, len, I2C_TIMEOUT);
|
||||
else
|
||||
status = i2c_memory_read(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, buf, len, I2C_TIMEOUT_US);
|
||||
status = i2c_memory_read(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_, buf, len, I2C_TIMEOUT);
|
||||
|
||||
if (status != I2C_OK) {
|
||||
return i2cHandleHardwareFailure(device);
|
||||
|
@ -213,7 +213,7 @@ bool i2cReadBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, u
|
|||
|
||||
i2c_status_type status;
|
||||
|
||||
status = i2c_memory_read_int(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_,buf, len,I2C_TIMEOUT_US);
|
||||
status = i2c_memory_read_int(pHandle,I2C_MEM_ADDR_WIDIH_8, addr_ << 1, reg_,buf, len,I2C_TIMEOUT);
|
||||
|
||||
if (status == I2C_ERR_STEP_1) {//busy
|
||||
return false;
|
||||
|
|
|
@ -168,7 +168,7 @@ void i2cInit(I2CDevice device)
|
|||
uint32_t i2cPclk=crm_clk_freq.apb1_freq;//at32f43x i2c123 on apb1
|
||||
|
||||
uint32_t I2Cx_CLKCTRL= i2cClockTIMINGR(i2cPclk, pDev->clockSpeed, 0);
|
||||
// uint32_t I2Cx_CLKCTRL=0x80504C4E;
|
||||
// uint32_t I2Cx_CLKCTRL=0x10D01728;
|
||||
|
||||
// HAL_I2C_Init(pHandle);
|
||||
i2c_reset( pHandle->i2cx);
|
||||
|
|
Loading…
Reference in New Issue