APM:Libraries
I2CDevice.cpp
Go to the documentation of this file.
1 /* -*- Mode: C++; indent-tabs-mode: nil; c-basic-offset: 2 -*- */
2 /*
3 
4 (c) 2017 night_ghost@ykoctpa.ru
5 
6  * I2CDriver.cpp --- AP_HAL_F4Light I2C driver.
7  *
8  */
9 #pragma GCC optimize ("O2")
10 
11 #include <AP_HAL/AP_HAL.h>
13 
14 #include "I2CDevice.h"
15 #include <i2c.h>
16 
17 using namespace F4Light;
18 
19 extern const AP_HAL::HAL& hal;
20 
21 F4Light::Semaphore I2CDevice::_semaphores[3]; // 2 HW and 1 SW
22 
23 const timer_dev * I2CDevice::_timers[3] = { // one timer per bus for all devices
24  TIMER4, // for bus 0 so not will be used on AirbotV2 boards when it used for PPM_IN
25  TIMER10,
26  TIMER9,
27 };
28 
29 bool I2CDevice::lateInitDone=false;
30 
31 
32 I2CDevice * I2CDevice::devices[MAX_I2C_DEVICES]; // links to all created devices
33 uint8_t I2CDevice::dev_count; // number of devices
34 
35 #ifdef I2C_DEBUG
36  I2C_State I2CDevice::log[I2C_LOG_SIZE] IN_CCM;
37  uint8_t I2CDevice::log_ptr=0;
38 #endif
39 
40 
41 
43  lateInitDone=true;
44 }
45 
46 
47 I2CDevice::I2CDevice(uint8_t bus, uint8_t address)
48  : _bus(bus)
49  , _address(address)
50  , _retries(5)
51  , _lockup_count(0)
52  , _initialized(false)
53  , _slow(false)
54  , _failed(false)
55  , need_reset(false)
56  , _dev(NULL)
57 {
58 
59 
60  // store link to created devices
62  devices[dev_count++] = this; // links to all created devices
63  }
64 }
65 
67  for(int i=0;i<dev_count;i++){
68  if(devices[i] == this){
69  devices[i] = NULL;
70  }
71  }
72 }
73 
74 
76  if(!lateInitDone) {
77  ((HAL_F4Light&) hal).lateInit();
78  }
79 
81 
82  if(_failed) return;
83 
84  if(_initialized) return;
85 
86  const i2c_dev *dev=NULL;
87 
88  switch(_bus) {
89  case 0: // this is always internal bus
90 #if defined(I2C1_SDA) && defined(I2C1_SCL) && !defined(BOARD_I2C1_DISABLE)
91  _offs =0;
92  #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==0
93  _slow=true;
94  #endif
95 
96  #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C1)
97  if(s_i2c==NULL) s_i2c = new Soft_I2C;
98  { // isolate p_sda & p_scl
99  const stm32_pin_info &p_sda = PIN_MAP[_I2C1->sda_pin];
100  const stm32_pin_info &p_scl = PIN_MAP[_I2C1->scl_pin];
101  s_i2c->init_hw(
102  p_scl.gpio_device, p_scl.gpio_bit,
103  p_sda.gpio_device, p_sda.gpio_bit,
104  _timers[_bus]
105  );
106  }
107  #else
108  dev = _I2C1;
109  #endif
110  break;
111 #else
112  return;
113 #endif
114 
115  case 1: // flexi port - I2C2
116 #if defined(I2C2_SDA) && defined(I2C2_SCL) && !defined( BOARD_I2C2_DISABLE) && !defined(BOARD_HAS_UART3) // in this case I2C on FlexiPort will be bus 2
117 
118  _offs = 2;
119  #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==1
120  _slow=true;
121  #endif
122 
123  #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C2)
124  if(s_i2c==NULL) s_i2c = new Soft_I2C;
125  { // isolate p_sda & p_scl
126  const stm32_pin_info &p_sda = PIN_MAP[_I2C2->sda_pin];
127  const stm32_pin_info &p_scl = PIN_MAP[_I2C2->scl_pin];
128  s_i2c->init_hw(
129  p_scl.gpio_device, p_scl.gpio_bit,
130  p_sda.gpio_device, p_sda.gpio_bit,
131  _timers[_bus]
132  );
133  }
134  #else
135  dev = _I2C2;
136  #endif
137  break;
138 #else
139  return; // not initialized so always returns false
140 #endif
141 
142  case 2: // this bus can use only soft I2C driver
143 #if defined(BOARD_I2C_BUS_SLOW) && BOARD_I2C_BUS_SLOW==2
144  _slow=true;
145 #endif
146 
147 #ifdef BOARD_I2C_FLEXI
148  if(hal_param_helper->_flexi_i2c){ // move external I2C to flexi port
149  #if defined(BOARD_SOFT_I2C) || defined(BOARD_SOFT_I2C3)
150  if(s_i2c==NULL) s_i2c = new Soft_I2C;
151  { // isolate p_sda & p_scl
152  const stm32_pin_info &p_sda = PIN_MAP[_I2C2->sda_pin];
153  const stm32_pin_info &p_scl = PIN_MAP[_I2C2->scl_pin];
154  s_i2c->init_hw(
155  p_scl.gpio_device, p_scl.gpio_bit,
156  p_sda.gpio_device, p_sda.gpio_bit,
157  _timers[_bus]
158  );
159  }
160  #else
161  dev = _I2C2;
162  #endif
163  } else
164 #endif
165  { // external I2C on Input port
166 #if defined(BOARD_SOFT_SCL) && defined(BOARD_SOFT_SDA)
167  if(s_i2c==NULL) s_i2c = new Soft_I2C;
168  s_i2c->init_hw(
169  PIN_MAP[BOARD_SOFT_SCL].gpio_device, PIN_MAP[BOARD_SOFT_SCL].gpio_bit,
170  PIN_MAP[BOARD_SOFT_SDA].gpio_device, PIN_MAP[BOARD_SOFT_SDA].gpio_bit,
171  _timers[_bus]
172  );
173 #endif
174  }
175  break;
176 
177 // TODO
178 #if defined(I2C3_SDA) && defined(I2C3_SCL)
179 #endif
180 
181  default:
182  return;
183  }
184  _dev = dev; // remember
185 
186 
187  if(_dev) {
189 
190  }else if (s_i2c){
191  s_i2c->init( );
192 
193  if(_slow) {
194  s_i2c->set_low_speed(true);
195  }
196  }
197  else { // neither hardware nor software initalization was successful
198  return;
199  }
200  _initialized=true;
201 }
202 
203 
204 
206  if(h && _completion_cb) {// IOC from last call still not called - some error occured so bus reset needed
207  _completion_cb=0;
208  _do_bus_reset();
209  }
210 
211  _completion_cb=h;
212 }
213 
214 
215 
216 
217 bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len)
218 {
219 
220  uint16_t retries=_retries;
221 
222 again:
223 
224 
225  uint32_t ret=0;
226  uint8_t last_op=0;
227 
228  if(!_initialized) {
229  init();
230  if(!_initialized) return false;
231  }
232 
233 
234  if(!_dev){ // no hardware so use soft I2C
235 
236  if(recv_len) memset(recv, 0, recv_len); // for DEBUG
237 
238  if(recv_len==0){ // only write
239  ret=s_i2c->writeBuffer( _address, send_len, send );
240  }else if(send_len==1){ // only read - send byte is address
241  ret=s_i2c->read(_address, *send, recv_len, recv);
242  } else {
243  ret=s_i2c->transfer(_address, send_len, send, recv_len, recv);
244  }
245 
246  if(ret == I2C_NO_DEVICE)
247  return false;
248 
249  if(ret == I2C_OK)
250  return true;
251 
252  if((_retries-retries) > 0) { // don't reset and count for fixed at 2nd try errors
253  _lockup_count ++;
254  last_error = ret;
255 
256  if(!s_i2c->bus_reset()) return false;
257  }
258 
259  _dev->state->busy = false;
260 
261  if(retries--) goto again;
262 
263  return false;
264  } // software I2C
265 
266 // Hardware
267 #ifdef I2C_DEBUG
268  {
269  I2C_State &sp = log[log_ptr]; // remember last operation
270  sp.st_sr1 = _dev->I2Cx->SR1;
271  sp.st_sr2 = _dev->I2Cx->SR2;
272  }
273 #endif
274 
275  // 1st wait for bus free
276  uint32_t t=Scheduler::_micros();
277  while(_dev->state->busy){
278  hal_yield(0);
279  if(Scheduler::_micros() - t > 5000) {
280 // grab_count++;
281  break;
282  }
283  }
284  _dev->state->busy=true;
285 
286  if(recv_len==0) { // only write
287  last_op=1;
288  ret = i2c_write(_address, send, send_len);
289  } else {
290  last_op=0;
291  ret = i2c_read( _address, send, send_len, recv, recv_len);
292  }
293 
294 
295 #ifdef I2C_DEBUG
296  I2C_State &sp = log[log_ptr]; // remember last operation
297 
298  sp.time = Scheduler::_micros();
299  sp.bus =_bus;
300  sp.addr =_address;
301  sp.send_len = send_len;
302  sp.recv_len = recv_len;
303  sp.ret = ret;
304  sp.sr1 = _dev->I2Cx->SR1;
305  sp.sr2 = _dev->I2Cx->SR2;
306  sp.cr1 = _dev->I2Cx->CR1;
307  sp.state = _state;
308  sp.pos = I2C_FINISH;
309  if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
310  else log_ptr=0;
311 #endif
312 
313 
314 
315  if(ret == I2C_PENDING) return true; // transfer with callback
316 
317  if(ret == I2C_OK) {
318  _dev->state->busy=false;
319  return true;
320  }
321 
322 // something went wrong and completion callback never will be called, so release bus semaphore
323  if(_completion_cb) {
324  _completion_cb = 0; // to prevent 2nd bus reset
326  }
327 
328  if(ret == I2C_ERR_STOP || ret == I2C_STOP_BERR || ret == I2C_STOP_BUSY) { // bus or another errors on Stop, or bus busy after Stop.
329  // Data is good but bus reset required
330  need_reset = true;
331  _initialized=false; // will be reinitialized at next transfer
332 
333  _dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set for some time
334 
335  // we not count such errors as _lockup_count
336 
337  Revo_handler h = { .mp=FUNCTOR_BIND_MEMBER(&I2CDevice::do_bus_reset, void) }; // schedule reset as io_task
339 
340  _dev->state->busy=false;
341  return true; // data is OK
342  }
343 
344  if(ret != I2C_NO_DEVICE) { // for all errors except NO_DEVICE do bus reset
345 
346  if(ret == I2C_BUS_BUSY) {
347  _dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set SoftReset for some time
348  hal_yield(0);
349  _dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear SoftReset flag
350  _dev->I2Cx->CR1 |= I2C_CR1_PE; // enable
351  }
352 
353  if((_retries-retries) > 0 || ret==I2C_BUS_ERR){ // not reset bus or log error on 1st try, except ArbitrationLost error
354  last_error = ret; // remember
355  last_error_state = _state; // remember to show
356  if(last_op) last_error+=50; // to distinguish read and write errors
357 
358  _lockup_count ++;
359  _initialized=false; // will be reinitialized at next transfer
360 
361  _do_bus_reset();
362 
363  if(_failed) {
364  _dev->state->busy=false;
365  return false;
366  }
367  }
368  }
369  _dev->state->busy=false;
370 
371  if(retries--) goto again;
372 
373  return false;
374 }
375 
376 
377 void I2CDevice::do_bus_reset(){ // public - with semaphores
379  _do_bus_reset();
380  _semaphores[_bus].give();
381  }
382 }
383 
384 void I2CDevice::_do_bus_reset(){ // private
385  _dev->state->busy=true;
386  _dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear soft reset flag
387 
388  if(!need_reset) return; // already done
389 
390  i2c_deinit(_dev); // disable I2C hardware
391  if(!i2c_bus_reset(_dev)) {
392  _failed = true; // can't do it in limited time
393  }
394  need_reset = false; // done
395  _dev->state->busy=false;
396 }
397 
398 
399 bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
400  uint32_t recv_len, uint8_t times){
401 
402  while(times--) {
403  bool ret = read_registers(first_reg, recv, recv_len);
404  if(!ret) return false;
405  recv += recv_len;
406  }
407 
408  return true;
409 }
410 
411 
412 enum I2C_state {
419  I2C_done // 6
420 } ;
421 
422 
423 /*
424  moved from low layer to be properly integrated to multitask
425 
426 */
427 
428 
429 
430 /* Send a buffer to the i2c port */
431 uint32_t I2CDevice::i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len) {
432 
433  uint32_t ret = wait_stop_done(true);
434  if(ret!=I2C_OK) return ret;
435 
436  _addr=addr;
437  _tx_buff=tx_buff;
438  _tx_len=len;
439  _rx_len=0; // only write
440 
441 
443 
446 
447  // Bus got! enable Acknowledge for our operation
448  _dev->I2Cx->CR1 |= I2C_CR1_ACK;
449  _dev->I2Cx->CR1 &= ~I2C_NACKPosition_Next;
450 
451  // need to wait until transfer complete
452  uint32_t t = hal_micros();
453  uint32_t timeout = i2c_bit_time * 9 * (len+1) * 8 + 100; // time to transfer all data *8 plus 100uS
454 
455  _task = Scheduler::get_current_task();// if function called from task - store it and pause
456 
458  // Send START condition
459  _dev->I2Cx->CR1 |= I2C_CR1_START;
460  _dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN; // Enable interrupts
461 
462  if(_task) Scheduler::task_pause(timeout);
464 
465  if(_completion_cb) return I2C_PENDING;
466 
467  while (hal_micros() - t < timeout && _error==I2C_ERR_TIMEOUT) {
468  hal_yield(0);
469  }
470 
472 
473  return _error;
474 }
475 
476 uint32_t I2CDevice::i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
477 {
478  uint32_t ret = wait_stop_done(false); // wait for bus release from previous transfer and force it if needed
479  if(ret!=I2C_OK) return ret;
480 
481  _addr=addr;
482  _tx_buff=tx_buff;
483  _tx_len=txlen;
484  _rx_buff=rx_buff;
485  _rx_len=rxlen;
486 
487 
489 
492 
493  _dev->I2Cx->CR1 &= ~I2C_NACKPosition_Next; // I2C_NACKPosition_Current
494  _dev->I2Cx->CR1 |= I2C_CR1_ACK; // enable Acknowledge for our operation
495 
496  uint32_t t = hal_micros();
497  uint32_t timeout = i2c_bit_time * 9 * (txlen+rxlen) * 8 + 100; // time to transfer all data *8 plus 100uS
498  _task = Scheduler::get_current_task(); // if function called from task - store it and pause
499 
501 #ifdef I2C_DEBUG
502  {
503  I2C_State &sp = log[log_ptr]; // remember last operation
504 
505  sp.time = Scheduler::_micros();
506  sp.cr1 = _dev->I2Cx->CR1;
507  sp.sr1 = _dev->I2Cx->SR1;
508  sp.sr2 = _dev->I2Cx->SR2;
509  sp.state = _state;
510  sp.pos = I2C_START;
511  if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
512  else log_ptr=0;
513  }
514 #endif
515 
516  _dev->I2Cx->CR1 |= I2C_CR1_START; // Send START condition
517  if(_task) Scheduler::task_pause(timeout);
518  _dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN; // Enable interrupts
519 
520 #ifdef I2C_DEBUG
521  I2C_State &sp = log[log_ptr]; // remember last operation
522 
523  sp.time = Scheduler::_micros();
524  sp.cr1 = _dev->I2Cx->CR1;
525  sp.sr1 = _dev->I2Cx->SR1;
526  sp.sr2 = _dev->I2Cx->SR2;
527  sp.state = _state;
528  sp.pos = I2C_START;
529  if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
530  else log_ptr=0;
531 #endif
533 
534  if(_completion_cb) return I2C_PENDING;
535 
536  // need to wait until DMA transfer complete
537  while (hal_micros() - t < timeout && _error==I2C_ERR_TIMEOUT) {
538  hal_yield(0);
539  }
540 
542 
543  return _error;
544 }
545 
547  bool err;
548 
549  // get err parameter
550  asm volatile("MOV %0, r1\n\t" : "=rm" (err));
551 
552  uint32_t sr1itflags = _dev->I2Cx->SR1;
553  uint32_t itsources = _dev->I2Cx->CR2;
554 
555  if(err){
556 
557  /* I2C Bus error interrupt occurred ----------------------------------------*/
558  if(((sr1itflags & I2C_BIT_BERR) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) { /* Clear BERR flag */
559  _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_BERR); // Errata 2.4.6
560  }
561 
562  /* I2C Arbitration Loss error interrupt occurred ---------------------------*/
563  if(((sr1itflags & I2C_BIT_ARLO) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
565 
566  /* Clear ARLO flag */
567  _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_ARLO); // reset them
568  }
569 
570  /* I2C Acknowledge failure error interrupt occurred ------------------------*/
571  if(((sr1itflags & I2C_BIT_AF) != RESET) && ((itsources & I2C_IE_ERR) != RESET)) {
572  /* Clear AF flag */
573  _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_AF); // reset it
574 
575  if(_state == I2C_want_ADDR) { // address transfer
577  } else if(_state == I2C_want_RX_ADDR) { // restart
579  } else {
580  _error = I2C_ERROR;
581  }
582 
583  _dev->I2Cx->CR1 |= I2C_CR1_STOP; /* Generate Stop */
584  }
585 
586 #ifdef I2C_DEBUG
587  I2C_State &sp = log[log_ptr]; // remember last operation
588 
589  sp.time = Scheduler::_micros();
590  sp.sr1 = sr1itflags;
591  sp.sr2 = _dev->I2Cx->SR2;
592  sp.cr1 = _dev->I2Cx->CR1;
593  sp.state = _state;
594  sp.pos = I2C_ERR;
595  if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
596  else log_ptr=0;
597 #endif
598 
599  if(_error) { // смысла ждать больше нет
600  finish_transfer();
601  }
602  }else{
603 
604  /* SB Set ----------------------------------------------------------------*/
605  if(((sr1itflags & I2C_BIT_SB & I2C_BIT_MASK) != RESET) && ((itsources & I2C_IE_EVT) != RESET)) {
606  // Send address for write
607  if(_tx_len){
610  } else {
613  }
614 
615  _dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_STOP); /* clear STOP condition - just to touch CR1*/
616  }
617  /* ADDR Set --------------------------------------------------------------*/
618  else if(((sr1itflags & I2C_BIT_ADDR & I2C_BIT_MASK) != RESET) && ((itsources & I2C_IE_EVT) != RESET)) {
619  /* Clear ADDR register by reading SR1 then SR2 register (SR1 has already been read) */
620 
621  if(_tx_len) { // transmit
622  // all flags set before
624  }else { // receive
625  _dev->I2Cx->CR2 |= I2C_CR2_ITBUFEN; // enable RXNE interrupt
626  if(_rx_len == 1) { // Disable Acknowledge for 1-byte transfer
627  _dev->I2Cx->CR1 &= ~I2C_CR1_ACK;
628  } else {
629  _dev->I2Cx->CR1 |= I2C_CR1_ACK;
630  }
632  }
633  }
634 
635  uint32_t sr2itflags = _dev->I2Cx->SR2; // read SR2 - ADDR is cleared
636 
637  if((itsources & I2C_IE_BUF) != RESET ){ // data io
638 
639  if((sr1itflags & I2C_BIT_TXE & I2C_BIT_MASK) != RESET) {// TXE set
640  if((sr2itflags & (I2C_BIT_TRA) & I2C_BIT_MASK) != RESET) { // I2C in mode Transmitter
641 
642  if(_tx_len) {
643  _dev->I2Cx->DR = *_tx_buff++; // 1 byte
644  _tx_len--;
645  } else { // tx is over and last byte is sent
646  _dev->I2Cx->CR2 &= ~I2C_CR2_ITBUFEN; // disable TXE interrupt
647  }
648  }
649  }
650  if((sr1itflags & I2C_BIT_RXNE & I2C_BIT_MASK) != RESET) { // RXNE set
651  if(_rx_len && !_tx_len) {
652  *_rx_buff++ = (uint8_t)(_dev->I2Cx->DR);
653  _rx_len -= 1; // 1 byte done
654 
655  if(_rx_len == 1) { // last second byte
656  _dev->I2Cx->CR1 &= ~I2C_CR1_ACK; // Disable Acknowledgement - send NACK for last byte
657  _dev->I2Cx->CR1 |= I2C_CR1_STOP; // Send STOP
658  } else if(_rx_len==0) {
659  _error = I2C_OK;
660  _state = I2C_done;
661 
662  finish_transfer();
663  }
664  } else { // fake byte after enable ITBUF
665  (void)_dev->I2Cx->DR;
666  }
667  }
668  }
669  if((sr1itflags & I2C_BIT_BTF & I2C_BIT_MASK) != RESET) {// BTF set
670  if((sr2itflags & (I2C_BIT_TRA) & I2C_BIT_MASK) != RESET) { // I2C in mode Transmitter
671  // BTF on transmit
672  if(_rx_len) {
673  // wait a little - some devices requires time for internal operations
674  delay_ns100(3);
675 
676  // Send START condition a second time
677  _dev->I2Cx->CR1 |= I2C_CR1_START;
679  _dev->I2Cx->CR2 &= ~I2C_CR2_ITBUFEN; // disable TXE interrupt - just for case, should be disabled
680  } else {
681  _dev->I2Cx->CR1 |= I2C_CR1_STOP; // Send STOP condition
682  _error = I2C_OK; // TX is done
683  _state = I2C_done;
684  finish_transfer();
685  }
686 
687  } else { // BTF on receive??
688  //
689  }
690  }
691 
692 #ifdef I2C_DEBUG
693  I2C_State &sp = log[log_ptr]; // remember last operation
694 
695  sp.time = Scheduler::_micros();
696  sp.sr1 = sr1itflags;
697  sp.sr2 = sr2itflags;
698  sp.cr1 = _dev->I2Cx->CR1;
699  sp.state = _state;
700  sp.pos = I2C_ISR;
701  if(log_ptr<I2C_LOG_SIZE-1) log_ptr++;
702  else log_ptr=0;
703 #endif
704 
705  }
706 }
707 
708 
710 
711  _dev->I2Cx->CR2 &= ~(I2C_CR2_ITBUFEN | I2C_CR2_ITEVTEN | I2C_CR2_ITERREN); // Disable interrupts
713  _dev->I2Cx->CR1 &= ~(I2C_CR1_STOP | I2C_CR1_START); // clear CR1 - just for case
714 
715  Handler h;
716  if( (h=_completion_cb) ){ // io completion
717  _completion_cb=0; // only once and before call because handler can set it itself
718 
719  revo_call_handler(h, (uint32_t)_dev);
720  }
721 
722  if(_task){ // resume paused task
724  _task=NULL;
725  }
726 }
727 
728 uint32_t I2CDevice::wait_stop_done(bool is_write){
729  uint32_t sr1;
730  uint32_t t;
731 
732  uint8_t ret;
733  uint8_t i;
734  for(i=0; i<10; i++){
735 
736  if( (_dev->I2Cx->CR1 & I2C_CR1_PE) ) {
737  ret=I2C_OK;
738  } else {
739  ret=91;
740  }
741  // Wait to make sure that STOP control bit has been cleared - bus released
742  t = hal_micros();
743  while (_dev->I2Cx->CR1 & I2C_CR1_STOP ){
744  if((sr1=_dev->I2Cx->SR1) & I2C_BIT_BERR & I2C_BIT_MASK) _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_BERR); // Errata 2.4.6
745 
746  if(sr1 & I2C_BIT_ARLO & I2C_BIT_MASK) { // arbitration lost or bus error
747  _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_ARLO); // reset them
748  ret= I2C_STOP_BERR; // bus error on STOP
749  break;
750  }
751  if(sr1 & I2C_BIT_TIMEOUT & I2C_BIT_MASK) { // bus timeout
752  _dev->I2Cx->SR1 = (uint16_t)(~I2C_BIT_TIMEOUT); // reset it
753  ret= I2C_ERR_STOP_TIMEOUT; // STOP generated by hardware
754  break;
755  }
756 
757  if (hal_micros() - t > I2C_SMALL_TIMEOUT) {
758  ret=I2C_ERR_STOP;
759  break;
760  }
761  hal_yield(0);
762  }
763 
764  /* wait while the bus is busy */
765  t = hal_micros();
766  while ((_dev->I2Cx->SR2 & (I2C_BIT_BUSY) & I2C_BIT_MASK) != 0) {
767  if (hal_micros() - t > I2C_SMALL_TIMEOUT) {
768  ret=2; // bus busy
769  break;
770  }
771 
772  hal_yield(0);
773  }
774 
775 
776  if(ret==I2C_OK) return ret;
777 
778  _dev->I2Cx->CR1 |= I2C_CR1_SWRST; // set SoftReset for some time
779  hal_yield(0);
780  _dev->I2Cx->CR1 &= (uint16_t)(~I2C_CR1_SWRST); // clear SoftReset flag
781  _dev->I2Cx->CR1 |= I2C_CR1_PE; // enable
782 
783  if(i>1){
784  last_error = ret; // remember
785  if(is_write) last_error+=50;
786 
787  _lockup_count ++;
788  _initialized=false; // will be reinitialized in init()
789 
790  need_reset=true;
791  init();
792 
793  if(!_initialized) return ret;
794 
795  }
796 
797  }
798 
799  return I2C_OK;
800 }
801 
802 
803 
804 /*
805  errata 2.4.6
806 Spurious Bus Error detection in Master mode
807 Description
808 In Master mode, a bus error can be detected by mistake, so the BERR flag can be wrongly
809 raised in the status register. This will generate a spurious Bus Error interrupt if the interrupt
810 is enabled. A bus error detection has no effect on the transfer in Master mode, therefore the
811 I2C transfer can continue normally.
812 Workaround
813 If a bus error interrupt is generated in Master mode, the BERR flag must be cleared by
814 software. No other action is required and the on-going transfer can be handled normally
815 
816 */
#define BOARD_SOFT_SCL
Definition: board.h:78
#define I2C_OK
Definition: i2c.h:61
#define I2C_BUS_BUSY
Definition: i2c.h:64
static Handler get_handler(AP_HAL::MemberProc proc)
Definition: Scheduler.h:436
AP_HAL::MemberProc mp
Definition: handler.h:18
#define I2C_ERR_STOP_TIMEOUT
Definition: i2c.h:74
#define MAX_I2C_DEVICES
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: I2CDevice.h:32
Handler h
Definition: handler.h:20
#define I2C_BUS_ERR
Definition: i2c.h:67
I2C device type.
Definition: i2c.h:100
#define I2C_IE_BUF
Definition: i2c.h:34
#define I2C_IE_EVT
Definition: i2c.h:35
uint8_t read(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t *buf)
Definition: tim_i2c.cpp:532
static void i2c_set_isr_handler(const i2c_dev *dev, Handler h)
Definition: i2c.h:128
uint32_t _lockup_count
Definition: I2CDevice.h:149
uint8_t transfer(uint8_t addr, uint8_t send_len, const uint8_t *send, uint8_t len, uint8_t *buf)
Definition: tim_i2c.cpp:549
#define LeaveCriticalSection
Definition: Scheduler.h:40
Soft_I2C * s_i2c
Definition: I2CDevice.h:159
const i2c_dev *const _I2C2
uint32_t wait_stop_done(bool v)
Definition: I2CDevice.cpp:728
const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS]
#define I2C_ERR_TIMEOUT
Definition: i2c.h:71
void init_hw(const gpio_dev *scl_dev, uint8_t scl_bit, const gpio_dev *sda_dev, uint8_t sda_bit, const timer_dev *tim)
Definition: tim_i2c.cpp:114
#define I2C_400KHz_SPEED
Definition: i2c.h:12
static void * get_current_task()
Definition: Scheduler.h:299
uint8_t last_error_state
Definition: I2CDevice.h:152
static void task_resume(void *h)
Definition: Scheduler.h:321
static uint8_t dev_count
Definition: I2CDevice.h:165
uint8_t * _rx_buff
Definition: I2CDevice.h:175
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
uint32_t i2c_write(uint8_t addr, const uint8_t *tx_buff, uint8_t len)
Definition: I2CDevice.cpp:431
#define I2C_BIT_RXNE
Definition: i2c.h:26
#define I2C_ERR_REGISTER
Definition: i2c.h:72
#define I2C_PENDING
Definition: i2c.h:76
#define I2C_STOP_BERR
Definition: i2c.h:69
uint32_t hal_micros()
Definition: Scheduler.cpp:1434
#define I2C_BIT_BTF
Definition: i2c.h:29
#define I2C_BIT_ARLO
Definition: i2c.h:23
static void _register_io_process(Handler h, Revo_IO_Flags flags)
Definition: Scheduler.cpp:391
#define I2C_SMALL_TIMEOUT
Definition: i2c.h:58
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times)
Definition: I2CDevice.cpp:399
void i2c_init(const i2c_dev *dev, uint16_t address, uint32_t speed)
Definition: i2c.c:166
i2c_state * state
Definition: i2c.h:109
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.cpp:217
void init()
Definition: tim_i2c.cpp:143
const i2c_dev * _dev
Definition: I2CDevice.h:158
#define I2C_BIT_ADDR
Definition: i2c.h:30
static void lateInit()
Definition: I2CDevice.cpp:42
#define TIMER4
Definition: timer.h:612
void i2c_deinit(const i2c_dev *dev)
DeInitializes peripherals used by the I2C driver.
Definition: i2c.c:199
#define BOARD_SOFT_SDA
Definition: board.h:79
volatile uint8_t _error
Definition: I2CDevice.h:171
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
#define I2C_BIT_AF
Definition: i2c.h:22
void register_completion_callback(Handler h)
Definition: I2CDevice.cpp:205
#define IN_CCM
Definition: AP_HAL_F4Light.h:9
uint32_t i2c_read(uint8_t addr, const uint8_t *tx_buff, uint8_t txlen, uint8_t *rx_buff, uint8_t rxlen)
Definition: I2CDevice.cpp:476
Handler _completion_cb
Definition: I2CDevice.h:168
bool bus_reset(void)
Definition: tim_i2c.cpp:567
#define I2C_BIT_TXE
Definition: i2c.h:25
void set_low_speed(bool s)
Definition: tim_i2c.h:107
#define I2C_250KHz_SPEED
Definition: i2c.h:11
static void i2c_send_address(const i2c_dev *dev, uint8_t address, uint8_t direction)
Definition: i2c.h:145
#define I2C_IE_ERR
Definition: i2c.h:36
#define I2C_BIT_BUSY
Definition: i2c.h:44
#define NULL
Definition: hal_types.h:59
#define I2C_NACKPosition_Next
Definition: i2c.h:48
#define TIMER10
Definition: timer.h:618
uint8_t sda_pin
Definition: i2c.h:102
#define I2C_BIT_SB
Definition: i2c.h:31
#define I2C_ERR_STOP
Definition: i2c.h:68
#define TIMER9
Definition: timer.h:617
static uint32_t _micros()
Definition: Scheduler.h:232
const i2c_dev *const _I2C1
uint32_t i2c_bit_time
Definition: i2c.c:80
static const timer_dev * _timers[3]
Definition: I2CDevice.h:162
static void i2c_clear_isr_handler(const i2c_dev *dev)
Definition: i2c.h:140
#define I2C_Direction_Receiver
Definition: i2c.h:52
#define I2C_ERROR
Definition: i2c.h:63
#define I2C_NO_DEVICE
Definition: i2c.h:62
I2C_state
Definition: I2CDevice.cpp:412
uint8_t scl_pin
Definition: i2c.h:103
static F4Light::I2CDevice * devices[MAX_I2C_DEVICES]
Definition: I2CDevice.h:164
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
static bool lateInitDone
Definition: I2CDevice.h:166
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
#define I2C_BIT_TIMEOUT
Definition: i2c.h:19
#define I2C_Direction_Transmitter
Definition: i2c.h:51
uint64_t Handler
Definition: hal_types.h:19
static void task_pause(uint32_t t)
Definition: Scheduler.h:316
static void delay_ns100(uint32_t us)
Definition: delay.h:36
#define I2C_BIT_MASK
Definition: i2c.h:15
const uint8_t * _tx_buff
Definition: I2CDevice.h:173
I2C_TypeDef * I2Cx
Definition: i2c.h:101
void revo_call_handler(Handler h, uint32_t arg)
Definition: Scheduler.cpp:1420
uint8_t gpio_bit
Definition: boards.h:92
#define EnterCriticalSection
Definition: Scheduler.h:39
static F4Light::Semaphore _semaphores[3]
Definition: I2CDevice.h:161
Stores STM32-specific information related to a given Maple pin.
Definition: boards.h:88
const gpio_dev *const gpio_device
Definition: boards.h:89
uint8_t writeBuffer(uint8_t addr_, uint8_t len_, const uint8_t *data)
Definition: tim_i2c.cpp:516
#define I2C_BIT_BERR
Definition: i2c.h:24
void hal_yield(uint16_t ttw)
Definition: Scheduler.cpp:1430
bool i2c_bus_reset(const i2c_dev *dev)
Definition: i2c.c:271
volatile bool busy
Definition: i2c.h:91
uint8_t last_error
Definition: I2CDevice.h:151
#define I2C_STOP_BUSY
Definition: i2c.h:70
#define I2C_BIT_TRA
Definition: i2c.h:43