1 /*
2  * Copyright (c) 2017 Intel Corporation
3  * Copyright (c) 2021 Espressif Systems (Shanghai) Co., Ltd.
4  *
5  * SPDX-License-Identifier: Apache-2.0
6  */
7 
8 #define DT_DRV_COMPAT espressif_esp32_i2c
9 
10 /* Include esp-idf headers first to avoid redefining BIT() macro */
11 #include <esp32/rom/gpio.h>
12 #include <soc/gpio_sig_map.h>
13 #include <hal/i2c_ll.h>
14 #include <hal/i2c_hal.h>
15 #include <hal/gpio_hal.h>
16 #include <clk_ctrl_os.h>
17 
18 #include <soc.h>
19 #include <errno.h>
20 #include <zephyr/drivers/gpio.h>
21 #include <zephyr/drivers/pinctrl.h>
22 #include <zephyr/drivers/i2c.h>
23 #include <zephyr/drivers/interrupt_controller/intc_esp32.h>
24 #include <zephyr/drivers/clock_control.h>
25 #include <zephyr/sys/util.h>
26 #include <string.h>
27 
28 #include <zephyr/logging/log.h>
29 LOG_MODULE_REGISTER(i2c_esp32, CONFIG_I2C_LOG_LEVEL);
30 
31 #include "i2c-priv.h"
32 
33 #define I2C_FILTER_CYC_NUM_DEF 7	/* Number of apb cycles filtered by default */
34 #define I2C_CLR_BUS_SCL_NUM 9		/* Number of SCL clocks to restore SDA signal */
35 #define I2C_CLR_BUS_HALF_PERIOD_US 5	/* Period of SCL clock to restore SDA signal */
36 #define I2C_TRANSFER_TIMEOUT_MSEC 500	/* Transfer timeout period */
37 
38 /* Freq limitation when using different clock sources */
39 #define I2C_CLK_LIMIT_REF_TICK (1 * 1000 * 1000 / 20)	/* REF_TICK, no more than REF_TICK/20*/
40 #define I2C_CLK_LIMIT_APB (80 * 1000 * 1000 / 20)	/* Limited by APB, no more than APB/20 */
41 #define I2C_CLK_LIMIT_RTC (20 * 1000 * 1000 / 20)	/* Limited by RTC, no more than RTC/20 */
42 #define I2C_CLK_LIMIT_XTAL (40 * 1000 * 1000 / 20)	/* Limited by RTC, no more than XTAL/20 */
43 
44 #define I2C_CLOCK_INVALID                 (-1)
45 
46 enum i2c_status_t {
47 	I2C_STATUS_READ,	/* read status for current master command */
48 	I2C_STATUS_WRITE,	/* write status for current master command */
49 	I2C_STATUS_IDLE,	/* idle status for current master command */
50 	I2C_STATUS_ACK_ERROR,	/* ack error status for current master command */
51 	I2C_STATUS_DONE,	/* I2C command done */
52 	I2C_STATUS_TIMEOUT,	/* I2C bus status error, and operation timeout */
53 };
54 
55 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
56 struct i2c_esp32_pin {
57 	struct gpio_dt_spec gpio;
58 	int sig_out;
59 	int sig_in;
60 };
61 #endif
62 
63 struct i2c_esp32_data {
64 	i2c_hal_context_t hal;
65 	struct k_sem cmd_sem;
66 	struct k_sem transfer_sem;
67 	volatile enum i2c_status_t status;
68 	uint32_t dev_config;
69 	int cmd_idx;
70 	int irq_line;
71 };
72 
73 typedef void (*irq_connect_cb)(void);
74 
75 struct i2c_esp32_config {
76 	int index;
77 
78 	const struct device *clock_dev;
79 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
80 	const struct i2c_esp32_pin scl;
81 	const struct i2c_esp32_pin sda;
82 #endif
83 	const struct pinctrl_dev_config *pcfg;
84 
85 	const clock_control_subsys_t clock_subsys;
86 
87 	const struct {
88 		bool tx_lsb_first;
89 		bool rx_lsb_first;
90 	} mode;
91 
92 	int irq_source;
93 	int irq_priority;
94 	int irq_flags;
95 
96 	const uint32_t bitrate;
97 	const uint32_t scl_timeout;
98 };
99 
i2c_get_src_clk_freq(i2c_clock_source_t clk_src)100 static uint32_t i2c_get_src_clk_freq(i2c_clock_source_t clk_src)
101 {
102 	uint32_t periph_src_clk_hz = 0;
103 
104 	switch (clk_src) {
105 #if SOC_I2C_SUPPORT_APB
106 	case I2C_CLK_SRC_APB:
107 		periph_src_clk_hz = esp_clk_apb_freq();
108 		break;
109 #endif
110 #if SOC_I2C_SUPPORT_XTAL
111 	case I2C_CLK_SRC_XTAL:
112 		periph_src_clk_hz = esp_clk_xtal_freq();
113 		break;
114 #endif
115 #if SOC_I2C_SUPPORT_RTC
116 	case I2C_CLK_SRC_RC_FAST:
117 		periph_rtc_dig_clk8m_enable();
118 		periph_src_clk_hz = periph_rtc_dig_clk8m_get_freq();
119 		break;
120 #endif
121 #if SOC_I2C_SUPPORT_REF_TICK
122 	case RMT_CLK_SRC_REF_TICK:
123 		periph_src_clk_hz = REF_CLK_FREQ;
124 		break;
125 #endif
126 	default:
127 		LOG_ERR("clock source %d is not supported", clk_src);
128 		break;
129 	}
130 
131 	return periph_src_clk_hz;
132 }
133 
i2c_get_clk_src(uint32_t clk_freq)134 static i2c_clock_source_t i2c_get_clk_src(uint32_t clk_freq)
135 {
136 	i2c_clock_source_t clk_srcs[] = SOC_I2C_CLKS;
137 
138 	for (size_t i = 0; i < ARRAY_SIZE(clk_srcs); i++) {
139 		/* I2C SCL clock frequency should not larger than clock source frequency/20 */
140 		if (clk_freq <= (i2c_get_src_clk_freq(clk_srcs[i]) / 20)) {
141 			return clk_srcs[i];
142 		}
143 	}
144 
145 	return I2C_CLOCK_INVALID;
146 }
147 
148 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
i2c_esp32_config_pin(const struct device * dev)149 static int i2c_esp32_config_pin(const struct device *dev)
150 {
151 	const struct i2c_esp32_config *config = dev->config;
152 	int ret = 0;
153 
154 	if (config->index >= SOC_I2C_NUM) {
155 		LOG_ERR("Invalid I2C peripheral number");
156 		return -EINVAL;
157 	}
158 
159 	gpio_pin_set_dt(&config->sda.gpio, 1);
160 	ret = gpio_pin_configure_dt(&config->sda.gpio, GPIO_PULL_UP | GPIO_OUTPUT | GPIO_INPUT);
161 	esp_rom_gpio_matrix_out(config->sda.gpio.pin, config->sda.sig_out, 0, 0);
162 	esp_rom_gpio_matrix_in(config->sda.gpio.pin, config->sda.sig_in, 0);
163 
164 	gpio_pin_set_dt(&config->scl.gpio, 1);
165 	ret |= gpio_pin_configure_dt(&config->scl.gpio, GPIO_PULL_UP | GPIO_OUTPUT | GPIO_INPUT);
166 	esp_rom_gpio_matrix_out(config->scl.gpio.pin, config->scl.sig_out, 0, 0);
167 	esp_rom_gpio_matrix_in(config->scl.gpio.pin, config->scl.sig_in, 0);
168 
169 	return ret;
170 }
171 #endif
172 
173 /* Some slave device will die by accident and keep the SDA in low level,
174  * in this case, master should send several clock to make the slave release the bus.
175  * Slave mode of ESP32 might also get in wrong state that held the SDA low,
176  * in this case, master device could send a stop signal to make esp32 slave release the bus.
177  **/
i2c_master_clear_bus(const struct device * dev)178 static void IRAM_ATTR i2c_master_clear_bus(const struct device *dev)
179 {
180 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
181 
182 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
183 	const struct i2c_esp32_config *config = dev->config;
184 	const int scl_half_period = I2C_CLR_BUS_HALF_PERIOD_US; /* use standard 100kHz data rate */
185 	int i = 0;
186 
187 	gpio_pin_configure_dt(&config->scl.gpio, GPIO_OUTPUT);
188 	gpio_pin_configure_dt(&config->sda.gpio, GPIO_OUTPUT | GPIO_INPUT);
189 	/* If a SLAVE device was in a read operation when the bus was interrupted, */
190 	/* the SLAVE device is controlling SDA. If the slave is sending a stream of ZERO bytes, */
191 	/* it will only release SDA during the  ACK bit period. So, this reset code needs */
192 	/* to synchronize the bit stream with either the ACK bit, or a 1 bit to correctly */
193 	/* generate a STOP condition. */
194 	gpio_pin_set_dt(&config->sda.gpio, 1);
195 	esp_rom_delay_us(scl_half_period);
196 	while (!gpio_pin_get_dt(&config->sda.gpio) && (i++ < I2C_CLR_BUS_SCL_NUM)) {
197 		gpio_pin_set_dt(&config->scl.gpio, 1);
198 		esp_rom_delay_us(scl_half_period);
199 		gpio_pin_set_dt(&config->scl.gpio, 0);
200 		esp_rom_delay_us(scl_half_period);
201 	}
202 	gpio_pin_set_dt(&config->sda.gpio, 0); /* setup for STOP */
203 	gpio_pin_set_dt(&config->scl.gpio, 1);
204 	esp_rom_delay_us(scl_half_period);
205 	gpio_pin_set_dt(&config->sda.gpio, 1); /* STOP, SDA low -> high while SCL is HIGH */
206 	i2c_esp32_config_pin(dev);
207 #else
208 	i2c_ll_master_clr_bus(data->hal.dev);
209 #endif
210 	i2c_ll_update(data->hal.dev);
211 }
212 
i2c_hw_fsm_reset(const struct device * dev)213 static void IRAM_ATTR i2c_hw_fsm_reset(const struct device *dev)
214 {
215 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
216 
217 #ifndef SOC_I2C_SUPPORT_HW_FSM_RST
218 	const struct i2c_esp32_config *config = dev->config;
219 	int scl_low_period, scl_high_period;
220 	int scl_start_hold, scl_rstart_setup;
221 	int scl_stop_hold, scl_stop_setup;
222 	int sda_hold, sda_sample;
223 	int timeout;
224 	uint8_t filter_cfg;
225 
226 	i2c_ll_get_scl_timing(data->hal.dev, &scl_high_period, &scl_low_period);
227 	i2c_ll_get_start_timing(data->hal.dev, &scl_rstart_setup, &scl_start_hold);
228 	i2c_ll_get_stop_timing(data->hal.dev, &scl_stop_setup, &scl_stop_hold);
229 	i2c_ll_get_sda_timing(data->hal.dev, &sda_sample, &sda_hold);
230 	i2c_ll_get_tout(data->hal.dev, &timeout);
231 	i2c_ll_get_filter(data->hal.dev, &filter_cfg);
232 
233 	/* to reset the I2C hw module, we need re-enable the hw */
234 	clock_control_off(config->clock_dev, config->clock_subsys);
235 	i2c_master_clear_bus(dev);
236 	clock_control_on(config->clock_dev, config->clock_subsys);
237 
238 	i2c_hal_master_init(&data->hal);
239 	i2c_ll_disable_intr_mask(data->hal.dev, I2C_LL_INTR_MASK);
240 	i2c_ll_clear_intr_mask(data->hal.dev, I2C_LL_INTR_MASK);
241 	i2c_ll_set_scl_timing(data->hal.dev, scl_high_period, scl_low_period);
242 	i2c_ll_set_start_timing(data->hal.dev, scl_rstart_setup, scl_start_hold);
243 	i2c_ll_set_stop_timing(data->hal.dev, scl_stop_setup, scl_stop_hold);
244 	i2c_ll_set_sda_timing(data->hal.dev, sda_sample, sda_hold);
245 	i2c_ll_set_tout(data->hal.dev, timeout);
246 	i2c_ll_set_filter(data->hal.dev, filter_cfg);
247 #else
248 	i2c_ll_master_fsm_rst(data->hal.dev);
249 	i2c_master_clear_bus(dev);
250 #endif
251 	i2c_ll_update(data->hal.dev);
252 }
253 
i2c_esp32_recover(const struct device * dev)254 static int i2c_esp32_recover(const struct device *dev)
255 {
256 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
257 
258 	k_sem_take(&data->transfer_sem, K_FOREVER);
259 	i2c_hw_fsm_reset(dev);
260 	k_sem_give(&data->transfer_sem);
261 
262 	return 0;
263 }
264 
i2c_esp32_configure_bitrate(const struct device * dev,uint32_t bitrate)265 static void IRAM_ATTR i2c_esp32_configure_bitrate(const struct device *dev, uint32_t bitrate)
266 {
267 	const struct i2c_esp32_config *config = dev->config;
268 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
269 
270 	i2c_clock_source_t sclk = i2c_get_clk_src(bitrate);
271 	uint32_t clk_freq_mhz = i2c_get_src_clk_freq(sclk);
272 
273 	i2c_hal_set_bus_timing(&data->hal, bitrate, sclk, clk_freq_mhz);
274 
275 	if (config->scl_timeout > 0) {
276 		uint32_t timeout_cycles = MIN(I2C_LL_MAX_TIMEOUT,
277 					      clk_freq_mhz / MHZ(1) * config->scl_timeout);
278 		i2c_ll_set_tout(data->hal.dev, timeout_cycles);
279 		LOG_DBG("SCL timeout: %d us, value: %d", config->scl_timeout, timeout_cycles);
280 	} else {
281 		/* Disabling the timeout by clearing the I2C_TIME_OUT_EN bit does not seem to work,
282 		 * at least for ESP32-C3 (tested with communication to bq76952 chip). So we set the
283 		 * timeout to maximum supported value instead.
284 		 */
285 		i2c_ll_set_tout(data->hal.dev, I2C_LL_MAX_TIMEOUT);
286 	}
287 
288 	i2c_ll_update(data->hal.dev);
289 }
290 
i2c_esp32_configure_data_mode(const struct device * dev)291 static void i2c_esp32_configure_data_mode(const struct device *dev)
292 {
293 	const struct i2c_esp32_config *config = dev->config;
294 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
295 
296 	i2c_trans_mode_t tx_mode = I2C_DATA_MODE_MSB_FIRST;
297 	i2c_trans_mode_t rx_mode = I2C_DATA_MODE_MSB_FIRST;
298 
299 	if (config->mode.tx_lsb_first) {
300 		tx_mode = I2C_DATA_MODE_LSB_FIRST;
301 	}
302 
303 	if (config->mode.rx_lsb_first) {
304 		rx_mode = I2C_DATA_MODE_LSB_FIRST;
305 	}
306 
307 	i2c_ll_set_data_mode(data->hal.dev, tx_mode, rx_mode);
308 	i2c_ll_set_filter(data->hal.dev, I2C_FILTER_CYC_NUM_DEF);
309 	i2c_ll_update(data->hal.dev);
310 
311 }
312 
i2c_esp32_configure(const struct device * dev,uint32_t dev_config)313 static int i2c_esp32_configure(const struct device *dev, uint32_t dev_config)
314 {
315 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
316 	uint32_t bitrate;
317 
318 	if (!(dev_config & I2C_MODE_CONTROLLER)) {
319 		LOG_ERR("Only I2C Master mode supported.");
320 		return -ENOTSUP;
321 	}
322 
323 	switch (I2C_SPEED_GET(dev_config)) {
324 	case I2C_SPEED_STANDARD:
325 		bitrate = KHZ(100);
326 		break;
327 	case I2C_SPEED_FAST:
328 		bitrate = KHZ(400);
329 		break;
330 	case I2C_SPEED_FAST_PLUS:
331 		bitrate = MHZ(1);
332 		break;
333 	default:
334 		LOG_ERR("Error configuring I2C speed.");
335 		return -ENOTSUP;
336 	}
337 
338 	k_sem_take(&data->transfer_sem, K_FOREVER);
339 
340 	data->dev_config = dev_config;
341 
342 	i2c_esp32_configure_bitrate(dev, bitrate);
343 
344 	k_sem_give(&data->transfer_sem);
345 
346 	return 0;
347 }
348 
i2c_esp32_get_config(const struct device * dev,uint32_t * config)349 static int i2c_esp32_get_config(const struct device *dev, uint32_t *config)
350 {
351 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
352 
353 	if (data->dev_config == 0) {
354 		LOG_ERR("I2C controller not configured");
355 		return -EIO;
356 	}
357 
358 	*config = data->dev_config;
359 
360 	return 0;
361 }
362 
i2c_esp32_reset_fifo(const struct device * dev)363 static void IRAM_ATTR i2c_esp32_reset_fifo(const struct device *dev)
364 {
365 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
366 
367 	/* reset fifo buffers */
368 	i2c_ll_txfifo_rst(data->hal.dev);
369 	i2c_ll_rxfifo_rst(data->hal.dev);
370 }
371 
i2c_esp32_transmit(const struct device * dev)372 static int IRAM_ATTR i2c_esp32_transmit(const struct device *dev)
373 {
374 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
375 	int ret = 0;
376 
377 	/* Start transmission*/
378 	i2c_ll_update(data->hal.dev);
379 	i2c_ll_trans_start(data->hal.dev);
380 	data->cmd_idx = 0;
381 
382 	ret = k_sem_take(&data->cmd_sem, K_MSEC(I2C_TRANSFER_TIMEOUT_MSEC));
383 	if (ret != 0) {
384 		/* If the I2C slave is powered off or the SDA/SCL is */
385 		/* connected to ground, for example, I2C hw FSM would get */
386 		/* stuck in wrong state, we have to reset the I2C module in this case. */
387 		i2c_hw_fsm_reset(dev);
388 		return -ETIMEDOUT;
389 	}
390 
391 	if (data->status == I2C_STATUS_TIMEOUT) {
392 		i2c_hw_fsm_reset(dev);
393 		ret = -ETIMEDOUT;
394 	} else if (data->status == I2C_STATUS_ACK_ERROR) {
395 		ret = -EFAULT;
396 	}
397 
398 	return ret;
399 }
400 
i2c_esp32_master_start(const struct device * dev)401 static void IRAM_ATTR i2c_esp32_master_start(const struct device *dev)
402 {
403 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
404 
405 	i2c_ll_hw_cmd_t cmd = {
406 		.op_code = I2C_LL_CMD_RESTART
407 	};
408 
409 	i2c_ll_write_cmd_reg(data->hal.dev, cmd, data->cmd_idx++);
410 }
411 
i2c_esp32_master_stop(const struct device * dev)412 static void IRAM_ATTR i2c_esp32_master_stop(const struct device *dev)
413 {
414 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
415 
416 	i2c_ll_hw_cmd_t cmd = {
417 		.op_code = I2C_LL_CMD_STOP
418 	};
419 
420 	i2c_ll_write_cmd_reg(data->hal.dev, cmd, data->cmd_idx++);
421 }
422 
i2c_esp32_write_addr(const struct device * dev,uint16_t addr)423 static int IRAM_ATTR i2c_esp32_write_addr(const struct device *dev, uint16_t addr)
424 {
425 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
426 	uint8_t addr_len = 1;
427 	uint8_t addr_byte = addr & 0xFF;
428 
429 	data->status = I2C_STATUS_WRITE;
430 
431 	/* write address value in tx buffer */
432 	i2c_ll_write_txfifo(data->hal.dev, &addr_byte, 1);
433 	if (data->dev_config & I2C_ADDR_10_BITS) {
434 		addr_byte = (addr >> 8) & 0xFF;
435 		i2c_ll_write_txfifo(data->hal.dev, &addr_byte, 1);
436 		addr_len++;
437 	}
438 
439 	const i2c_ll_hw_cmd_t cmd_end = {
440 		.op_code = I2C_LL_CMD_END,
441 	};
442 
443 	i2c_ll_hw_cmd_t cmd = {
444 		.op_code = I2C_LL_CMD_WRITE,
445 		.ack_en = true,
446 		.byte_num = addr_len,
447 	};
448 
449 	i2c_ll_write_cmd_reg(data->hal.dev, cmd, data->cmd_idx++);
450 	i2c_ll_write_cmd_reg(data->hal.dev, cmd_end, data->cmd_idx++);
451 	i2c_ll_master_enable_tx_it(data->hal.dev);
452 
453 	return i2c_esp32_transmit(dev);
454 }
455 
i2c_esp32_master_read(const struct device * dev,struct i2c_msg * msg)456 static int IRAM_ATTR i2c_esp32_master_read(const struct device *dev, struct i2c_msg *msg)
457 {
458 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
459 
460 	uint32_t msg_len = msg->len;
461 	uint8_t *msg_buf = msg->buf;
462 	uint8_t rd_filled = 0;
463 	int ret = 0;
464 
465 	data->status = I2C_STATUS_READ;
466 
467 	i2c_ll_hw_cmd_t cmd = {
468 		.op_code = I2C_LL_CMD_READ,
469 	};
470 	const i2c_ll_hw_cmd_t cmd_end = {
471 		.op_code = I2C_LL_CMD_END,
472 	};
473 
474 	while (msg_len) {
475 		rd_filled = (msg_len > SOC_I2C_FIFO_LEN) ? SOC_I2C_FIFO_LEN : (msg_len - 1);
476 
477 		/* I2C master won't acknowledge the last byte read from the
478 		 * slave device. Divide the read command in two segments as
479 		 * recommended by the ESP32 Technical Reference Manual.
480 		 */
481 		if (msg_len == 1) {
482 			rd_filled = 1;
483 			cmd.ack_val = 1;
484 		} else {
485 			cmd.ack_val = 0;
486 		}
487 		cmd.byte_num = rd_filled;
488 
489 		i2c_ll_write_cmd_reg(data->hal.dev, cmd, data->cmd_idx++);
490 		i2c_ll_write_cmd_reg(data->hal.dev, cmd_end, data->cmd_idx++);
491 		i2c_ll_master_enable_tx_it(data->hal.dev);
492 		ret = i2c_esp32_transmit(dev);
493 		if (ret < 0) {
494 			return ret;
495 		}
496 
497 		i2c_ll_read_rxfifo(data->hal.dev, msg_buf, rd_filled);
498 		msg_buf += rd_filled;
499 		msg_len -= rd_filled;
500 	}
501 
502 	return 0;
503 }
504 
i2c_esp32_read_msg(const struct device * dev,struct i2c_msg * msg,uint16_t addr)505 static int IRAM_ATTR i2c_esp32_read_msg(const struct device *dev,
506 					struct i2c_msg *msg, uint16_t addr)
507 {
508 	int ret = 0;
509 
510 	/* Set the R/W bit to R */
511 	addr |= BIT(0);
512 
513 	if (msg->flags & I2C_MSG_RESTART) {
514 		i2c_esp32_master_start(dev);
515 		ret = i2c_esp32_write_addr(dev, addr);
516 		if (ret < 0) {
517 			LOG_ERR("I2C transfer error: %d", ret);
518 			return ret;
519 		}
520 	}
521 
522 	ret = i2c_esp32_master_read(dev, msg);
523 	if (ret < 0) {
524 		LOG_ERR("I2C transfer error: %d", ret);
525 		return ret;
526 	}
527 
528 	if (msg->flags & I2C_MSG_STOP) {
529 		i2c_esp32_master_stop(dev);
530 		ret = i2c_esp32_transmit(dev);
531 		if (ret < 0) {
532 			LOG_ERR("I2C transfer error: %d", ret);
533 			return ret;
534 		}
535 	}
536 
537 	return 0;
538 }
539 
i2c_esp32_master_write(const struct device * dev,struct i2c_msg * msg)540 static int IRAM_ATTR i2c_esp32_master_write(const struct device *dev, struct i2c_msg *msg)
541 {
542 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
543 	uint8_t wr_filled = 0;
544 	uint32_t msg_len = msg->len;
545 	uint8_t *msg_buf = msg->buf;
546 	int ret = 0;
547 
548 	data->status = I2C_STATUS_WRITE;
549 
550 	i2c_ll_hw_cmd_t cmd = {
551 		.op_code = I2C_LL_CMD_WRITE,
552 		.ack_en = true,
553 	};
554 
555 	const i2c_ll_hw_cmd_t cmd_end = {
556 		.op_code = I2C_LL_CMD_END,
557 	};
558 
559 	while (msg_len) {
560 		wr_filled = (msg_len > SOC_I2C_FIFO_LEN) ? SOC_I2C_FIFO_LEN : msg_len;
561 		cmd.byte_num = wr_filled;
562 
563 		if (wr_filled > 0) {
564 			i2c_ll_write_txfifo(data->hal.dev, msg_buf, wr_filled);
565 			i2c_ll_write_cmd_reg(data->hal.dev, cmd, data->cmd_idx++);
566 			i2c_ll_write_cmd_reg(data->hal.dev, cmd_end, data->cmd_idx++);
567 			i2c_ll_master_enable_tx_it(data->hal.dev);
568 			ret = i2c_esp32_transmit(dev);
569 			if (ret < 0) {
570 				return ret;
571 			}
572 		}
573 
574 		msg_buf += wr_filled;
575 		msg_len -= wr_filled;
576 	}
577 
578 	return 0;
579 }
580 
i2c_esp32_write_msg(const struct device * dev,struct i2c_msg * msg,uint16_t addr)581 static int IRAM_ATTR i2c_esp32_write_msg(const struct device *dev,
582 					 struct i2c_msg *msg, uint16_t addr)
583 {
584 	int ret = 0;
585 
586 	if (msg->flags & I2C_MSG_RESTART) {
587 		i2c_esp32_master_start(dev);
588 		ret = i2c_esp32_write_addr(dev, addr);
589 		if (ret < 0) {
590 			LOG_ERR("I2C transfer error: %d", ret);
591 			return ret;
592 		}
593 	}
594 
595 	ret = i2c_esp32_master_write(dev, msg);
596 	if (ret < 0) {
597 		LOG_ERR("I2C transfer error: %d", ret);
598 		return ret;
599 	}
600 
601 	if (msg->flags & I2C_MSG_STOP) {
602 		i2c_esp32_master_stop(dev);
603 		ret = i2c_esp32_transmit(dev);
604 		if (ret < 0) {
605 			LOG_ERR("I2C transfer error: %d", ret);
606 			return ret;
607 		}
608 	}
609 
610 	return 0;
611 }
612 
i2c_esp32_transfer(const struct device * dev,struct i2c_msg * msgs,uint8_t num_msgs,uint16_t addr)613 static int IRAM_ATTR i2c_esp32_transfer(const struct device *dev, struct i2c_msg *msgs,
614 					uint8_t num_msgs, uint16_t addr)
615 {
616 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
617 	struct i2c_msg *current, *next;
618 	uint32_t timeout = I2C_TRANSFER_TIMEOUT_MSEC * USEC_PER_MSEC;
619 	int ret = 0;
620 
621 	if (!num_msgs) {
622 		return 0;
623 	}
624 
625 	while (i2c_ll_is_bus_busy(data->hal.dev)) {
626 		k_busy_wait(1);
627 		if (timeout-- == 0) {
628 			return -EBUSY;
629 		}
630 	}
631 
632 	/* Check for validity of all messages before transfer */
633 	current = msgs;
634 
635 	/* Add restart flag on first message to send start event */
636 	current->flags |= I2C_MSG_RESTART;
637 
638 	for (int k = 1; k <= num_msgs; k++) {
639 		if (k < num_msgs) {
640 			next = current + 1;
641 
642 			/* messages of different direction require restart event */
643 			if ((current->flags & I2C_MSG_RW_MASK) != (next->flags & I2C_MSG_RW_MASK)) {
644 				if (!(next->flags & I2C_MSG_RESTART)) {
645 					ret = -EINVAL;
646 					break;
647 				}
648 			}
649 
650 			/* check if there is any stop event in the middle of the transaction */
651 			if (current->flags & I2C_MSG_STOP) {
652 				ret = -EINVAL;
653 				break;
654 			}
655 		}
656 
657 		current++;
658 	}
659 
660 	if (ret) {
661 		return ret;
662 	}
663 
664 	k_sem_take(&data->transfer_sem, K_FOREVER);
665 
666 	/* Mask out unused address bits, and make room for R/W bit */
667 	addr &= BIT_MASK(data->dev_config & I2C_ADDR_10_BITS ? 10 : 7);
668 	addr <<= 1;
669 
670 	for (; num_msgs > 0; num_msgs--, msgs++) {
671 
672 		if (data->status == I2C_STATUS_TIMEOUT || i2c_ll_is_bus_busy(data->hal.dev)) {
673 			i2c_hw_fsm_reset(dev);
674 		}
675 
676 		/* reset all fifo buffer before start */
677 		i2c_esp32_reset_fifo(dev);
678 
679 		/* These two interrupts some times can not be cleared when the FSM gets stuck. */
680 		/* So we disable them when these two interrupt occurs and re-enable them here. */
681 		i2c_ll_disable_intr_mask(data->hal.dev, I2C_LL_INTR_MASK);
682 		i2c_ll_clear_intr_mask(data->hal.dev, I2C_LL_INTR_MASK);
683 
684 		if ((msgs->flags & I2C_MSG_RW_MASK) == I2C_MSG_READ) {
685 			ret = i2c_esp32_read_msg(dev, msgs, addr);
686 		} else {
687 			ret = i2c_esp32_write_msg(dev, msgs, addr);
688 		}
689 
690 		if (ret < 0) {
691 			break;
692 		}
693 	}
694 
695 	k_sem_give(&data->transfer_sem);
696 
697 	return ret;
698 }
699 
i2c_esp32_isr(void * arg)700 static void IRAM_ATTR i2c_esp32_isr(void *arg)
701 {
702 	const struct device *dev = (const struct device *)arg;
703 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
704 	i2c_intr_event_t evt_type = I2C_INTR_EVENT_ERR;
705 
706 	if (data->status == I2C_STATUS_WRITE) {
707 		i2c_hal_master_handle_tx_event(&data->hal, &evt_type);
708 	} else if (data->status == I2C_STATUS_READ) {
709 		i2c_hal_master_handle_rx_event(&data->hal, &evt_type);
710 	}
711 
712 	if (evt_type == I2C_INTR_EVENT_NACK) {
713 		data->status = I2C_STATUS_ACK_ERROR;
714 	} else if (evt_type == I2C_INTR_EVENT_TOUT) {
715 		data->status = I2C_STATUS_TIMEOUT;
716 	} else if (evt_type == I2C_INTR_EVENT_ARBIT_LOST) {
717 		data->status = I2C_STATUS_TIMEOUT;
718 	} else if (evt_type == I2C_INTR_EVENT_TRANS_DONE) {
719 		data->status = I2C_STATUS_DONE;
720 	}
721 
722 	k_sem_give(&data->cmd_sem);
723 }
724 
725 static DEVICE_API(i2c, i2c_esp32_driver_api) = {
726 	.configure = i2c_esp32_configure,
727 	.get_config = i2c_esp32_get_config,
728 	.transfer = i2c_esp32_transfer,
729 	.recover_bus = i2c_esp32_recover,
730 #ifdef CONFIG_I2C_RTIO
731 	.iodev_submit = i2c_iodev_submit_fallback,
732 #endif
733 };
734 
i2c_esp32_init(const struct device * dev)735 static int IRAM_ATTR i2c_esp32_init(const struct device *dev)
736 {
737 	const struct i2c_esp32_config *config = dev->config;
738 	struct i2c_esp32_data *data = (struct i2c_esp32_data *const)(dev)->data;
739 
740 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
741 	if (!gpio_is_ready_dt(&config->scl.gpio)) {
742 		LOG_ERR("SCL GPIO device is not ready");
743 		return -EINVAL;
744 	}
745 
746 	if (!gpio_is_ready_dt(&config->sda.gpio)) {
747 		LOG_ERR("SDA GPIO device is not ready");
748 		return -EINVAL;
749 	}
750 #endif
751 	int ret = pinctrl_apply_state(config->pcfg, PINCTRL_STATE_DEFAULT);
752 
753 	if (ret < 0) {
754 		LOG_ERR("Failed to configure I2C pins");
755 		return -EINVAL;
756 	}
757 
758 	if (!device_is_ready(config->clock_dev)) {
759 		LOG_ERR("clock control device not ready");
760 		return -ENODEV;
761 	}
762 
763 	clock_control_on(config->clock_dev, config->clock_subsys);
764 
765 	ret = esp_intr_alloc(config->irq_source,
766 			ESP_PRIO_TO_FLAGS(config->irq_priority) |
767 			ESP_INT_FLAGS_CHECK(config->irq_flags) | ESP_INTR_FLAG_IRAM,
768 			i2c_esp32_isr,
769 			(void *)dev,
770 			NULL);
771 
772 	if (ret != 0) {
773 		LOG_ERR("could not allocate interrupt (err %d)", ret);
774 		return ret;
775 	}
776 
777 	i2c_hal_master_init(&data->hal);
778 
779 	i2c_esp32_configure_data_mode(dev);
780 
781 	return i2c_esp32_configure(dev, I2C_MODE_CONTROLLER | i2c_map_dt_bitrate(config->bitrate));
782 }
783 
784 #define I2C(idx) DT_NODELABEL(i2c##idx)
785 
786 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
787 #define I2C_ESP32_GET_PIN_INFO(idx)					\
788 	.scl = {							\
789 		.gpio = GPIO_DT_SPEC_GET(I2C(idx), scl_gpios),		\
790 		.sig_out = I2CEXT##idx##_SCL_OUT_IDX,			\
791 		.sig_in = I2CEXT##idx##_SCL_IN_IDX,			\
792 	},								\
793 	.sda = {							\
794 		.gpio = GPIO_DT_SPEC_GET(I2C(idx), sda_gpios),		\
795 		.sig_out = I2CEXT##idx##_SDA_OUT_IDX,			\
796 		.sig_in = I2CEXT##idx##_SDA_IN_IDX,			\
797 	},
798 #else
799 #define I2C_ESP32_GET_PIN_INFO(idx)
800 #endif /* SOC_I2C_SUPPORT_HW_CLR_BUS */
801 
802 #define I2C_ESP32_TIMEOUT(inst)						\
803 	COND_CODE_1(DT_NODE_HAS_PROP(I2C(inst), scl_timeout_us),	\
804 		    (DT_PROP(I2C(inst), scl_timeout_us)), (0))
805 
806 #define I2C_ESP32_FREQUENCY(bitrate)					\
807 	 (bitrate == I2C_BITRATE_STANDARD ? KHZ(100)			\
808 	: bitrate == I2C_BITRATE_FAST     ? KHZ(400)			\
809 	: bitrate == I2C_BITRATE_FAST_PLUS  ? MHZ(1) : 0)
810 
811 #define I2C_FREQUENCY(idx)						\
812 	I2C_ESP32_FREQUENCY(DT_PROP(I2C(idx), clock_frequency))
813 
814 #define ESP32_I2C_INIT(idx)									   \
815 												   \
816 	PINCTRL_DT_DEFINE(I2C(idx));								   \
817 												   \
818 	static struct i2c_esp32_data i2c_esp32_data_##idx = {					   \
819 		.hal = {									   \
820 			.dev = (i2c_dev_t *) DT_REG_ADDR(I2C(idx)),				   \
821 		},										   \
822 		.cmd_sem = Z_SEM_INITIALIZER(i2c_esp32_data_##idx.cmd_sem, 0, 1),		   \
823 		.transfer_sem = Z_SEM_INITIALIZER(i2c_esp32_data_##idx.transfer_sem, 1, 1),	   \
824 	};											   \
825 												   \
826 	static const struct i2c_esp32_config i2c_esp32_config_##idx = {				   \
827 		.index = idx,									   \
828 		.clock_dev = DEVICE_DT_GET(DT_CLOCKS_CTLR(I2C(idx))),				   \
829 		.pcfg = PINCTRL_DT_DEV_CONFIG_GET(I2C(idx)),					   \
830 		.clock_subsys = (clock_control_subsys_t)DT_CLOCKS_CELL(I2C(idx), offset),	   \
831 		I2C_ESP32_GET_PIN_INFO(idx)							   \
832 		.mode = {									   \
833 			.tx_lsb_first = DT_PROP(I2C(idx), tx_lsb),				   \
834 			.rx_lsb_first = DT_PROP(I2C(idx), rx_lsb),				   \
835 		},										   \
836 		.irq_source = DT_IRQ_BY_IDX(I2C(idx), 0, irq),				   \
837 		.irq_priority = DT_IRQ_BY_IDX(I2C(idx), 0, priority),		   \
838 		.irq_flags = DT_IRQ_BY_IDX(I2C(idx), 0, flags),				   \
839 		.bitrate = I2C_FREQUENCY(idx),							   \
840 		.scl_timeout = I2C_ESP32_TIMEOUT(idx),						   \
841 	};											   \
842 	I2C_DEVICE_DT_DEFINE(I2C(idx), i2c_esp32_init, NULL, &i2c_esp32_data_##idx,		   \
843 			     &i2c_esp32_config_##idx, POST_KERNEL, CONFIG_I2C_INIT_PRIORITY,	   \
844 			     &i2c_esp32_driver_api);
845 
846 #if DT_NODE_HAS_STATUS_OKAY(I2C(0))
847 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
848 #if !DT_NODE_HAS_PROP(I2C(0), sda_gpios) || !DT_NODE_HAS_PROP(I2C(0), scl_gpios)
849 #error "Missing <sda-gpios> and <scl-gpios> properties to build for this target."
850 #endif
851 #else
852 #if DT_NODE_HAS_PROP(I2C(0), sda_gpios) || DT_NODE_HAS_PROP(I2C(0), scl_gpios)
853 #error "Properties <sda-gpios> and <scl-gpios> are not required for this target."
854 #endif
855 #endif /* !SOC_I2C_SUPPORT_HW_CLR_BUS */
856 ESP32_I2C_INIT(0);
857 #endif /* DT_NODE_HAS_STATUS_OKAY(I2C(0)) */
858 
859 #if DT_NODE_HAS_STATUS_OKAY(I2C(1))
860 #ifndef SOC_I2C_SUPPORT_HW_CLR_BUS
861 #if !DT_NODE_HAS_PROP(I2C(1), sda_gpios) || !DT_NODE_HAS_PROP(I2C(1), scl_gpios)
862 #error "Missing <sda-gpios> and <scl-gpios> properties to build for this target."
863 #endif
864 #else
865 #if DT_NODE_HAS_PROP(I2C(1), sda_gpios) || DT_NODE_HAS_PROP(I2C(1), scl_gpios)
866 #error "Properties <sda-gpios> and <scl-gpios> are not required for this target."
867 #endif
868 #endif /* !SOC_I2C_SUPPORT_HW_CLR_BUS */
869 ESP32_I2C_INIT(1);
870 #endif /* DT_NODE_HAS_STATUS_OKAY(I2C(1)) */
871