drv_i2c.c
Go to the documentation of this file.
1 /*
2  drv_i2c.c : I^2C support for STM32F103
3 
4  Adapted from https://github.com/multiwii/baseflight/blob/master/src/drv_i2c.c
5 
6  This file is part of BreezySTM32.
7 
8  BreezySTM32 is free software: you can redistribute it and/or modify
9  it under the terms of the GNU General Public License as published by
10  the Free Software Foundation, either version 3 of the License, or
11  (at your option) any later version.
12 
13  BreezySTM32 is distributed in the hope that it will be useful,
14  but WITHOUT ANY WARRANTY; without even the implied warranty of
15  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
16  GNU General Public License for more details.
17 
18  You should have received a copy of the GNU General Public License
19  along with BreezySTM32. If not, see <http://www.gnu.org/licenses/>.
20  */
21 
22 #define I2C_DEVICE (I2CDEV_2)
23 
24 #include <stdbool.h>
25 #include <stdio.h>
26 #include <string.h> // memset
27 
28 #include "stm32f10x_conf.h"
29 #include "drv_system.h" // timers, delays, etc
30 #include "drv_gpio.h"
31 
32 #include "drv_i2c.h"
33 
34 // I2C Interrupt Handlers
35 static void i2c_er_handler(void);
36 static void i2c_ev_handler(void);
37 static void i2cUnstick(void);
38 
39 // I2C Circular Buffer Variables
40 static bool i2c_buffer_lock = false;
42 static volatile uint8_t i2c_buffer_head;
43 static volatile uint8_t i2c_buffer_tail;
44 static volatile uint8_t i2c_buffer_count;
45 static void i2c_init_buffer(void);
46 static void i2c_job_handler(void);
47 
48 typedef struct i2cDevice_t {
51  uint16_t scl;
52  uint16_t sda;
53  uint8_t ev_irq;
54  uint8_t er_irq;
55  uint32_t peripheral;
56 } i2cDevice_t;
57 
58 static const i2cDevice_t i2cHardwareMap[] = {
59  { I2C1, GPIOB, Pin_6, Pin_7, I2C1_EV_IRQn, I2C1_ER_IRQn, RCC_APB1Periph_I2C1 },
60  { I2C2, GPIOB, Pin_10, Pin_11, I2C2_EV_IRQn, I2C2_ER_IRQn, RCC_APB1Periph_I2C2 },
61 };
62 
63 // Copy of peripheral address for IRQ routines
64 static I2C_TypeDef *I2Cx = NULL;
65 // Copy of device index for reinit, etc purposes
67 
68 
70 {
72 }
73 
75 {
77 }
78 
80 {
82 }
83 
85 {
87 }
88 
89 #define I2C_DEFAULT_TIMEOUT 30000
90 static volatile uint16_t i2cErrorCount = 0;
91 
92 static volatile bool error = false;
93 static volatile bool busy;
94 
95 static volatile uint8_t addr;
96 static volatile uint8_t reg;
97 static volatile uint8_t bytes;
98 static volatile uint8_t writing;
99 static volatile uint8_t reading;
100 static volatile uint8_t *write_p;
101 static volatile uint8_t *read_p;
102 static volatile uint8_t *status;
103 static void (*complete_CB)(uint8_t);
104 
105 static bool i2cHandleHardwareFailure(void)
106 {
107  i2cErrorCount++;
108  // reinit peripheral + clock out garbage
110  return false;
111 }
112 
113 bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
114 {
115  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
116 
117  addr = addr_ << 1;
118  reg = reg_;
119  writing = 1;
120  reading = 0;
121  write_p = data;
122  read_p = data;
123  bytes = len_;
124  busy = 1;
125  error = false;
126 
127  if (!I2Cx)
128  return false;
129 
130  if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
131  if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
132  while (I2Cx->CR1 & 0x0200 && --timeout > 0) {
133  ; // wait for any stop to finish sending
134  }
135  if (timeout == 0)
136  return i2cHandleHardwareFailure();
137  I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
138  }
139  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
140  }
141 
142  timeout = I2C_DEFAULT_TIMEOUT;
143  while (busy && --timeout > 0) {
144  ;
145  }
146  if (timeout == 0)
147  return i2cHandleHardwareFailure();
148 
149  return !error;
150 }
151 
152 bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
153 {
154  return i2cWriteBuffer(addr_, reg_, 1, &data);
155 }
156 
157 bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf)
158 {
159  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
160 
161  addr = addr_ << 1;
162  reg = reg_;
163  writing = 0;
164  reading = 1;
165  read_p = buf;
166  write_p = buf;
167  bytes = len;
168  busy = 1;
169  error = false;
170 
171  if (!I2Cx)
172  return false;
173 
174  if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
175  if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
176  while (I2Cx->CR1 & 0x0200 && --timeout > 0) {
177  ; // wait for any stop to finish sending
178  }
179  if (timeout == 0)
180  return i2cHandleHardwareFailure();
181  I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
182  }
183  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
184  }
185 
186  timeout = I2C_DEFAULT_TIMEOUT;
187  while (busy && --timeout > 0) {
188  ;
189  }
190  if (timeout == 0)
191  return i2cHandleHardwareFailure();
192 
193  return !error;
194 }
195 
196 bool i2cReadAsync(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf, volatile uint8_t* status_, void (*CB)(uint8_t))
197 {
198  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
199 
200  addr = addr_ << 1;
201  reg = reg_;
202  writing = 0;
203  reading = 1;
204  read_p = buf;
205  write_p = buf;
206  bytes = len;
207  busy = 1;
208  error = false;
209  status = status_;
210  complete_CB = CB;
211 
212  if(!I2Cx)
213  return false;
214 
215  if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
216  if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
217  while (I2Cx->CR1 & 0x0200 && --timeout > 0) { // This is blocking, but happens only
218  ; // wait for any stop to finish sending // if we are stomping on the port (try to avoid)
219  }
220  if (timeout == 0)
221  return i2cHandleHardwareFailure();
222  I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
223  }
224  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
225  }
226  return true;
227 }
228 
229 bool i2cWriteAsync(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf_, volatile uint8_t* status_, void (*CB)(uint8_t))
230 {
231  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
232 
233  addr = addr_ << 1;
234  reg = reg_;
235  writing = 1;
236  reading = 0;
237  write_p = buf_;
238  read_p = buf_;
239  bytes = len_;
240  busy = 1;
241  error = false;
242  status = status_;
243  complete_CB = CB;
244 
245  if (!I2Cx)
246  return false;
247 
248  if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
249  if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
250  while (I2Cx->CR1 & 0x0200 && --timeout > 0) {
251  ; // wait for any stop to finish sending
252  }
253  if (timeout == 0)
254  return i2cHandleHardwareFailure();
255  I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
256  }
257  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
258  }
259  return true;
260 }
261 
262 static void i2c_er_handler(void)
263 {
264  // Read the I2C1 status register
265  volatile uint32_t SR1Register = I2Cx->SR1;
266 
267  if (SR1Register & 0x0F00) // an error
268  {
269  i2cErrorCount++;
270  error = true;
271  }
272 
273  // If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
274  if (SR1Register & 0x0700) {
275  (void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
276  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
277  if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
278  if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
279  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
280  while (I2Cx->CR1 & 0x0100 && --timeout > 0) {
281  ; // wait for any start to finish sending
282  }
283  I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
284  timeout = I2C_DEFAULT_TIMEOUT;
285  while (I2Cx->CR1 & 0x0200 && --timeout > 0) {
286  ; // wait for stop to finish sending
287  }
288  i2cInit(I2Cx_index); // reset and configure the hardware
289  } else {
290  I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
291  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
292  }
293  }
294  }
295  I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
296  if (status)
297  (*status) = I2C_JOB_ERROR; // Update job status
298  if (complete_CB != NULL)
300  busy = 0;
301  i2c_job_handler();
302 }
303 
304 void i2c_ev_handler(void)
305 {
306  static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
307  static int8_t index; // index is signed -1 == send the subaddress
308  uint8_t SReg_1 = I2Cx->SR1; // read the status register here
309 
310  if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual
311  I2Cx->CR1 &= ~0x0800; // reset the POS bit so ACK/NACK applied to the current byte
312  I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on
313  index = 0; // reset the index
314  if (reading && (subaddress_sent || 0xFF == reg)) { // we have sent the subaddr
315  subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
316  if (bytes == 2)
317  I2Cx->CR1 |= 0x0800; // set the POS bit so NACK applied to the final byte in the two byte read
318  I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Receiver); // send the address and set hardware mode
319  } else { // direction is Tx, or we havent sent the sub and rep start
320  I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Transmitter); // send the address and set hardware mode
321  if (reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
322  index = -1; // send a subaddress
323  }
324 
325  } else if (SReg_1 & 0x0002) { // we just sent the address - EV6 in ref manual
326  // Read SR1,2 to clear ADDR
327  __DMB(); // memory fence to control hardware
328  if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
329  I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
330  __DMB();
331  (void)I2Cx->SR2; // clear ADDR after ACK is turned off
332  I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
333  final_stop = 1;
334  I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
335  } else { // EV6 and EV6_1
336  (void)I2Cx->SR2; // clear the ADDR here
337  __DMB();
338  if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1
339  I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
340  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
341  } else if (bytes == 3 && reading && subaddress_sent) // rx 3 bytes
342  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
343  else // receiving greater than three bytes, sending subaddress, or transmitting
345  }
346 
347  } else if (SReg_1 & 0x004) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
348  final_stop = 1;
349  if (reading && subaddress_sent) { // EV7_2, EV7_3
350  if (bytes > 2) { // EV7_2
351  I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
352  read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
353  I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
354  final_stop = 1; // required to fix hardware
355  read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
356  I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
357  } else { // EV7_3
358  if (final_stop){
359  I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
360  }
361  else
362  I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
363  read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
364  read_p[index++] = (uint8_t)I2Cx->DR; // read data N
365  index++; // to show job completed
366  }
367  } else { // EV8_2, which may be due to a subaddress sent or a write completion
368  if (subaddress_sent || (writing)) {
369  if (final_stop)
370  I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
371  else
372  I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
373  index++; // to show that the job is complete
374  } else { // We need to send a subaddress
375  I2C_GenerateSTART(I2Cx, ENABLE); // program the repeated Start
376  subaddress_sent = 1; // this is set back to zero upon completion of the current task
377  }
378  }
379  // we must wait for the start to clear, otherwise we get constant BTF
380  uint32_t timeout = I2C_DEFAULT_TIMEOUT;
381  while (I2Cx->CR1 & 0x0100 && --timeout > 0) {
382  ;
383  }
384 
385  } else if (SReg_1 & 0x0040) { // Byte received - EV7
386  read_p[index++] = (uint8_t)I2Cx->DR;
387  if (bytes == (index + 3))
388  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
389  if (bytes == index) // We have completed a final EV7
390  index++; // to show job is complete
391  } else if (SReg_1 & 0x0080) { // Byte transmitted EV8 / EV8_1
392  if (index != -1) { // we dont have a subaddress to send
393  I2Cx->DR = write_p[index++];
394  if (bytes == index) // we have sent all the data
395  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
396  } else {
397  index++;
398  I2Cx->DR = reg; // send the subaddress
399  if (reading || !bytes) // if receiving or sending 0 bytes, flush now
400  I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
401  }
402  }
403 
404  if (index == bytes + 1) { // we have completed the current job
405  subaddress_sent = 0; // reset this here
406  if (final_stop) { // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
407  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
408  }
409  if (status){
410  (*status) = I2C_JOB_COMPLETE; // Update status
411  }
412  if (complete_CB != NULL){
413  complete_CB(I2C_JOB_COMPLETE); // Call the custom callback (we are finished)
414  }
415  busy = 0;
416  i2c_job_handler(); // Start the next job (if there is one on the queue)
417  }
418 }
419 
420 void i2cInit(I2CDevice index)
421 {
422  NVIC_InitTypeDef nvic;
423  I2C_InitTypeDef i2c;
424 
425  if (index > I2CDEV_MAX)
426  index = I2CDEV_MAX;
427 
428  // Turn on peripheral clock, save device and index
429  I2Cx = i2cHardwareMap[index].dev;
430  I2Cx_index = index;
431  RCC_APB1PeriphClockCmd(i2cHardwareMap[index].peripheral, ENABLE);
432 
433  // clock out stuff to make sure slaves arent stuck
434  // This will also configure GPIO as AF_OD at the end
435  i2cUnstick();
436 
437  // Init I2C peripheral
438  I2C_DeInit(I2Cx);
439  I2C_StructInit(&i2c);
440 
441  I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Enable EVT and ERR interrupts - they are enabled by the first request
442  i2c.I2C_Mode = I2C_Mode_I2C;
445  i2c.I2C_ClockSpeed = 400000;
446  I2C_Cmd(I2Cx, ENABLE);
447  I2C_Init(I2Cx, &i2c);
448 
449  // I2C ER Interrupt
450  nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq;
451  // Set the priority to just below the systick interrupt
454  nvic.NVIC_IRQChannelCmd = ENABLE;
455  NVIC_Init(&nvic);
456 
457  // I2C EV Interrupt
458  nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq;
459  // Set the priority to just below the systick interrupt
461  NVIC_Init(&nvic);
462 
463  // Initialize buffer
464  i2c_init_buffer();
465 }
466 
467 uint16_t i2cGetErrorCounter(void)
468 {
469  return i2cErrorCount;
470 }
471 
472 static void i2cUnstick(void)
473 {
475  gpio_config_t cfg;
476  uint16_t scl, sda;
477  int i;
478 
479  // disable any I2C interrupts
481 
482 
483  // prepare pins
484  gpio = i2cHardwareMap[I2Cx_index].gpio;
485  scl = i2cHardwareMap[I2Cx_index].scl;
486  sda = i2cHardwareMap[I2Cx_index].sda;
487 
488  digitalHi(gpio, scl | sda);
489 
490  cfg.pin = scl | sda;
491  cfg.speed = Speed_2MHz;
492  cfg.mode = Mode_Out_OD;
493  gpioInit(gpio, &cfg);
494 
495  for (i = 0; i < 8; i++) {
496  // Wait for any clock stretching to finish
497  while (!digitalIn(gpio, scl))
498  delayMicroseconds(10);
499 
500  // Pull low
501  digitalLo(gpio, scl); // Set bus low
502  delayMicroseconds(10);
503  // Release high again
504  digitalHi(gpio, scl); // Set bus high
505  delayMicroseconds(10);
506  }
507 
508  // Generate a start then stop condition
509  // SCL PB10
510  // SDA PB11
511  digitalLo(gpio, sda); // Set bus data low
512  delayMicroseconds(10);
513  digitalLo(gpio, scl); // Set bus scl low
514  delayMicroseconds(10);
515  digitalHi(gpio, scl); // Set bus scl high
516  delayMicroseconds(10);
517  digitalHi(gpio, sda); // Set bus sda high
518 
519  // Init pins
520  cfg.pin = scl | sda;
521  cfg.speed = Speed_2MHz;
522  cfg.mode = Mode_AF_OD;
523  gpioInit(gpio, &cfg);
524 
525  // clear the buffer
526 }
527 
529 {
530  if(i2c_buffer_count == 0)
531  {
532  // the queue is empty, stop performing i2c until
533  // a new job is enqueued
534  return;
535  }
536 
537  if(busy)
538  {
539  // wait for the current job to finish. This function
540  // will get called again when the job is done
541  return;
542  }
543 
544  // Perform the job on the front of the queue
545  i2cJob_t* job = i2c_buffer + i2c_buffer_tail;
546 
547  // First, change status to BUSY
548  if (job->status)
549  (*job->status) = I2C_JOB_BUSY;
550 
551  // perform the appropriate job
552  if(job->type == READ)
553  {
554  i2cReadAsync(job->addr,
555  job->reg,
556  job->length,
557  job->data,
558  job->status,
559  job->CB);
560  }
561  else
562  {
563  i2cWriteAsync(job->addr,
564  job->reg,
565  job->length,
566  job->data,
567  job->status,
568  job->CB);
569  }
570 
571  // Increment the tail
572  i2c_buffer_tail = (i2c_buffer_tail + 1) % I2C_BUFFER_SIZE;
573 
574  // Decrement the number of jobs on the buffer
576  return;
577 }
578 
579 void i2c_queue_job(i2cJobType_t type, uint8_t addr_, uint8_t reg_, uint8_t *data, uint8_t length, volatile uint8_t* status_, void(*CB)(uint8_t))
580 {
581  // If this job were going to overflow the buffer, ignore it.
583  {
584  if(status_)
585  *status_ = I2C_JOB_ERROR;
586  return;
587  }
588 
589  // Get a pointer to the head
590  volatile i2cJob_t* job = i2c_buffer + i2c_buffer_head;
591  // Increment the buffer head for next call
592  i2c_buffer_head = (i2c_buffer_head + 1) % I2C_BUFFER_SIZE;
593  // Increment the buffer size
595 
596  // save the data about the job
597  job->type = type;
598  job->data = data;
599  job->addr = addr_;
600  job->reg = reg_;
601  job->length = length;
602  job->next_job = NULL;
603  job->status = status_;
604  job->CB = CB;
605 
606  // change job status
607  if (job->status)
608  (*job->status) = I2C_JOB_QUEUED;
609 
610  if(i2c_buffer_count == 1)
611  {
612  // if the buffer queue was empty, restart i2c job handling
613  i2c_job_handler();
614  }
615  i2c_buffer_lock = false;
616 
617  return;
618 }
619 
621 {
622  // write zeros to the buffer, and set all the indexes to zero
623  memset(i2c_buffer, 0, I2C_BUFFER_SIZE*sizeof(i2cJob_t));
624  i2c_buffer_count = 0;
625  i2c_buffer_head = 0;
626  i2c_buffer_tail = 0;
627 }
628 
uint8_t ev_irq
Definition: drv_i2c.c:53
uint16_t i2cGetErrorCounter(void)
Definition: drv_i2c.c:467
static bool i2c_buffer_lock
Definition: drv_i2c.c:40
static void i2c_job_handler(void)
Definition: drv_i2c.c:528
uint8_t * data
Definition: drv_i2c.h:47
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf)
Definition: drv_i2c.c:157
GPIO_Mode mode
Definition: drv_gpio.h:63
void RCC_APB1PeriphClockCmd(uint32_t RCC_APB1Periph, FunctionalState NewState)
Enables or disables the Low Speed APB (APB1) peripheral clock.
#define digitalIn(p, i)
Definition: drv_gpio.h:70
void i2cInit(I2CDevice index)
Definition: drv_i2c.c:420
static i2cJob_t i2c_buffer[I2C_BUFFER_SIZE+10]
Definition: drv_i2c.c:41
GPIO_Speed speed
Definition: drv_gpio.h:64
static volatile bool error
Definition: drv_i2c.c:92
static uint8_t buf_[2]
Definition: drv_mb1242.c:36
static bool i2cHandleHardwareFailure(void)
Definition: drv_i2c.c:105
static volatile uint8_t writing
Definition: drv_i2c.c:98
bool i2cWriteAsync(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf_, volatile uint8_t *status_, void(*CB)(uint8_t))
Definition: drv_i2c.c:229
uint16_t I2C_AcknowledgedAddress
Definition: stm32f4xx_i2c.h:71
static void(* complete_CB)(uint8_t)
Definition: drv_i2c.c:103
#define I2C_DutyCycle_2
#define I2C_IT_ERR
#define I2C_BUFFER_SIZE
Definition: drv_i2c.h:54
void I2C_AcknowledgeConfig(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C acknowledge feature.
#define I2C_Mode_I2C
void I2C_GenerateSTART(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication START condition.
#define GPIOB
Definition: stm32f4xx.h:2111
void delayMicroseconds(uint32_t us)
Definition: system.c:94
void I2C_Send7bitAddress(I2C_TypeDef *I2Cx, uint8_t Address, uint8_t I2C_Direction)
Transmits the address byte to select the slave device.
static I2CDevice I2Cx_index
Definition: drv_i2c.c:66
__IO uint16_t CR2
Definition: stm32f4xx.h:1324
static volatile uint8_t i2c_buffer_head
Definition: drv_i2c.c:42
static volatile uint8_t * write_p
Definition: drv_i2c.c:100
__IO uint16_t DR
Definition: stm32f4xx.h:1330
void I2C_GenerateSTOP(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication STOP condition.
void I2C1_ER_IRQHandler(void)
Definition: drv_i2c.c:69
static I2C_TypeDef * I2Cx
Definition: drv_i2c.c:64
void(* CB)(uint8_t)
Definition: drv_i2c.h:51
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
Definition: drv_gpio.c:56
static volatile bool busy
Definition: drv_i2c.c:93
static volatile uint8_t * status
Definition: drv_i2c.c:102
uint8_t er_irq
Definition: drv_i2c.c:54
Definition: drv_gpio.h:48
#define I2C_Direction_Transmitter
bool i2cReadAsync(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t *buf, volatile uint8_t *status_, void(*CB)(uint8_t))
Definition: drv_i2c.c:196
__IO uint16_t SR2
Definition: stm32f4xx.h:1334
#define I2C_AcknowledgedAddress_7bit
I2C_TypeDef * dev
Definition: drv_i2c.c:49
static const i2cDevice_t i2cHardwareMap[]
Definition: drv_i2c.c:58
void I2C2_ER_IRQHandler(void)
Definition: drv_i2c.c:79
static volatile uint16_t i2cErrorCount
Definition: drv_i2c.c:90
volatile uint8_t * status
Definition: drv_i2c.h:50
void I2C_DeInit(I2C_TypeDef *I2Cx)
Deinitializes the I2Cx peripheral registers to their default reset values.
static void i2c_init_buffer(void)
Definition: drv_i2c.c:620
uint16_t scl
Definition: drv_i2c.c:51
void I2C2_EV_IRQHandler(void)
Definition: drv_i2c.c:84
uint16_t pin
Definition: drv_gpio.h:62
bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
Definition: drv_i2c.c:152
General Purpose I/O.
Definition: stm32f4xx.h:1281
void I2C_StructInit(I2C_InitTypeDef *I2C_InitStruct)
Fills each I2C_InitStruct member with its default value.
uint16_t sda
Definition: drv_i2c.c:52
static volatile uint8_t bytes
Definition: drv_i2c.c:97
static volatile uint8_t addr
Definition: drv_i2c.c:95
void I2C_Cmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C peripheral.
static volatile uint8_t reg
Definition: drv_i2c.c:96
uint32_t peripheral
Definition: drv_i2c.c:55
static volatile uint8_t i2c_buffer_tail
Definition: drv_i2c.c:43
Definition: drv_i2c.h:43
static volatile uint8_t * read_p
Definition: drv_i2c.c:101
void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef *I2C_InitStruct)
Initializes the I2Cx peripheral according to the specified parameters in the I2C_InitStruct.
uint8_t length
Definition: drv_i2c.h:48
void i2c_queue_job(i2cJobType_t type, uint8_t addr_, uint8_t reg_, uint8_t *data, uint8_t length, volatile uint8_t *status_, void(*CB)(uint8_t))
Definition: drv_i2c.c:579
i2cJobType_t type
Definition: drv_i2c.h:44
static void i2c_er_handler(void)
Definition: drv_i2c.c:262
uint32_t I2C_ClockSpeed
Definition: stm32f4xx_i2c.h:56
uint8_t addr
Definition: drv_i2c.h:45
static void i2cUnstick(void)
Definition: drv_i2c.c:472
__IO uint16_t SR1
Definition: stm32f4xx.h:1332
#define digitalLo(p, i)
Definition: drv_gpio.h:68
I2C Init structure definition.
Definition: stm32f4xx_i2c.h:54
#define I2C_IT_BUF
Definition: drv_i2c.h:31
struct i2cJob * next_job
Definition: drv_i2c.h:49
#define NULL
Definition: usbd_def.h:50
#define I2C2
Definition: stm32f4xx.h:2061
static volatile uint8_t i2c_buffer_count
Definition: drv_i2c.c:44
static void i2c_ev_handler(void)
Definition: drv_i2c.c:304
Inter-integrated Circuit Interface.
Definition: stm32f4xx.h:1320
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
Definition: drv_i2c.c:113
#define I2C_Direction_Receiver
__IO uint16_t CR1
Definition: stm32f4xx.h:1322
struct i2cDevice_t i2cDevice_t
#define I2C_DEFAULT_TIMEOUT
Definition: drv_i2c.c:89
#define I2C1
Definition: stm32f4xx.h:2060
I2CDevice
Definition: drv_i2c.h:24
Definition: drv_gpio.h:49
i2cJobType_t
Definition: drv_i2c.h:30
uint16_t I2C_DutyCycle
Definition: stm32f4xx_i2c.h:62
void I2C_ITConfig(I2C_TypeDef *I2Cx, uint16_t I2C_IT, FunctionalState NewState)
Enables or disables the specified I2C interrupts.
uint16_t I2C_Mode
Definition: stm32f4xx_i2c.h:59
GPIO_TypeDef * gpio
Definition: drv_i2c.c:50
uint8_t reg
Definition: drv_i2c.h:46
static volatile uint8_t reading
Definition: drv_i2c.c:99
#define I2C_IT_EVT
#define digitalHi(p, i)
Definition: drv_gpio.h:67
void I2C1_EV_IRQHandler(void)
Definition: drv_i2c.c:74


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Thu Apr 15 2021 05:07:46