diff --git a/mk/source.mk b/mk/source.mk
index 6ab52f66e3..ccc7541175 100644
--- a/mk/source.mk
+++ b/mk/source.mk
@@ -19,6 +19,7 @@ COMMON_SRC = \
drivers/bus.c \
drivers/bus_i2c_config.c \
drivers/bus_i2c_busdev.c \
+ drivers/bus_i2c_utils.c \
drivers/bus_i2c_soft.c \
drivers/bus_octospi.c \
drivers/bus_quadspi.c \
diff --git a/src/main/drivers/at32/bus_i2c_atbsp_init.c b/src/main/drivers/at32/bus_i2c_atbsp_init.c
index 15786b3a5e..4934e0021b 100644
--- a/src/main/drivers/at32/bus_i2c_atbsp_init.c
+++ b/src/main/drivers/at32/bus_i2c_atbsp_init.c
@@ -27,7 +27,6 @@
#if defined(USE_I2C) && !defined(SOFT_I2C)
#include "drivers/io.h"
-#include "drivers/io_impl.h"
#include "drivers/nvic.h"
#include "drivers/time.h"
#include "drivers/rcc.h"
@@ -35,22 +34,10 @@
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
#include "drivers/bus_i2c_timing.h"
+#include "drivers/bus_i2c_utils.h"
#include "pg/pinio.h"
-// Number of bits in I2C protocol phase
-#define LEN_ADDR 7
-#define LEN_RW 1
-#define LEN_ACK 1
-
-// Clock period in us during unstick transfer
-#define UNSTICK_CLK_US 10
-
-// Allow 500us for clock strech to complete during unstick
-#define UNSTICK_CLK_STRETCH (500/UNSTICK_CLK_US)
-
-static void i2cUnstick(IO_t scl, IO_t sda);
-
#define IOCFG_I2C_PU IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_UP)
#define IOCFG_I2C IO_CONFIG(GPIO_MODE_MUX , GPIO_DRIVE_STRENGTH_STRONGER, GPIO_OUTPUT_OPEN_DRAIN , GPIO_PULL_NONE)
@@ -169,36 +156,4 @@ void i2cInit(I2CDevice device)
i2c_enable(i2cx, TRUE);
}
-static void i2cUnstick(IO_t scl, IO_t sda)
-{
- int i;
-
- IOHi(scl);
- IOHi(sda);
-
- IOConfigGPIO(scl, IOCFG_OUT_OD);
- IOConfigGPIO(sda, IOCFG_OUT_OD);
-
- for (i = 0; i < (LEN_ADDR + LEN_RW + LEN_ACK); i++) {
- int timeout = UNSTICK_CLK_STRETCH;
- while (!IORead(scl) && timeout) {
- delayMicroseconds(UNSTICK_CLK_US);
- timeout--;
- }
-
- IOLo(scl);
- delayMicroseconds(UNSTICK_CLK_US / 2);
- IOHi(scl);
- delayMicroseconds(UNSTICK_CLK_US / 2);
- }
-
- IOLo(scl);
- delayMicroseconds(UNSTICK_CLK_US / 2);
- IOLo(sda);
- delayMicroseconds(UNSTICK_CLK_US / 2);
-
- IOHi(scl);
- delayMicroseconds(UNSTICK_CLK_US / 2);
- IOHi(sda);
-}
#endif
diff --git a/src/main/drivers/bus_i2c_utils.c b/src/main/drivers/bus_i2c_utils.c
new file mode 100644
index 0000000000..ace10dab1f
--- /dev/null
+++ b/src/main/drivers/bus_i2c_utils.c
@@ -0,0 +1,89 @@
+/*
+ * This file is part of Betaflight.
+ *
+ * Betaflight is free software. You can redistribute this software
+ * and/or modify this software under the terms of the GNU General
+ * Public License as published by the Free Software Foundation,
+ * either version 3 of the License, or (at your option) any later
+ * version.
+ *
+ * Betaflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public
+ * License along with this software.
+ *
+ * If not, see .
+ */
+
+#include
+
+#include "platform.h"
+
+#include "drivers/io.h"
+#include "drivers/time.h"
+
+#include "bus_i2c_utils.h"
+
+// Clock period in us during unstick transfer
+#define UNSTICK_CLK_US 10 // 100Khz
+// Allow 500us for clock stretch to complete during unstick
+#define UNSTICK_CLK_STRETCH (500 / UNSTICK_CLK_US)
+
+// wait for SCL to return high (clock stretching)
+static bool i2cUnstick_waitStretch(IO_t scl, int timeout)
+{
+ bool sclVal;
+ while (!(sclVal = IORead(scl)) && timeout) {
+ delayMicroseconds(UNSTICK_CLK_US);
+ timeout--;
+ }
+ return sclVal;
+}
+
+// generate clock pulses + STOP on I2C bus
+// this should get all devices into idle state
+// return true if bus seems to be idle (both SCL and SDA are high)
+bool i2cUnstick(IO_t scl, IO_t sda)
+{
+ // output value first to prevent glitch after switching direction
+ IOHi(scl);
+ IOHi(sda);
+
+ // bus was probably in I2C (alternate function) mode
+ IOConfigGPIO(scl, IOCFG_OUT_OD);
+ IOConfigGPIO(sda, IOCFG_OUT_OD);
+
+ // Clock out, with SDA high:
+ // 7 data bits, 1 READ bit, 1 cycle for the ACK
+ for (int i = 0; i < (7 + 1 + 1); i++) {
+ // Wait for any clock stretching to finish
+ i2cUnstick_waitStretch(scl, UNSTICK_CLK_STRETCH);
+ // Pull low
+ IOLo(scl); // Set bus low
+ delayMicroseconds(UNSTICK_CLK_US / 2);
+ IOHi(scl); // Set bus high
+ delayMicroseconds(UNSTICK_CLK_US / 2);
+ }
+ // slave may be still stretching after last pulse
+ i2cUnstick_waitStretch(scl, UNSTICK_CLK_STRETCH);
+
+ // Generate a stop condition in case there was none
+ // SCL low pulse to switch SDA low
+ IOLo(scl);
+ delayMicroseconds(UNSTICK_CLK_US / 2);
+ IOLo(sda);
+ delayMicroseconds(UNSTICK_CLK_US / 2);
+ IOHi(scl);
+ delayMicroseconds(UNSTICK_CLK_US / 2);
+ // SDA rising edge = STOP
+ IOHi(sda);
+ // check that both SCL and SDA are high
+ delayMicroseconds(UNSTICK_CLK_US / 2); // time for SDA to return high
+ bool ok = IORead(scl) && IORead(sda);
+ // I2C ping are left in GPIO mode
+ return ok;
+}
diff --git a/src/main/drivers/bus_i2c_utils.h b/src/main/drivers/bus_i2c_utils.h
new file mode 100644
index 0000000000..ddc68d52ee
--- /dev/null
+++ b/src/main/drivers/bus_i2c_utils.h
@@ -0,0 +1,28 @@
+/*
+ * This file is part of Betaflight.
+ *
+ * Betaflight is free software. You can redistribute this software
+ * and/or modify this software under the terms of the GNU General
+ * Public License as published by the Free Software Foundation,
+ * either version 3 of the License, or (at your option) any later
+ * version.
+ *
+ * Betaflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
+ *
+ * See the GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public
+ * License along with this software.
+ *
+ * If not, see .
+ */
+
+#pragma once
+
+/*
+ * common functions shared by different I2C implementations
+ */
+
+bool i2cUnstick(IO_t scl, IO_t sda);
diff --git a/src/main/drivers/stm32/bus_i2c_hal_init.c b/src/main/drivers/stm32/bus_i2c_hal_init.c
index f5d7acfd15..8924fa469b 100644
--- a/src/main/drivers/stm32/bus_i2c_hal_init.c
+++ b/src/main/drivers/stm32/bus_i2c_hal_init.c
@@ -27,7 +27,6 @@
#if defined(USE_I2C) && !defined(SOFT_I2C)
#include "drivers/io.h"
-#include "drivers/io_impl.h"
#include "drivers/nvic.h"
#include "drivers/time.h"
#include "drivers/rcc.h"
@@ -35,19 +34,7 @@
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
#include "drivers/bus_i2c_timing.h"
-
-// Number of bits in I2C protocol phase
-#define LEN_ADDR 7
-#define LEN_RW 1
-#define LEN_ACK 1
-
-// Clock period in us during unstick transfer
-#define UNSTICK_CLK_US 10
-
-// Allow 500us for clock strech to complete during unstick
-#define UNSTICK_CLK_STRETCH (500/UNSTICK_CLK_US)
-
-static void i2cUnstick(IO_t scl, IO_t sda);
+#include "drivers/bus_i2c_utils.h"
#define IOCFG_I2C_PU IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP)
#define IOCFG_I2C IO_CONFIG(GPIO_MODE_AF_OD, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_NOPULL)
@@ -287,44 +274,4 @@ void i2cInit(I2CDevice device)
HAL_NVIC_EnableIRQ(hardware->ev_irq);
}
-static void i2cUnstick(IO_t scl, IO_t sda)
-{
- int i;
-
- IOHi(scl);
- IOHi(sda);
-
- IOConfigGPIO(scl, IOCFG_OUT_OD);
- IOConfigGPIO(sda, IOCFG_OUT_OD);
-
- // Clock out, with SDA high:
- // 7 data bits
- // 1 READ bit
- // 1 cycle for the ACK
- for (i = 0; i < (LEN_ADDR + LEN_RW + LEN_ACK); i++) {
- // Wait for any clock stretching to finish
- int timeout = UNSTICK_CLK_STRETCH;
- while (!IORead(scl) && timeout) {
- delayMicroseconds(UNSTICK_CLK_US);
- timeout--;
- }
-
- // Pull low
- IOLo(scl); // Set bus low
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOHi(scl); // Set bus high
- delayMicroseconds(UNSTICK_CLK_US/2);
- }
-
- // Generate a stop condition in case there was none
- IOLo(scl);
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOLo(sda);
- delayMicroseconds(UNSTICK_CLK_US/2);
-
- IOHi(scl); // Set bus scl high
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOHi(sda); // Set bus sda high
-}
-
#endif
diff --git a/src/main/drivers/stm32/bus_i2c_stm32f4xx.c b/src/main/drivers/stm32/bus_i2c_stm32f4xx.c
index a0c7ddde20..26ea2e5d96 100644
--- a/src/main/drivers/stm32/bus_i2c_stm32f4xx.c
+++ b/src/main/drivers/stm32/bus_i2c_stm32f4xx.c
@@ -34,21 +34,10 @@
#include "drivers/bus_i2c.h"
#include "drivers/bus_i2c_impl.h"
-
-// Number of bits in I2C protocol phase
-#define LEN_ADDR 7
-#define LEN_RW 1
-#define LEN_ACK 1
-
-// Clock period in us during unstick transfer
-#define UNSTICK_CLK_US 10
-
-// Allow 500us for clock strech to complete during unstick
-#define UNSTICK_CLK_STRETCH (500/UNSTICK_CLK_US)
+#include "drivers/bus_i2c_utils.h"
static void i2c_er_handler(I2CDevice device);
static void i2c_ev_handler(I2CDevice device);
-static void i2cUnstick(IO_t scl, IO_t sda);
#ifdef STM32F4
#define IOCFG_I2C_PU IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
@@ -513,44 +502,4 @@ uint16_t i2cGetErrorCounter(void)
return i2cErrorCount;
}
-static void i2cUnstick(IO_t scl, IO_t sda)
-{
- int i;
-
- IOHi(scl);
- IOHi(sda);
-
- IOConfigGPIO(scl, IOCFG_OUT_OD);
- IOConfigGPIO(sda, IOCFG_OUT_OD);
-
- // Clock out, with SDA high:
- // 7 data bits
- // 1 READ bit
- // 1 cycle for the ACK
- for (i = 0; i < (LEN_ADDR + LEN_RW + LEN_ACK); i++) {
- // Wait for any clock stretching to finish
- int timeout = UNSTICK_CLK_STRETCH;
- while (!IORead(scl) && timeout) {
- delayMicroseconds(UNSTICK_CLK_US);
- timeout--;
- }
-
- // Pull low
- IOLo(scl); // Set bus low
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOHi(scl); // Set bus high
- delayMicroseconds(UNSTICK_CLK_US/2);
- }
-
- // Generate a stop condition in case there was none
- IOLo(scl);
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOLo(sda);
- delayMicroseconds(UNSTICK_CLK_US/2);
-
- IOHi(scl); // Set bus scl high
- delayMicroseconds(UNSTICK_CLK_US/2);
- IOHi(sda); // Set bus sda high
-}
-
#endif