8 #define I2C_50KHz_SPEED 50000 9 #define I2C_75KHz_SPEED 75000 10 #define I2C_100KHz_SPEED 100000 11 #define I2C_250KHz_SPEED 250000 12 #define I2C_400KHz_SPEED 400000 15 #define I2C_BIT_MASK ((uint32_t)0x00FFFFFF) 18 #define I2C_BIT_SMBALERT ((uint32_t)0x0008000) 19 #define I2C_BIT_TIMEOUT ((uint32_t)0x4000) 20 #define I2C_BIT_PECERR ((uint32_t)0x1000) 21 #define I2C_BIT_OVR ((uint32_t)0x0800) 22 #define I2C_BIT_AF ((uint32_t)0x0400) 23 #define I2C_BIT_ARLO ((uint32_t)0x0200) 24 #define I2C_BIT_BERR ((uint32_t)0x0100) 25 #define I2C_BIT_TXE ((uint32_t)0x0080) 26 #define I2C_BIT_RXNE ((uint32_t)0x0040) 27 #define I2C_BIT_STOPF ((uint32_t)0x0010) 28 #define I2C_BIT_ADD10 ((uint32_t)0x0008) 29 #define I2C_BIT_BTF ((uint32_t)0x0004) 30 #define I2C_BIT_ADDR ((uint32_t)0x0002) 31 #define I2C_BIT_SB ((uint32_t)0x0001) 34 #define I2C_IE_BUF ((uint16_t)0x0400) 35 #define I2C_IE_EVT ((uint16_t)0x0200) 36 #define I2C_IE_ERR ((uint16_t)0x0100) 39 #define I2C_BIT_DUALF ((uint32_t)0x0080) 40 #define I2C_BIT_SMBHOST ((uint32_t)0x0040) 41 #define I2C_BIT_SMBDEFAULT ((uint32_t)0x0020) 42 #define I2C_BIT_GENCALL ((uint32_t)0x0010) 43 #define I2C_BIT_TRA ((uint32_t)0x0004) 44 #define I2C_BIT_BUSY ((uint32_t)0x0002) 45 #define I2C_BIT_MSL ((uint32_t)0x0001) 48 #define I2C_NACKPosition_Next ((uint16_t)0x0800) 49 #define I2C_NACKPosition_Current ((uint16_t)0xF7FF) 51 #define I2C_Direction_Transmitter ((uint8_t)0x00) 52 #define I2C_Direction_Receiver ((uint8_t)0x01) 57 #define I2C_TIMEOUT (300)// in uS - wait for byte transfer: 10us per bit (100kHz) * 9 bits 58 #define I2C_SMALL_TIMEOUT (50) // in uS - wait for bit 62 #define I2C_NO_DEVICE 1 64 #define I2C_BUS_BUSY 2 65 #define I2C_ERR_WRITE 6 66 #define I2C_NO_REGISTER 8 // 8 Acknolege Failed - not "no device"! this happens when we try to read non-existent register from chip 67 #define I2C_BUS_ERR 99 68 #define I2C_ERR_STOP 98 69 #define I2C_STOP_BERR 97 70 #define I2C_STOP_BUSY 96 71 #define I2C_ERR_TIMEOUT 95 72 #define I2C_ERR_REGISTER 94 73 #define I2C_ERR_OVERRUN 93 74 #define I2C_ERR_STOP_TIMEOUT 92 75 #define I2C_DMA_BUSY 103 76 #define I2C_PENDING 255 77 #define I2C_DMA_ERROR 100 80 #define DMA_BUFSIZE 8 // we read just 6 bytes from compass 120 uint32_t
i2c_write(
const i2c_dev *dev, uint8_t addr,
const uint8_t *tx_buff, uint8_t txlen);
121 uint32_t
i2c_read (
const i2c_dev *dev, uint8_t addr,
const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen);
149 dev->
I2Cx->DR = address | I2C_OAR1_ADD0;
151 dev->
I2Cx->DR = address & (uint8_t)~((uint8_t)I2C_OAR1_ADD0);
156 uint32_t i2c_get_operation_time(uint8_t *psr1);
static void i2c_set_isr_handler(const i2c_dev *dev, Handler h)
const i2c_dev *const _I2C2
uint32_t i2c_write(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen)
void i2c_master_release_bus(const i2c_dev *dev)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void enable_nvic_irq(uint8_t irq, uint8_t prio)
struct i2c_dev i2c_dev
I2C device type.
static void i2c_send_address(const i2c_dev *dev, uint8_t address, uint8_t direction)
void i2c_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
enum Dma_stream dma_stream
const i2c_dev *const _I2C1
bool i2c_bus_reset(const i2c_dev *dev)
void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
static void i2c_clear_isr_handler(const i2c_dev *dev)
#define I2C_Direction_Transmitter
struct I2c_state i2c_state
uint32_t i2c_read(const i2c_dev *dev, uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
void i2c_lowLevel_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
const i2c_dev *const _I2C3