8 #pragma GCC optimize ("O2") 13 #include "stm32f4xx_i2c.h" 14 #include "stm32f4xx_dma.h" 18 #if defined(I2C1_SDA) && defined(I2C1_SCL) 21 static const i2c_dev i2c_dev1 = {
25 .clk = RCC_APB1Periph_I2C1,
26 .gpio_af = GPIO_AF_I2C1,
27 .ev_nvic_line = I2C1_EV_IRQn,
28 .er_nvic_line = I2C1_ER_IRQn,
36 #if defined(I2C2_SDA) && defined(I2C2_SCL) 39 static const i2c_dev i2c_dev2 = {
43 .clk = RCC_APB1Periph_I2C2,
44 .gpio_af = GPIO_AF_I2C2,
45 .ev_nvic_line = I2C2_EV_IRQn,
46 .er_nvic_line = I2C2_ER_IRQn,
55 #if defined(I2C3_SDA) && defined(I2C3_SCL) 58 static const i2c_dev i2c_dev3 = {
62 .clk = RCC_APB1Periph_I2C3,
63 .gpio_af = GPIO_AF_I2C3,
64 .ev_nvic_line = I2C3_EV_IRQn,
65 .er_nvic_line = I2C3_ER_IRQn,
88 GPIO_InitTypeDef GPIO_InitStructure;
91 I2C_Cmd(dev->
I2Cx, DISABLE);
94 I2C_DeInit(dev->
I2Cx);
97 GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
98 GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
99 GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
124 GPIO_InitTypeDef GPIO_InitStructure;
127 RCC_APB1PeriphClockCmd(dev->
clk, ENABLE);
130 RCC_APB1PeriphResetCmd(dev->
clk, ENABLE);
131 RCC_APB1PeriphResetCmd(dev->
clk, DISABLE);
137 GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
138 GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz;
139 GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
140 GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
173 I2C_InitTypeDef I2C_InitStructure;
174 I2C_StructInit(&I2C_InitStructure);
176 I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
177 I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
178 I2C_InitStructure.I2C_OwnAddress1 = address;
179 I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
180 I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
181 I2C_InitStructure.I2C_ClockSpeed = speed;
184 I2C_ITConfig(dev->
I2Cx, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE);
189 I2C_Cmd(dev->
I2Cx, ENABLE);
191 I2C_Init(dev->
I2Cx, &I2C_InitStructure);
207 dev->
I2Cx->CR2 &= ~(I2C_CR2_ITBUFEN|I2C_CR2_ITEVTEN|I2C_CR2_ITERREN);
218 #if defined(I2C1_SDA) && defined(I2C1_SCL) 228 #if defined(I2C2_SDA) && defined(I2C2_SCL) 238 #if defined(I2C3_SDA) && defined(I2C3_SCL) 269 #define MAX_I2C_TIME 300 // 300ms before device turn off 330 dev->
I2Cx->CR1 |= I2C_CR1_SWRST;
332 dev->
I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST);
static uint32_t stopwatch_getticks()
void I2C1_EV_IRQHandler()
void i2c_lowLevel_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
const i2c_dev *const _I2C2
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
void I2C3_ER_IRQHandler()
void hal_delay_microseconds(uint16_t t)
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
void i2c_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
static void ev_handler(const i2c_dev *dev, bool err)
static AP_HAL::OwnPtr< AP_HAL::Device > dev
void I2C2_ER_IRQHandler()
#define MAX_I2C_TIME
Reset an I2C bus.
void I2C1_ER_IRQHandler()
Board-specific pin information.
void i2c_master_release_bus(const i2c_dev *dev)
const i2c_dev *const _I2C1
void I2C2_EV_IRQHandler()
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
static void i2c_lowLevel_init(const i2c_dev *dev)
Initializes peripherals used by the I2C driver.
void revo_call_handler(Handler h, uint32_t arg)
Stores STM32-specific information related to a given Maple pin.
void I2C3_EV_IRQHandler()
const gpio_dev *const gpio_device
void hal_yield(uint16_t ttw)
bool i2c_bus_reset(const i2c_dev *dev)
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
const i2c_dev *const _I2C3