APM:Libraries
i2c.c
Go to the documentation of this file.
1 /*
2  (c) 2017 night_ghost@ykoctpa.ru
3 
4 based on: datasheet
5 
6 */
7 
8 #pragma GCC optimize ("O2")
9 
10 #include "i2c.h"
11 #include "dma.h"
12 #include "systick.h"
13 #include "stm32f4xx_i2c.h"
14 #include "stm32f4xx_dma.h"
15 #include <boards.h>
16 
17 
18 #if defined(I2C1_SDA) && defined(I2C1_SCL)
19 static i2c_state i2c1_state IN_CCM;
20 
21 static const i2c_dev i2c_dev1 = {
22  .I2Cx = I2C1,
23  .sda_pin = I2C1_SDA,
24  .scl_pin = I2C1_SCL, // 101 PB8
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,
29 // .dma = { DMA_CR_CH1, DMA1_STREAM0, DMA1_STREAM6 }, // I2C1
30  .state = &i2c1_state,
31 };
33 const i2c_dev* const _I2C1 = &i2c_dev1;
34 #endif
35 
36 #if defined(I2C2_SDA) && defined(I2C2_SCL)
37 static i2c_state i2c2_state IN_CCM;
38 
39 static const i2c_dev i2c_dev2 = {
40  .I2Cx = I2C2,
41  .sda_pin = I2C2_SDA,
42  .scl_pin = I2C2_SCL,
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,
47 // .dma = { DMA_CR_CH7, DMA1_STREAM3 /* intersects with spi2_tx */ , DMA1_STREAM7 }, // I2C2
48  .state = &i2c2_state,
49 };
50 
52 const i2c_dev* const _I2C2 = &i2c_dev2;
53 #endif
54 
55 #if defined(I2C3_SDA) && defined(I2C3_SCL)
56 static i2c_state i2c3_state IN_CCM;
57 
58 static const i2c_dev i2c_dev3 = {
59  .I2Cx = I2C3,
60  .sda_pin = I2C3_SDA,
61  .scl_pin = I2C3_SCL,
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,
66  .state = &i2c3_state,
67 };
68 
70 const i2c_dev* const _I2C3 = &i2c_dev3;
71 #endif
72 
73 
74 typedef enum {TX = 0, RX = 1, TXREG = 2} I2C_Dir;
75 
76 static void delay_10us(){
78 }
79 
80 uint32_t i2c_bit_time=4;
81 
88  GPIO_InitTypeDef GPIO_InitStructure;
89 
90  /* I2C Peripheral Disable */
91  I2C_Cmd(dev->I2Cx, DISABLE);
92 
93  /* I2C DeInit */
94  I2C_DeInit(dev->I2Cx);
95 
97  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
98  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
99  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz; // low speed to prevent glitches
100 
101  {
102  const stm32_pin_info *p = &PIN_MAP[dev->scl_pin];
103 
105  GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit);
106  GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure);
107  }
108 
109  {
110  const stm32_pin_info *p = &PIN_MAP[dev->sda_pin];
111 
113  GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit);
114  GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure);
115  }
116 }
117 
121 static inline void i2c_lowLevel_init(const i2c_dev *dev) {
122  memset(dev->state,0,sizeof(i2c_state));
123 
124  GPIO_InitTypeDef GPIO_InitStructure;
125 
126  /* Enable the i2c */
127  RCC_APB1PeriphClockCmd(dev->clk, ENABLE);
128 
129  /* Reset the Peripheral */
130  RCC_APB1PeriphResetCmd(dev->clk, ENABLE);
131  RCC_APB1PeriphResetCmd(dev->clk, DISABLE);
132 
133  memset(dev->state,0,sizeof(i2c_state));
134 
135 // common configuration
136  /* common GPIO configuration */
137  GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
138  GPIO_InitStructure.GPIO_Speed = GPIO_Speed_25MHz; // GPIO_Speed_50MHz;
139  GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
140  GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
141 
142  { /* Configure SCL */
143  const stm32_pin_info *p = &PIN_MAP[dev->scl_pin];
144 
145  /* Enable the GPIOs for the SCL/SDA Pins */
146  RCC_AHB1PeriphClockCmd(p->gpio_device->clk, ENABLE);
147 
148  GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit);
149  GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure);
150  /* Connect GPIO pins to peripheral, SCL must be first! */
152  }
153 
154  { /* Configure SDA */
155  const stm32_pin_info *p = &PIN_MAP[dev->sda_pin];
156 
157  /* Enable the GPIOs for the SCL/SDA Pins */
158  RCC_AHB1PeriphClockCmd(p->gpio_device->clk, ENABLE);
159 
160  GPIO_InitStructure.GPIO_Pin = BIT(p->gpio_bit);
161  GPIO_Init(p->gpio_device->GPIOx, &GPIO_InitStructure);
163  }
164 }
165 
166 void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
167 {
168 
169  i2c_lowLevel_init(dev); // init GPIO hardware
170 
171  i2c_bit_time = 1000000l / speed;
172 
173  I2C_InitTypeDef I2C_InitStructure; /* I2C configuration */
174  I2C_StructInit(&I2C_InitStructure);
175 
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;
182 
183 
184  I2C_ITConfig(dev->I2Cx, I2C_IT_EVT | I2C_IT_BUF | I2C_IT_ERR, DISABLE);
185 
186  (void)dev->I2Cx->DR;
187 
188  /* I2C Peripheral Enable */
189  I2C_Cmd(dev->I2Cx, ENABLE);
190  /* Apply I2C configuration after enabling it */
191  I2C_Init(dev->I2Cx, &I2C_InitStructure);
192 }
193 
199 void i2c_deinit(const i2c_dev *dev)
200 {
201  i2c_lowLevel_deinit(dev);
202 }
203 
204 static void ev_handler(const i2c_dev *dev, bool err){
205  if(dev->state->handler) revo_call_handler(dev->state->handler, err);
206  else { // disable interrupts
207  dev->I2Cx->CR2 &= ~(I2C_CR2_ITBUFEN|I2C_CR2_ITEVTEN|I2C_CR2_ITERREN); // Disable interrupts
208  }
209 }
210 
211 void I2C1_EV_IRQHandler(); // to avoid warnings
212 void I2C1_ER_IRQHandler();
213 void I2C2_EV_IRQHandler();
214 void I2C2_ER_IRQHandler();
215 void I2C3_EV_IRQHandler();
216 void I2C3_ER_IRQHandler();
217 
218 #if defined(I2C1_SDA) && defined(I2C1_SCL)
219 void I2C1_EV_IRQHandler(){ // I2C1 Event
220  ev_handler(_I2C1, false);
221 }
222 
223 void I2C1_ER_IRQHandler(){ // I2C1 Error
224  ev_handler(_I2C1, true);
225 }
226 #endif
227 
228 #if defined(I2C2_SDA) && defined(I2C2_SCL)
229 void I2C2_EV_IRQHandler(){ // I2C2 Event
230  ev_handler(_I2C2, false);
231 }
232 
233 void I2C2_ER_IRQHandler(){ // I2C2 Error
234  ev_handler(_I2C2, true);
235 }
236 #endif
237 
238 #if defined(I2C3_SDA) && defined(I2C3_SCL)
239 void I2C3_EV_IRQHandler(){ // I2C2 Event
240  ev_handler(_I2C3, false);
241 }
242 
243 void I2C3_ER_IRQHandler(){ // I2C2 Error
244  ev_handler(_I2C3, true);
245 }
246 #endif
247 
249  const stm32_pin_info *p_sda = &PIN_MAP[dev->sda_pin];
250  const stm32_pin_info *p_scl = &PIN_MAP[dev->scl_pin];
251 
252  gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1);
253  gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 1);
256 }
257 
258 
269 #define MAX_I2C_TIME 300 // 300ms before device turn off
270 
271 bool i2c_bus_reset(const i2c_dev *dev) {
272 
273  /* Release both lines */
275 
276  uint32_t t=systick_uptime();
277 
278  const stm32_pin_info *p_sda = &PIN_MAP[dev->sda_pin];
279  const stm32_pin_info *p_scl = &PIN_MAP[dev->scl_pin];
280 
281  /*
282  * Make sure the bus is free by clocking it until any slaves release the
283  * bus.
284  */
285 
286 again:
287  /* Wait for any clock stretching to finish */
288  while (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)) {// device can output 1 so check clock first
289  if(systick_uptime()-t > MAX_I2C_TIME) return false;
290  hal_yield(10);
291  }
292  delay_10us(); // 50kHz
293 
294  while (!gpio_read_bit(p_sda->gpio_device, p_sda->gpio_bit)) {
295  /* Wait for any clock stretching to finish */
296  while (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)){
297  if(systick_uptime()-t > MAX_I2C_TIME) return false;
298  hal_yield(10);
299  }
300  delay_10us(); // 50kHz
301 
302  /* Pull low */
303  gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 0);
304  delay_10us();
305 
306  /* Release high again */
307  gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1);
308  delay_10us();
309  }
310 
311  /* Generate start then stop condition */
312  gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 0);
313  delay_10us();
314  gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 0);
315  delay_10us();
316  gpio_write_bit(p_scl->gpio_device, p_scl->gpio_bit, 1);
317  delay_10us();
318  gpio_write_bit(p_sda->gpio_device, p_sda->gpio_bit, 1);
319 
320  uint32_t rtime = stopwatch_getticks();
321  uint32_t dt = us_ticks * 50; // 50uS
322 
323  while ((stopwatch_getticks() - rtime) < dt) {
324  if (!gpio_read_bit(p_scl->gpio_device, p_scl->gpio_bit)) goto again; // any SCL activity after STOP
325  }
326 
327 // we was generating signals on I2C bus, but BUSY flag senses it even when hardware is off
328 // datasheet: It indicates a communication in progress on the bus. This information is still updated when the interface is disabled (PE=0).
329 
330  dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set SoftReset for some time
331  hal_yield(0);
332  dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear SoftReset flag
333  return true;
334 }
335 
336 
337 
static uint32_t stopwatch_getticks()
Definition: stopwatch.h:33
Handler handler
Definition: i2c.h:90
I2C device type.
Definition: i2c.h:100
void I2C1_EV_IRQHandler()
void i2c_lowLevel_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
Definition: i2c.c:87
const i2c_dev *const _I2C2
static uint64_t systick_uptime(void)
Returns the system uptime, in milliseconds.
Definition: systick.h:44
I2C_Dir
Definition: i2c.c:74
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
#define I2C1_SDA
Definition: board.h:98
void I2C3_ER_IRQHandler()
GPIO_TypeDef * GPIOx
Definition: gpio_hal.h:54
#define I2C2_SDA
Definition: board.h:101
void hal_delay_microseconds(uint16_t t)
Definition: Scheduler.cpp:1432
void gpio_set_mode(const gpio_dev *const dev, uint8_t pin, gpio_pin_mode mode)
Definition: gpio_hal.c:125
void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
Definition: i2c.c:166
Definition: i2c.c:74
i2c_state * state
Definition: i2c.h:109
void i2c_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
Definition: i2c.c:199
uint8_t gpio_af
Definition: i2c.h:105
static void ev_handler(const i2c_dev *dev, bool err)
Definition: i2c.c:204
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
void I2C2_ER_IRQHandler()
#define BIT(shift)
Definition: util.h:40
#define MAX_I2C_TIME
Reset an I2C bus.
Definition: i2c.c:269
#define IN_CCM
Definition: AP_HAL_F4Light.h:9
void I2C1_ER_IRQHandler()
uint32_t clk
Definition: i2c.h:104
#define I2C1_SCL
Definition: board.h:99
uint32_t us_ticks
Definition: stopwatch.c:10
uint8_t sda_pin
Definition: i2c.h:102
Board-specific pin information.
void i2c_master_release_bus(const i2c_dev *dev)
Definition: i2c.c:248
uint32_t clk
Definition: gpio_hal.h:55
const i2c_dev *const _I2C1
Definition: i2c.c:74
uint32_t i2c_bit_time
Definition: i2c.c:80
Definition: i2c.c:74
void I2C2_EV_IRQHandler()
static INLINE uint8_t gpio_read_bit(const gpio_dev *const dev, uint8_t pin)
Definition: gpio_hal.h:130
Definition: i2c.h:89
static void gpio_set_af_mode(const gpio_dev *const dev, uint8_t pin, uint8_t mode)
Definition: gpio_hal.h:102
uint8_t scl_pin
Definition: i2c.h:103
I2C_TypeDef * I2Cx
Definition: i2c.h:101
static void i2c_lowLevel_init(const i2c_dev *dev)
Initializes peripherals used by the I2C driver.
Definition: i2c.c:121
void revo_call_handler(Handler h, uint32_t arg)
Definition: Scheduler.cpp:1420
uint8_t gpio_bit
Definition: boards.h:92
#define I2C2_SCL
Definition: board.h:102
static void delay_10us()
Definition: i2c.c:76
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
void I2C3_EV_IRQHandler()
const gpio_dev *const gpio_device
Definition: boards.h:89
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
bool i2c_bus_reset(const i2c_dev *dev)
Definition: i2c.c:271
static INLINE void gpio_write_bit(const gpio_dev *const dev, uint8_t pin, uint8_t val)
Definition: gpio_hal.h:115
const i2c_dev *const _I2C3