2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
28 #if defined(USE_I2C) && !defined(SOFT_I2C)
30 #include "drivers/io.h"
31 #include "drivers/time.h"
32 #include "drivers/nvic.h"
33 #include "drivers/rcc.h"
35 #include "drivers/bus_i2c.h"
36 #include "drivers/bus_i2c_impl.h"
37 #include "drivers/bus_i2c_utils.h"
39 static void i2c_er_handler(I2CDevice device
);
40 static void i2c_ev_handler(I2CDevice device
);
43 #define IOCFG_I2C_PU IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
44 #define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
46 #define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
49 const i2cHardware_t i2cHardware
[I2CDEV_COUNT
] = {
50 #ifdef USE_I2C_DEVICE_1
55 I2CPINDEF(PB6
, GPIO_AF_I2C1
),
56 I2CPINDEF(PB8
, GPIO_AF_I2C1
),
59 I2CPINDEF(PB7
, GPIO_AF_I2C1
),
60 I2CPINDEF(PB9
, GPIO_AF_I2C1
),
62 .rcc
= RCC_APB1(I2C1
),
63 .ev_irq
= I2C1_EV_IRQn
,
64 .er_irq
= I2C1_ER_IRQn
,
67 #ifdef USE_I2C_DEVICE_2
72 I2CPINDEF(PB10
, GPIO_AF_I2C2
),
73 I2CPINDEF(PF1
, GPIO_AF_I2C2
),
76 #if defined(STM32F446xx)
77 I2CPINDEF(PC12
, GPIO_AF_I2C2
),
79 I2CPINDEF(PB11
, GPIO_AF_I2C2
),
81 I2CPINDEF(PF0
, GPIO_AF_I2C2
),
83 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
84 // STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG
85 I2CPINDEF(PB3
, GPIO_AF9_I2C2
),
86 I2CPINDEF(PB9
, GPIO_AF9_I2C2
),
89 .rcc
= RCC_APB1(I2C2
),
90 .ev_irq
= I2C2_EV_IRQn
,
91 .er_irq
= I2C2_ER_IRQn
,
94 #ifdef USE_I2C_DEVICE_3
99 I2CPINDEF(PA8
, GPIO_AF_I2C3
),
102 I2CPINDEF(PC9
, GPIO_AF_I2C3
),
104 #if defined(STM32F40_41xxx) || defined(STM32F411xE)
105 // STM32F401xx/STM32F410xx/STM32F411xE/STM32F412xG
106 I2CPINDEF(PB4
, GPIO_AF9_I2C3
),
107 I2CPINDEF(PB8
, GPIO_AF9_I2C3
),
110 .rcc
= RCC_APB1(I2C3
),
111 .ev_irq
= I2C3_EV_IRQn
,
112 .er_irq
= I2C3_ER_IRQn
,
117 i2cDevice_t i2cDevice
[I2CDEV_COUNT
];
119 static volatile uint16_t i2cErrorCount
= 0;
121 void I2C1_ER_IRQHandler(void)
123 i2c_er_handler(I2CDEV_1
);
126 void I2C1_EV_IRQHandler(void)
128 i2c_ev_handler(I2CDEV_1
);
131 void I2C2_ER_IRQHandler(void)
133 i2c_er_handler(I2CDEV_2
);
136 void I2C2_EV_IRQHandler(void)
138 i2c_ev_handler(I2CDEV_2
);
142 void I2C3_ER_IRQHandler(void)
144 i2c_er_handler(I2CDEV_3
);
147 void I2C3_EV_IRQHandler(void)
149 i2c_ev_handler(I2CDEV_3
);
153 static bool i2cHandleHardwareFailure(I2CDevice device
)
156 // reinit peripheral + clock out garbage
161 bool i2cWriteBuffer(I2CDevice device
, uint8_t addr_
, uint8_t reg_
, uint8_t len_
, uint8_t *data
)
163 if (device
== I2CINVALID
|| device
>= I2CDEV_COUNT
) {
167 I2C_TypeDef
*I2Cx
= i2cDevice
[device
].reg
;
173 i2cState_t
*state
= &i2cDevice
[device
].state
;
178 timeUs_t timeoutStartUs
= microsISR();
180 state
->addr
= addr_
<< 1;
184 state
->write_p
= data
;
185 state
->read_p
= data
;
188 state
->error
= false;
190 if (!(I2Cx
->CR2
& I2C_IT_EVT
)) { // if we are restarting the driver
191 if (!(I2Cx
->CR1
& I2C_CR1_START
)) { // ensure sending a start
192 while (I2Cx
->CR1
& I2C_CR1_STOP
) { // wait for any stop to finish sending
193 if (cmpTimeUs(microsISR(), timeoutStartUs
) >= I2C_TIMEOUT_US
) {
194 return i2cHandleHardwareFailure(device
);
197 I2C_GenerateSTART(I2Cx
, ENABLE
); // send the start for the new job
199 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, ENABLE
); // allow the interrupts to fire off again
205 bool i2cBusy(I2CDevice device
, bool *error
)
207 i2cState_t
*state
= &i2cDevice
[device
].state
;
210 *error
= state
->error
;
215 static bool i2cWait(I2CDevice device
)
217 i2cState_t
*state
= &i2cDevice
[device
].state
;
218 timeUs_t timeoutStartUs
= microsISR();
220 while (state
->busy
) {
221 if (cmpTimeUs(microsISR(), timeoutStartUs
) >= I2C_TIMEOUT_US
) {
222 return i2cHandleHardwareFailure(device
) && i2cWait(device
);
226 return !(state
->error
);
229 bool i2cWrite(I2CDevice device
, uint8_t addr_
, uint8_t reg_
, uint8_t data
)
231 return i2cWriteBuffer(device
, addr_
, reg_
, 1, &data
) && i2cWait(device
);
234 bool i2cReadBuffer(I2CDevice device
, uint8_t addr_
, uint8_t reg_
, uint8_t len
, uint8_t* buf
)
236 if (device
== I2CINVALID
|| device
>= I2CDEV_COUNT
) {
240 I2C_TypeDef
*I2Cx
= i2cDevice
[device
].reg
;
245 i2cState_t
*state
= &i2cDevice
[device
].state
;
250 timeUs_t timeoutStartUs
= microsISR();
252 state
->addr
= addr_
<< 1;
257 state
->write_p
= buf
;
260 state
->error
= false;
262 if (!(I2Cx
->CR2
& I2C_IT_EVT
)) { // if we are restarting the driver
263 if (!(I2Cx
->CR1
& I2C_CR1_START
)) { // ensure sending a start
264 while (I2Cx
->CR1
& I2C_CR1_STOP
) { // wait for any stop to finish sending
265 if (cmpTimeUs(microsISR(), timeoutStartUs
) >= I2C_TIMEOUT_US
) {
266 return i2cHandleHardwareFailure(device
);
269 I2C_GenerateSTART(I2Cx
, ENABLE
); // send the start for the new job
271 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, ENABLE
); // allow the interrupts to fire off again
277 bool i2cRead(I2CDevice device
, uint8_t addr_
, uint8_t reg_
, uint8_t len
, uint8_t* buf
)
279 return i2cReadBuffer(device
, addr_
, reg_
, len
, buf
) && i2cWait(device
);
282 static void i2c_er_handler(I2CDevice device
)
284 I2C_TypeDef
*I2Cx
= i2cDevice
[device
].hardware
->reg
;
286 i2cState_t
*state
= &i2cDevice
[device
].state
;
288 // Read the I2C1 status register
289 volatile uint32_t SR1Register
= I2Cx
->SR1
;
291 if (SR1Register
& (I2C_SR1_BERR
| I2C_SR1_ARLO
| I2C_SR1_AF
| I2C_SR1_OVR
)) // an error
294 // If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
295 if (SR1Register
& (I2C_SR1_BERR
| I2C_SR1_ARLO
| I2C_SR1_AF
)) {
296 (void)I2Cx
->SR2
; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
297 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
298 if (!(SR1Register
& I2C_SR1_ARLO
) && !(I2Cx
->CR1
& I2C_CR1_STOP
)) { // if we dont have an ARLO error, ensure sending of a stop
299 if (I2Cx
->CR1
& I2C_CR1_START
) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
300 while (I2Cx
->CR1
& I2C_CR1_START
) {; } // wait for any start to finish sending
301 I2C_GenerateSTOP(I2Cx
, ENABLE
); // send stop to finalise bus transaction
302 while (I2Cx
->CR1
& I2C_CR1_STOP
) {; } // wait for stop to finish sending
303 i2cInit(device
); // reset and configure the hardware
306 I2C_GenerateSTOP(I2Cx
, ENABLE
); // stop to free up the bus
307 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, DISABLE
); // Disable EVT and ERR interrupts while bus inactive
311 I2Cx
->SR1
&= ~(I2C_SR1_BERR
| I2C_SR1_ARLO
| I2C_SR1_AF
| I2C_SR1_OVR
); // reset all the error bits to clear the interrupt
315 void i2c_ev_handler(I2CDevice device
)
317 I2C_TypeDef
*I2Cx
= i2cDevice
[device
].hardware
->reg
;
319 i2cState_t
*state
= &i2cDevice
[device
].state
;
321 static uint8_t subaddress_sent
, final_stop
; // flag to indicate if subaddess sent, flag to indicate final bus condition
322 static int8_t index
; // index is signed -1 == send the subaddress
323 uint8_t SReg_1
= I2Cx
->SR1
; // read the status register here
325 if (SReg_1
& I2C_SR1_SB
) { // we just sent a start - EV5 in ref manual
326 I2Cx
->CR1
&= ~I2C_CR1_POS
; // reset the POS bit so ACK/NACK applied to the current byte
327 I2C_AcknowledgeConfig(I2Cx
, ENABLE
); // make sure ACK is on
328 index
= 0; // reset the index
329 if (state
->reading
&& (subaddress_sent
|| 0xFF == state
->reg
)) { // we have sent the subaddr
330 subaddress_sent
= 1; // make sure this is set in case of no subaddress, so following code runs correctly
331 if (state
->bytes
== 2)
332 I2Cx
->CR1
|= I2C_CR1_POS
; // set the POS bit so NACK applied to the final byte in the two byte read
333 I2C_Send7bitAddress(I2Cx
, state
->addr
, I2C_Direction_Receiver
); // send the address and set hardware mode
335 else { // direction is Tx, or we havent sent the sub and rep start
336 I2C_Send7bitAddress(I2Cx
, state
->addr
, I2C_Direction_Transmitter
); // send the address and set hardware mode
337 if (state
->reg
!= 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
338 index
= -1; // send a subaddress
341 else if (SReg_1
& I2C_SR1_ADDR
) { // we just sent the address - EV6 in ref manual
342 // Read SR1,2 to clear ADDR
343 __DMB(); // memory fence to control hardware
344 if (state
->bytes
== 1 && state
->reading
&& subaddress_sent
) { // we are receiving 1 byte - EV6_3
345 I2C_AcknowledgeConfig(I2Cx
, DISABLE
); // turn off ACK
347 (void)I2Cx
->SR2
; // clear ADDR after ACK is turned off
348 I2C_GenerateSTOP(I2Cx
, ENABLE
); // program the stop
350 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, ENABLE
); // allow us to have an EV7
352 else { // EV6 and EV6_1
353 (void)I2Cx
->SR2
; // clear the ADDR here
355 if (state
->bytes
== 2 && state
->reading
&& subaddress_sent
) { // rx 2 bytes - EV6_1
356 I2C_AcknowledgeConfig(I2Cx
, DISABLE
); // turn off ACK
357 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // disable TXE to allow the buffer to fill
359 else if (state
->bytes
== 3 && state
->reading
&& subaddress_sent
) // rx 3 bytes
360 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // make sure RXNE disabled so we get a BTF in two bytes time
361 else // receiving greater than three bytes, sending subaddress, or transmitting
362 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, ENABLE
);
365 else if (SReg_1
& I2C_SR1_BTF
) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
367 if (state
->reading
&& subaddress_sent
) { // EV7_2, EV7_3
368 if (state
->bytes
> 2) { // EV7_2
369 I2C_AcknowledgeConfig(I2Cx
, DISABLE
); // turn off ACK
370 state
->read_p
[index
++] = (uint8_t)I2Cx
->DR
; // read data N-2
371 I2C_GenerateSTOP(I2Cx
, ENABLE
); // program the Stop
372 final_stop
= 1; // required to fix hardware
373 state
->read_p
[index
++] = (uint8_t)I2Cx
->DR
; // read data N - 1
374 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, ENABLE
); // enable TXE to allow the final EV7
378 I2C_GenerateSTOP(I2Cx
, ENABLE
); // program the Stop
380 I2C_GenerateSTART(I2Cx
, ENABLE
); // program a rep start
381 state
->read_p
[index
++] = (uint8_t)I2Cx
->DR
; // read data N - 1
382 state
->read_p
[index
++] = (uint8_t)I2Cx
->DR
; // read data N
383 index
++; // to show job completed
386 else { // EV8_2, which may be due to a subaddress sent or a write completion
387 if (subaddress_sent
|| (state
->writing
)) {
389 I2C_GenerateSTOP(I2Cx
, ENABLE
); // program the Stop
391 I2C_GenerateSTART(I2Cx
, ENABLE
); // program a rep start
392 index
++; // to show that the job is complete
394 else { // We need to send a subaddress
395 I2C_GenerateSTART(I2Cx
, ENABLE
); // program the repeated Start
396 subaddress_sent
= 1; // this is set back to zero upon completion of the current task
399 // we must wait for the start to clear, otherwise we get constant BTF
400 while (I2Cx
->CR1
& I2C_CR1_START
) {; }
402 else if (SReg_1
& I2C_SR1_RXNE
) { // Byte received - EV7
403 state
->read_p
[index
++] = (uint8_t)I2Cx
->DR
;
404 if (state
->bytes
== (index
+ 3))
405 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // disable TXE to allow the buffer to flush so we can get an EV7_2
406 if (state
->bytes
== index
) // We have completed a final EV7
407 index
++; // to show job is complete
409 else if (SReg_1
& I2C_SR1_TXE
) { // Byte transmitted EV8 / EV8_1
410 if (index
!= -1) { // we dont have a subaddress to send
411 I2Cx
->DR
= state
->write_p
[index
++];
412 if (state
->bytes
== index
) // we have sent all the data
413 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // disable TXE to allow the buffer to flush
417 I2Cx
->DR
= state
->reg
; // send the subaddress
418 if (state
->reading
|| !(state
->bytes
)) // if receiving or sending 0 bytes, flush now
419 I2C_ITConfig(I2Cx
, I2C_IT_BUF
, DISABLE
); // disable TXE to allow the buffer to flush
422 if (index
== state
->bytes
+ 1) { // we have completed the current job
423 subaddress_sent
= 0; // reset this here
424 if (final_stop
) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
425 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, DISABLE
); // Disable EVT and ERR interrupts while bus inactive
430 void i2cInit(I2CDevice device
)
432 if (device
== I2CINVALID
)
435 i2cDevice_t
*pDev
= &i2cDevice
[device
];
436 const i2cHardware_t
*hw
= pDev
->hardware
;
437 const IO_t scl
= pDev
->scl
;
438 const IO_t sda
= pDev
->sda
;
440 if (!hw
|| IOGetOwner(scl
) || IOGetOwner(sda
)) {
444 I2C_TypeDef
*I2Cx
= hw
->reg
;
446 memset(&pDev
->state
, 0, sizeof(pDev
->state
));
448 NVIC_InitTypeDef nvic
;
449 I2C_InitTypeDef i2cInit
;
451 IOInit(scl
, OWNER_I2C_SCL
, RESOURCE_INDEX(device
));
452 IOInit(sda
, OWNER_I2C_SDA
, RESOURCE_INDEX(device
));
455 RCC_ClockCmd(hw
->rcc
, ENABLE
);
457 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, DISABLE
);
459 i2cUnstick(scl
, sda
);
463 IOConfigGPIOAF(scl
, pDev
->pullUp
? IOCFG_I2C_PU
: IOCFG_I2C
, pDev
->sclAF
);
464 IOConfigGPIOAF(sda
, pDev
->pullUp
? IOCFG_I2C_PU
: IOCFG_I2C
, pDev
->sdaAF
);
466 IOConfigGPIO(scl
, IOCFG_I2C
);
467 IOConfigGPIO(sda
, IOCFG_I2C
);
471 I2C_StructInit(&i2cInit
);
473 I2C_ITConfig(I2Cx
, I2C_IT_EVT
| I2C_IT_ERR
, DISABLE
); // Disable EVT and ERR interrupts - they are enabled by the first request
474 i2cInit
.I2C_Mode
= I2C_Mode_I2C
;
475 i2cInit
.I2C_DutyCycle
= I2C_DutyCycle_2
;
476 i2cInit
.I2C_OwnAddress1
= 0;
477 i2cInit
.I2C_Ack
= I2C_Ack_Enable
;
478 i2cInit
.I2C_AcknowledgedAddress
= I2C_AcknowledgedAddress_7bit
;
479 i2cInit
.I2C_ClockSpeed
= pDev
->clockSpeed
* 1000;
481 I2C_Cmd(I2Cx
, ENABLE
);
482 I2C_Init(I2Cx
, &i2cInit
);
484 I2C_StretchClockCmd(I2Cx
, ENABLE
);
487 nvic
.NVIC_IRQChannel
= hw
->er_irq
;
488 nvic
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER
);
489 nvic
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER
);
490 nvic
.NVIC_IRQChannelCmd
= ENABLE
;
494 nvic
.NVIC_IRQChannel
= hw
->ev_irq
;
495 nvic
.NVIC_IRQChannelPreemptionPriority
= NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV
);
496 nvic
.NVIC_IRQChannelSubPriority
= NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV
);
500 uint16_t i2cGetErrorCounter(void)
502 return i2cErrorCount
;