i2c.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2017, James Jackson
3  *
4  * All rights reserved.
5  *
6  * Redistribution and use in source and binary forms, with or without
7  * modification, are permitted provided that the following conditions are met:
8  *
9  * * Redistributions of source code must retain the above copyright notice, this
10  * list of conditions and the following disclaimer.
11  *
12  * * Redistributions in binary form must reproduce the above copyright notice,
13  * this list of conditions and the following disclaimer in the documentation
14  * and/or other materials provided with the distribution.
15  *
16  * * Neither the name of the copyright holder nor the names of its
17  * contributors may be used to endorse or promote products derived from
18  * this software without specific prior written permission.
19  *
20  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
30  */
31 
32 #include "i2c.h"
33 
34 #define while_check(cond, result) \
35 {\
36  int32_t timeout_var = 200; \
37  while ((cond) && timeout_var) \
38  timeout_var--; \
39  if (!timeout_var) \
40 { \
41  handle_hardware_failure();\
42  result = RESULT_ERROR; \
43  }\
44  }
45 
46 #define log_line event_history_.add_event(__LINE__)
47 
48 //global i2c ptrs used by the event interrupts
52 
54 {
55  c_ = c;
56 
57  if (c->dev == I2C1)
58  I2C1_Ptr = this;
59 
60  if (c->dev == I2C2)
61  I2C2_Ptr = this;
62 
63  if (c->dev == I2C3)
64  I2C3_Ptr = this;
65 
70 
71  //initialize the i2c itself
72  I2C_DeInit(c->dev);
73 
74  I2C_InitTypeDef I2C_InitStructure;
75  I2C_StructInit(&I2C_InitStructure);
76  I2C_InitStructure.I2C_ClockSpeed = c->I2C_ClockSpeed;
77  I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
78  I2C_InitStructure.I2C_DutyCycle = I2C_DutyCycle_2;
79  I2C_InitStructure.I2C_OwnAddress1 = 0; //The first device address
80  I2C_InitStructure.I2C_Ack = I2C_Ack_Disable;
82  I2C_Init(c->dev, &I2C_InitStructure);
83 
84  // Interrupts
85  NVIC_InitTypeDef NVIC_InitStructure;
86  NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = 0x01;
87  NVIC_InitStructure.NVIC_IRQChannelSubPriority = 0x00;
88  NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
89  NVIC_InitStructure.NVIC_IRQChannel = c->I2C_EV_IRQn;
90  NVIC_Init(&NVIC_InitStructure);
91 
92  // I2C Event Interrupt
93  NVIC_InitStructure.NVIC_IRQChannel = c->I2C_ER_IRQn;
94  NVIC_Init(&NVIC_InitStructure);
95 
96  // DMA Event Interrupt
97  NVIC_InitStructure.NVIC_IRQChannel = c->DMA_IRQn;
98  NVIC_Init(&NVIC_InitStructure);
99 
111 
112  DMA_InitStructure_.DMA_PeripheralBaseAddr = reinterpret_cast<uint32_t>(&(c->dev->DR));
117 
119  I2C_Cmd(c->dev, ENABLE);
120 
121  unstick(); //unsti1ck will properly initialize pins
122  log_line;
123 }
124 
126 {
127  I2C_Cmd(c_->dev, DISABLE);
128 
130 
131  // Turn off the interrupts
133 
134  //reset errors
136 
139 
142 
143  delayMicroseconds(100);
144 
145  // clock out some bits
146  for (int i = 0; i < 16; ++i)
147  {
149  scl_.toggle();
150  }
152 
153  // send a start condition
158 
159  // then a stop
164 
165  // turn things back on
168  I2C_Cmd(c_->dev, ENABLE);
169 
171  write(0, 0, 0);
172 
174  log_line;
175 
176 }
177 
178 
179 int8_t I2C::read(uint8_t addr, uint8_t reg, uint8_t num_bytes, uint8_t *data, void(*callback)(uint8_t), bool blocking)
180 {
181  if (check_busy())
182  return RESULT_BUSY;
183  log_line;
184 
185  // configure the job
187  addr_ = addr << 1;
188  cb_ = callback;
189  reg_ = reg;
190  subaddress_sent_ = (reg_ == 0xFF);
191  len_ = num_bytes;
192  done_ = false;
194 
196  DMA_InitStructure_.DMA_BufferSize = static_cast<uint16_t>(len_);
197  DMA_InitStructure_.DMA_Memory0BaseAddr = reinterpret_cast<uint32_t>(data);
199 
200  I2C_Cmd(c_->dev, ENABLE);
201 
203 
204  // If we don't need to send the subaddress, then go ahead and spool up the DMA NACK
205  if (subaddress_sent_)
206  {
209  }
211 
213 
215  if (blocking)
216  {
217  log_line;
218  while (check_busy());
219  }
220  log_line;
222 
223  return return_code_;
224 }
225 
226 
228 {
230  if (cb_)
231  cb_(return_code_);
232  log_line;
233 }
234 
235 
236 // blocking, single register read (for configuring devices)
237 int8_t I2C::read(uint8_t addr, uint8_t reg, uint8_t *data)
238 {
239  if (check_busy())
240  return RESULT_BUSY;
241  log_line;
243 
244  // Turn off interrupts while blocking
246 
248 
249  I2C_Cmd(c_->dev, ENABLE);
250  if (reg != 0xFF)
251  {
252  log_line;
256  uint32_t timeout = 500;
257  while (!I2C_CheckEvent(c_->dev, I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) && --timeout != 0);
258  if (timeout != 0)
259  {
261  I2C_Cmd(c_->dev, DISABLE);
262  }
263  else
264  {
266  log_line;
267  return return_code_;
268  }
269  I2C_Cmd(c_->dev, ENABLE);
270  I2C_SendData(c_->dev, reg);
272  }
273 
274  // Read the byte
278  I2C_Cmd(c_->dev, ENABLE);
280  uint32_t timeout = 500;
281  while (!I2C_CheckEvent(c_->dev, I2C_EVENT_MASTER_BYTE_RECEIVED) && --timeout != 0);
282  if (timeout != 0)
283  {
284  *data = I2C_ReceiveData(c_->dev);
285  }
286  else
287  {
289  }
291  I2C_Cmd(c_->dev, DISABLE);
292  log_line;
293 
294  return return_code_;
295 }
296 
297 // asynchronous write, for commanding adc conversions
298 int8_t I2C::write(uint8_t addr, uint8_t reg, uint8_t data, void(*callback)(uint8_t), bool blocking)
299 {
300  if (check_busy())
301  return RESULT_BUSY;
302 
303  log_line;
305  addr_ = addr << 1;
306  cb_ = callback;
307  reg_ = reg;
308  subaddress_sent_ = (reg_ == 0xFF);
309  len_ = 1;
310  done_ = false;
311  data_ = data;
313 
314  I2C_Cmd(c_->dev, ENABLE);
315 
316 
318 
320 
322 
324  if (blocking)
325  {
326  log_line;
327  while (check_busy());
328  }
329  log_line;
330  return return_code_;
331 }
332 
333 // blocking, single register write (for configuring devices)
334 int8_t I2C::write(uint8_t addr, uint8_t reg, uint8_t data)
335 {
336  if (check_busy())
337  return RESULT_BUSY;
338 
339  log_line;
342 
343  // Turn off interrupts for blocking write
345  I2C_Cmd(c_->dev, ENABLE);
346 
347  // start the transfer
351  uint32_t timeout = 500;
353  && timeout--);
354 
355  // No acknowledgement or timeout
356  if (I2C_GetLastEvent(c_->dev) & AF || timeout == 0)
357  {
358  log_line;
360  I2C_Cmd(c_->dev, DISABLE);
361  return RESULT_ERROR;
362  }
363 
364  // Send the register
365  if (reg != 0xFF)
366  {
367  log_line;
368  I2C_SendData(c_->dev, reg);
370  }
371 
372  // Write the byte with a NACK
374  I2C_SendData(c_->dev, data);
377  I2C_Cmd(c_->dev, DISABLE);
378  log_line;
380  return return_code_;
381 
382 }
383 
384 // if for some reason, a step in an I2C read or write fails, call this
386 {
387  error_count_++;
389  log_line;
390 // unstick(); //unstick and reinitialize the hardware
391 }
392 
393 
394 // This is the I2C_IT_ERR handler
396 {
397  log_line;
398  I2C_Cmd(c_->dev, DISABLE);
401 
402  // Turn off the interrupts
404 
405  //reset errors
408  log_line;
410 }
411 
412 // This is the I2C_IT_EV handler
414 {
415  uint32_t last_event = I2C_GetLastEvent(c_->dev);
417  // We just sent a byte
418  if ((last_event & I2C_EVENT_MASTER_BYTE_TRANSMITTED) == I2C_EVENT_MASTER_BYTE_TRANSMITTED)
419  {
421  // If we are reading, then we just sent a subaddress and need to send
422  // a repeated start, and enable the DMA NACK
423  if (current_status_ == READING)
424  {
425  log_line;
429  }
430  // We are in write mode and are done, need to clean up
431  else
432  {
433  log_line;
437  }
438  }
439 
440  // We just sent the address in write mode
441  else if ((last_event & I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED) == I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED)
442  {
444  // We need to send the subaddress
445  if (!subaddress_sent_)
446  {
447  log_line;
448  I2C_SendData(c_->dev, reg_);
449  subaddress_sent_ = true;
450  if (current_status_ == WRITING)
451  {
452  log_line;
454  done_ = true;
455  }
456  }
457  // We need to send our data (no subaddress)
458  else
459  {
460  log_line;
462  done_ = true;
463  }
464  }
465 
466  // We are in receiving mode, preparing to receive the big DMA dump
467  else if ((last_event & I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED) == I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED)
468  {
470  log_line;
471  // I2C_ITConfig(c_->dev, I2C_IT_EVT, DISABLE);
473  I2C_DMACmd(c_->dev, ENABLE);
476  }
477 
478  // Start just sent
479  else if ((last_event & I2C_EVENT_MASTER_MODE_SELECT) == I2C_EVENT_MASTER_MODE_SELECT)
480  {
482  // we either don't need to send, or already sent the subaddress
484  {
485  log_line;
486  // Set up a receive
488  }
489  // We need to either send the subaddress or our datas
490  else
491  {
492  log_line;
493  // Set up a write
495  }
496  }
497 
498  // Sometimes we just get this over and over and over again
499  else if (last_event == SB)
500  {
501  // SB is cleared by clearing and resetting PE
502  I2C_Cmd(c_->dev, DISABLE);
503  I2C_Cmd(c_->dev, ENABLE);
504  error_count_++;
505  }
506 }
507 
508 
509 // This checks to make sure that the I2C device isn't currently handling an i2c job, and if
510 // it is, that it hasn't stalled out
512 {
513  if (current_status_ == IDLE)
514  return false;
515  else
516  {
517  // If we haven't seen anything in a long while, then restart the device
518  if (micros() > last_event_us_ + 2000)
519  {
520  error_count_++;
521  // Send a stop condition
525 
526  // Force reset of the bus
527  // This is really slow, but it seems to be the only
528  // way to regain a connection if bad things happen
529  if (return_code_ == RESULT_ERROR)
530  {
531  I2C_Cmd(c_->dev, DISABLE);
534 
535  // Write Pins low
539 
540  // Send a stop
545 
546  // turn things back on
549  I2C_Cmd(c_->dev, ENABLE);
550 
552  }
553  log_line;
554  return false;
555  }
556  else
557  {
558  return true;
559  }
560  }
561 }
562 
563 extern "C"
564 {
565 
566 // C-based IRQ functions (defined in the startup script)
568  {
569 
571  {
572  /* Clear transmission complete flag */
574 
576  /* Send I2C1 STOP Condition */
578  /* Disable DMA channel*/
580 
581  /* Turn off I2C interrupts since we are done with the transfer */
583 
584  I2C2_Ptr->transfer_complete_cb(); // TODO make this configurable
585  }
586  }
587 
589  {
591  {
592  /* Clear transmission complete flag */
594 
596  /* Send I2C1 STOP Condition */
598  /* Disable DMA channel*/
600  /* Turn off I2C interrupts, because we are done with the transfer */
602 
603  I2C1_Ptr->transfer_complete_cb(); // TODO make this configurable
604  }
605  }
606 
608  {
609  I2C1_Ptr->handle_error();
610  }
611 
613  {
614  I2C1_Ptr->handle_event();
615  }
616 
618  {
619  I2C2_Ptr->handle_error();
620  }
621 
623  {
624  I2C2_Ptr->handle_event();
625  }
626 
628  {
629  I2C3_Ptr->handle_error();
630  }
631 
633  {
634  I2C3_Ptr->handle_event();
635  }
636 
637 }
#define DMA_MemoryInc_Enable
uint32_t DMA_MemoryInc
Definition: stm32f4xx_dma.h:76
IRQn_Type DMA_IRQn
Definition: system.h:89
void I2C_DMALastTransferCmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Specifies that the next DMA transfer is the last one.
void transfer_complete_cb()
Definition: i2c.cpp:227
uint16_t I2C_Ack
Definition: stm32f4xx_i2c.h:68
I2C * I2C2_Ptr
Definition: i2c.cpp:50
uint32_t DMA_Channel
Definition: stm32f4xx_dma.h:56
void GPIO_PinAFConfig(GPIO_TypeDef *GPIOx, uint16_t GPIO_PinSource, uint8_t GPIO_AF)
Changes the mapping of the specified pin.
void(* cb_)(uint8_t)
Definition: i2c.h:133
#define I2C_SR1_BERR
Definition: stm32f4xx.h:6851
uint32_t I2C_ClockSpeed
Definition: system.h:78
void NVIC_Init(NVIC_InitTypeDef *NVIC_InitStruct)
Initializes the NVIC peripheral according to the specified parameters in the NVIC_InitStruct.
void toggle(void)
Definition: gpio.cpp:52
#define DMA_MemoryDataSize_Byte
void I2C_ClearFlag(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
Clears the I2Cx&#39;s pending flags.
uint16_t I2C_AcknowledgedAddress
Definition: stm32f4xx_i2c.h:71
void I2C1_ER_IRQHandler(void)
Definition: i2c.cpp:607
void I2C3_EV_IRQHandler(void)
Definition: i2c.cpp:632
#define I2C_DutyCycle_2
#define I2C_IT_ERR
#define I2C_EVENT_MASTER_MODE_SELECT
Communication start.
uint16_t error_count_
Definition: i2c.h:86
void I2C_AcknowledgeConfig(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C acknowledge feature.
void set_mode(gpio_mode_t mode)
Definition: gpio.cpp:82
#define I2C_Mode_I2C
uint32_t DMA_MemoryBurst
#define I2C_SR1_AF
Definition: stm32f4xx.h:6853
void DMA_DeInit(DMA_Stream_TypeDef *DMAy_Streamx)
Deinitialize the DMAy Streamx registers to their default reset values.
#define I2C_SR1_ARLO
Definition: stm32f4xx.h:6852
void I2C_GenerateSTART(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication START condition.
void DMA1_Stream0_IRQHandler(void)
Definition: i2c.cpp:588
#define DMA_FLAG_TCIF2
#define I2C_EVENT_MASTER_BYTE_TRANSMITTED
#define DMA_PeripheralInc_Disable
void delayMicroseconds(uint32_t us)
Definition: system.c:91
void I2C_Send7bitAddress(I2C_TypeDef *I2Cx, uint8_t Address, uint8_t I2C_Direction)
Transmits the address byte to select the slave device.
uint8_t I2C_ReceiveData(I2C_TypeDef *I2Cx)
Returns the most recent received data by the I2Cx peripheral.
I2C * I2C1_Ptr
Definition: i2c.cpp:49
Debug_History interrupt_history_
Definition: i2c.h:129
uint32_t DMA_MemoryDataSize
Definition: stm32f4xx_dma.h:82
void init(const i2c_hardware_struct_t *c)
Definition: i2c.cpp:53
void add_event(uint32_t event)
Definition: i2c.h:118
FlagStatus DMA_GetFlagStatus(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Checks whether the specified DMAy Streamx flag is set or not.
#define DMA_Priority_High
__IO uint16_t DR
Definition: stm32f4xx.h:1330
uint16_t I2C_OwnAddress1
Definition: stm32f4xx_i2c.h:65
#define I2C3
Definition: stm32f4xx.h:2062
void DMA_Init(DMA_Stream_TypeDef *DMAy_Streamx, DMA_InitTypeDef *DMA_InitStruct)
Initializes the DMAy Streamx according to the specified parameters in the DMA_InitStruct structure...
void I2C_GenerateSTOP(I2C_TypeDef *I2Cx, FunctionalState NewState)
Generates I2Cx communication STOP condition.
uint32_t DMA_DIR
Definition: stm32f4xx_dma.h:65
void I2C2_EV_IRQHandler(void)
Definition: i2c.cpp:622
uint32_t DMA_PeripheralInc
Definition: stm32f4xx_dma.h:73
void DMA1_Stream2_IRQHandler(void)
Definition: i2c.cpp:567
DMA_InitTypeDef DMA_InitStructure_
Definition: i2c.h:99
volatile uint8_t data_
Definition: i2c.h:97
volatile uint64_t micros(void)
Definition: system.c:44
volatile current_status_t current_status_
Definition: i2c.h:89
void DMA_ITConfig(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_IT, FunctionalState NewState)
Enables or disables the specified DMAy Streamx interrupts.
#define I2C_FLAG_BUSY
#define I2C_Direction_Transmitter
uint32_t DMA_PeripheralDataSize
Definition: stm32f4xx_dma.h:79
uint16_t SCL_Pin
Definition: system.h:84
__IO uint16_t SR2
Definition: stm32f4xx.h:1334
#define I2C_EVENT_MASTER_TRANSMITTER_MODE_SELECTED
Address Acknowledge.
#define I2C_AcknowledgedAddress_7bit
#define DMA_FIFOMode_Enable
#define DMA_FIFOThreshold_Full
Definition: i2c.h:47
void I2C_DeInit(I2C_TypeDef *I2Cx)
Deinitializes the I2Cx peripheral registers to their default reset values.
void init(GPIO_TypeDef *BasePort, uint16_t pin, gpio_mode_t mode)
Definition: gpio.cpp:34
GPIO sda_
Definition: i2c.h:84
I2C_TypeDef * dev
Definition: system.h:77
void I2C2_ER_IRQHandler(void)
Definition: i2c.cpp:617
#define DMA1_Stream0
Definition: stm32f4xx.h:2125
#define DMA_FLAG_TCIF0
void I2C_StructInit(I2C_InitTypeDef *I2C_InitStruct)
Fills each I2C_InitStruct member with its default value.
uint32_t DMA_PeripheralBurst
void I2C1_EV_IRQHandler(void)
Definition: i2c.cpp:612
static volatile uint8_t addr
Definition: drv_i2c.c:95
void handle_hardware_failure()
Definition: i2c.cpp:385
void DMA_Cmd(DMA_Stream_TypeDef *DMAy_Streamx, FunctionalState NewState)
Enables or disables the specified DMAy Streamx.
uint32_t DMA_PeripheralBaseAddr
Definition: stm32f4xx_dma.h:59
uint32_t DMA_Memory0BaseAddr
Definition: stm32f4xx_dma.h:61
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
IRQn_Type I2C_EV_IRQn
Definition: system.h:79
bool done_
Definition: i2c.h:92
#define DMA_MemoryBurst_Single
uint32_t DMA_FIFOThreshold
Definition: stm32f4xx_dma.h:98
void I2C_Init(I2C_TypeDef *I2Cx, I2C_InitTypeDef *I2C_InitStruct)
Initializes the I2Cx peripheral according to the specified parameters in the I2C_InitStruct.
Definition: i2c.h:57
uint32_t I2C_ClockSpeed
Definition: stm32f4xx_i2c.h:56
void unstick()
Definition: i2c.cpp:125
#define DMA_Mode_Normal
#define DMA1_Stream2
Definition: stm32f4xx.h:2127
void write(gpio_write_t state)
Definition: gpio.cpp:41
bool check_busy()
Definition: i2c.cpp:511
void I2C3_ER_IRQHandler(void)
Definition: i2c.cpp:627
uint16_t SDA_Pin
Definition: system.h:86
IRQn_Type I2C_ER_IRQn
Definition: system.h:80
__IO uint16_t SR1
Definition: stm32f4xx.h:1332
#define I2C_EVENT_MASTER_RECEIVER_MODE_SELECTED
uint32_t DMA_Channel
Definition: system.h:88
uint32_t DMA_FIFOMode
Definition: stm32f4xx_dma.h:93
I2C Init structure definition.
Definition: stm32f4xx_i2c.h:54
Definition: i2c.h:78
#define while_check(cond, result)
Definition: i2c.cpp:34
#define DMA_PeripheralDataSize_Byte
volatile uint8_t addr_
Definition: i2c.h:94
int8_t write(uint8_t addr, uint8_t reg, uint8_t data, void(*callback)(uint8_t), bool blocking=false)
Definition: i2c.cpp:298
#define log_line
Definition: i2c.cpp:46
Definition: i2c.h:40
void handle_event()
Definition: i2c.cpp:413
Definition: gpio.h:44
uint32_t DMA_Mode
Definition: stm32f4xx_dma.h:85
volatile uint8_t len_
Definition: i2c.h:96
#define I2C2
Definition: stm32f4xx.h:2061
DMA_Stream_TypeDef * DMA_Stream
Definition: system.h:87
volatile uint8_t return_code_
Definition: i2c.h:90
I2C * I2C3_Ptr
Definition: i2c.cpp:51
FlagStatus I2C_GetFlagStatus(I2C_TypeDef *I2Cx, uint32_t I2C_FLAG)
Checks whether the specified I2C flag is set or not.
#define DMA_DIR_PeripheralToMemory
GPIO_TypeDef * GPIO
Definition: system.h:81
const i2c_hardware_struct_t * c_
Definition: i2c.h:101
int8_t read(uint8_t addr, uint8_t reg, uint8_t num_bytes, uint8_t *data, void(*callback)(uint8_t)=nullptr, bool blocking=false)
Definition: i2c.cpp:179
volatile uint8_t reg_
Definition: i2c.h:95
uint32_t DMA_BufferSize
Definition: stm32f4xx_dma.h:69
void handle_error()
Definition: i2c.cpp:395
Definition: i2c.h:64
uint32_t DMA_Priority
Definition: stm32f4xx_dma.h:90
void I2C_DMACmd(I2C_TypeDef *I2Cx, FunctionalState NewState)
Enables or disables the specified I2C DMA requests.
#define I2C_Direction_Receiver
bool subaddress_sent_
Definition: i2c.h:91
GPIO scl_
Definition: i2c.h:83
#define I2C1
Definition: stm32f4xx.h:2060
uint32_t I2C_GetLastEvent(I2C_TypeDef *I2Cx)
Returns the last I2Cx Event.
void I2C_SendData(I2C_TypeDef *I2Cx, uint8_t Data)
Sends a data byte through the I2Cx peripheral.
void DMA_ClearFlag(DMA_Stream_TypeDef *DMAy_Streamx, uint32_t DMA_FLAG)
Clears the DMAy Streamx&#39;s pending flags.
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.
uint64_t last_event_us_
Definition: i2c.h:131
uint16_t I2C_Mode
Definition: stm32f4xx_i2c.h:59
uint8_t SCL_PinSource
Definition: system.h:83
uint8_t SDA_PinSource
Definition: system.h:85
void DMA_SetCurrDataCounter(DMA_Stream_TypeDef *DMAy_Streamx, uint16_t Counter)
Writes the number of data units to be transferred on the DMAy Streamx.
#define DMA_IT_TC
#define I2C_Ack_Disable
ErrorStatus I2C_CheckEvent(I2C_TypeDef *I2Cx, uint32_t I2C_EVENT)
Checks whether the last I2Cx Event is equal to the one passed as parameter.
#define I2C_SR1_OVR
Definition: stm32f4xx.h:6854
#define I2C_IT_EVT
#define DMA_PeripheralBurst_Single
#define I2C_EVENT_MASTER_BYTE_RECEIVED
Communication events.


rosflight_firmware
Author(s): Daniel Koch , James Jackson
autogenerated on Wed Jul 3 2019 19:59:24