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 <soc/dport_reg.h>
12 #include <soc/i2c_reg.h>
13 #include <esp32/rom/gpio.h>
14 #include <soc/gpio_sig_map.h>
15 
16 #include <soc.h>
17 #include <errno.h>
18 #include <drivers/gpio.h>
19 #include <drivers/gpio/gpio_esp32.h>
20 #include <drivers/i2c.h>
21 #include <drivers/interrupt_controller/intc_esp32.h>
22 #include <drivers/clock_control.h>
23 #include <sys/util.h>
24 #include <string.h>
25 
26 #define LOG_LEVEL CONFIG_I2C_LOG_LEVEL
27 #include <logging/log.h>
28 LOG_MODULE_REGISTER(i2c_esp32);
29 
30 #include "i2c-priv.h"
31 
32 /* Number of entries in hardware command queue */
33 #define I2C_ESP32_NUM_CMDS 16
34 /* Number of bytes in hardware FIFO */
35 #define I2C_ESP32_BUFFER_SIZE 32
36 
37 #define I2C_ESP32_TRANSFER_TIMEOUT_MS 100
38 #define I2C_ESP32_TIMEOUT_USEC  1000
39 
40 enum i2c_esp32_opcodes {
41 	I2C_ESP32_OP_RSTART,
42 	I2C_ESP32_OP_WRITE,
43 	I2C_ESP32_OP_READ,
44 	I2C_ESP32_OP_STOP,
45 	I2C_ESP32_OP_END
46 };
47 
48 struct i2c_esp32_cmd {
49 	uint32_t num_bytes : 8;
50 	uint32_t ack_en : 1;
51 	uint32_t ack_exp : 1;
52 	uint32_t ack_val : 1;
53 	uint32_t opcode : 3;
54 	uint32_t reserved : 17;
55 	uint32_t done : 1;
56 };
57 
58 struct i2c_esp32_data {
59 	uint32_t dev_config;
60 	uint16_t address;
61 	uint32_t err_status;
62 
63 	struct k_sem fifo_sem;
64 	struct k_sem transfer_sem;
65 
66 	int irq_line;
67 };
68 
69 typedef void (*irq_connect_cb)(void);
70 
71 struct i2c_esp32_config {
72 	int index;
73 
74 	const struct device *clock_dev;
75 
76 	const struct {
77 		int sda_out;
78 		int sda_in;
79 		int scl_out;
80 		int scl_in;
81 	} sig;
82 
83 	const struct {
84 		int scl;
85 		int sda;
86 	} pins;
87 
88 	const clock_control_subsys_t peripheral_id;
89 
90 	const struct {
91 		bool tx_lsb_first;
92 		bool rx_lsb_first;
93 	} mode;
94 
95 	int irq_source;
96 
97 	const uint32_t default_config;
98 	const uint32_t bitrate;
99 };
100 
i2c_esp32_configure_pins(int pin,int matrix_out,int matrix_in)101 static int i2c_esp32_configure_pins(int pin, int matrix_out, int matrix_in)
102 {
103 	const int pin_mode = GPIO_OUTPUT_HIGH |
104 			     GPIO_OPEN_DRAIN  |
105 			     GPIO_PULL_UP;
106 	const char *device_name = gpio_esp32_get_gpio_for_pin(pin);
107 	const struct device *gpio;
108 	int ret;
109 
110 	if (!device_name) {
111 		return -EINVAL;
112 	}
113 	gpio = device_get_binding(device_name);
114 	if (!gpio) {
115 		return -EINVAL;
116 	}
117 
118 	ret = gpio_pin_configure(gpio, pin, pin_mode);
119 	if (ret < 0) {
120 		return ret;
121 	}
122 
123 	esp32_rom_gpio_matrix_out(pin, matrix_out, false, false);
124 	esp32_rom_gpio_matrix_in(pin, matrix_in, false);
125 
126 	return 0;
127 }
128 
i2c_esp32_configure_speed(const struct device * dev,uint32_t speed)129 static int i2c_esp32_configure_speed(const struct device *dev,
130 				     uint32_t speed)
131 {
132 	static const uint32_t speed_to_freq_tbl[] = {
133 		[I2C_SPEED_STANDARD] = KHZ(100),
134 		[I2C_SPEED_FAST] = KHZ(400),
135 		[I2C_SPEED_FAST_PLUS] = MHZ(1),
136 		[I2C_SPEED_HIGH] = 0,
137 		[I2C_SPEED_ULTRA] = 0
138 	};
139 
140 	const struct i2c_esp32_config *config = dev->config;
141 
142 	uint32_t sys_clk_freq = 0;
143 	uint32_t freq_hz = speed_to_freq_tbl[speed];
144 	uint32_t period;
145 
146 	if (!freq_hz) {
147 		return -ENOTSUP;
148 	}
149 
150 	if (clock_control_get_rate(config->clock_dev,
151 				   config->peripheral_id,
152 				   &sys_clk_freq)) {
153 		return -EINVAL;
154 	}
155 
156 	period = (sys_clk_freq / freq_hz);
157 	period /= 2U; /* Set hold and setup times to 1/2th of period */
158 
159 	esp32_set_mask32(period << I2C_SCL_LOW_PERIOD_S,
160 		   I2C_SCL_LOW_PERIOD_REG(config->index));
161 	esp32_set_mask32(period << I2C_SCL_HIGH_PERIOD_S,
162 		   I2C_SCL_HIGH_PERIOD_REG(config->index));
163 
164 	esp32_set_mask32(period << I2C_SCL_START_HOLD_TIME_S,
165 		   I2C_SCL_START_HOLD_REG(config->index));
166 	esp32_set_mask32(period << I2C_SCL_RSTART_SETUP_TIME_S,
167 		   I2C_SCL_RSTART_SETUP_REG(config->index));
168 	esp32_set_mask32(period << I2C_SCL_STOP_HOLD_TIME_S,
169 		   I2C_SCL_STOP_HOLD_REG(config->index));
170 	esp32_set_mask32(period << I2C_SCL_STOP_SETUP_TIME_S,
171 		   I2C_SCL_STOP_SETUP_REG(config->index));
172 
173 	period /= 2U; /* Set sample and hold times to 1/4th of period */
174 	esp32_set_mask32(period << I2C_SDA_HOLD_TIME_S,
175 		   I2C_SDA_HOLD_REG(config->index));
176 	esp32_set_mask32(period << I2C_SDA_SAMPLE_TIME_S,
177 		   I2C_SDA_SAMPLE_REG(config->index));
178 
179 	return 0;
180 }
181 
i2c_esp32_configure(const struct device * dev,uint32_t dev_config)182 static int i2c_esp32_configure(const struct device *dev, uint32_t dev_config)
183 {
184 	const struct i2c_esp32_config *config = dev->config;
185 	struct i2c_esp32_data *data = dev->data;
186 	unsigned int key = irq_lock();
187 	uint32_t v = 0U;
188 	int ret;
189 
190 	ret = i2c_esp32_configure_pins(config->pins.scl,
191 				       config->sig.scl_out,
192 				       config->sig.scl_in);
193 	if (ret < 0) {
194 		return ret;
195 	}
196 
197 	ret = i2c_esp32_configure_pins(config->pins.sda,
198 				       config->sig.sda_out,
199 				       config->sig.sda_in);
200 	if (ret < 0) {
201 		return ret;
202 	}
203 
204 	clock_control_on(config->clock_dev, config->peripheral_id);
205 
206 	/* MSB or LSB first is configurable for both TX and RX */
207 	if (config->mode.tx_lsb_first) {
208 		v |= I2C_TX_LSB_FIRST;
209 	}
210 
211 	if (config->mode.rx_lsb_first) {
212 		v |= I2C_RX_LSB_FIRST;
213 	}
214 
215 	if (dev_config & I2C_MODE_MASTER) {
216 		v |= I2C_MS_MODE;
217 		sys_write32(0, I2C_SLAVE_ADDR_REG(config->index));
218 	} else {
219 		uint32_t addr = (data->address & I2C_SLAVE_ADDR_V);
220 
221 		if (dev_config & I2C_ADDR_10_BITS) {
222 			addr |= I2C_ADDR_10BIT_EN;
223 		}
224 		sys_write32(addr << I2C_SLAVE_ADDR_S,
225 			    I2C_SLAVE_ADDR_REG(config->index));
226 
227 		/* Before setting up FIFO and interrupts, stop transmission */
228 		sys_clear_bit(I2C_CTR_REG(config->index), I2C_TRANS_START_S);
229 
230 		/* Byte after address isn't the offset address in slave RAM */
231 		sys_clear_bit(I2C_FIFO_CONF_REG(config->index),
232 			      I2C_FIFO_ADDR_CFG_EN_S);
233 	}
234 
235 	/* Use open-drain for clock and data pins */
236 	v |= (I2C_SCL_FORCE_OUT | I2C_SDA_FORCE_OUT);
237 	v |= I2C_CLK_EN;
238 	sys_write32(v, I2C_CTR_REG(config->index));
239 
240 	ret = i2c_esp32_configure_speed(dev, I2C_SPEED_GET(dev_config));
241 	if (ret < 0) {
242 		goto out;
243 	}
244 
245 	/* Use FIFO to transmit data */
246 	sys_clear_bit(I2C_FIFO_CONF_REG(config->index), I2C_NONFIFO_EN_S);
247 
248 	v = CONFIG_I2C_ESP32_TIMEOUT & I2C_TIME_OUT_REG;
249 	sys_write32(v << I2C_TIME_OUT_REG_S, I2C_TO_REG(config->index));
250 
251 	/* Enable interrupt types handled by the ISR */
252 	sys_write32(I2C_ACK_ERR_INT_ENA_M |
253 		    I2C_TIME_OUT_INT_ENA_M |
254 		    I2C_TRANS_COMPLETE_INT_ENA_M |
255 		    I2C_ARBITRATION_LOST_INT_ENA_M,
256 		    I2C_INT_ENA_REG(config->index));
257 
258 	irq_enable(data->irq_line);
259 
260 out:
261 	irq_unlock(key);
262 
263 	return ret;
264 }
265 
i2c_esp32_reset_fifo(const struct i2c_esp32_config * config)266 static inline void i2c_esp32_reset_fifo(const struct i2c_esp32_config *config)
267 {
268 	uint32_t reg = I2C_FIFO_CONF_REG(config->index);
269 
270 	/* Writing 1 and then 0 to these bits will reset the I2C fifo */
271 	esp32_set_mask32(I2C_TX_FIFO_RST | I2C_RX_FIFO_RST, reg);
272 	esp32_clear_mask32(I2C_TX_FIFO_RST | I2C_RX_FIFO_RST, reg);
273 }
274 
i2c_esp32_wait_timeout(uint32_t * counter)275 static int i2c_esp32_wait_timeout(uint32_t *counter)
276 {
277 	if (*counter == 0) {
278 		return 1;
279 	}
280 
281 	(*counter)--;
282 	k_busy_wait(1);
283 	return 0;
284 }
285 
i2c_esp32_wait(const struct device * dev,volatile struct i2c_esp32_cmd * wait_cmd)286 static int i2c_esp32_wait(const struct device *dev,
287 			  volatile struct i2c_esp32_cmd *wait_cmd)
288 {
289 	const struct i2c_esp32_config *config = dev->config;
290 	struct i2c_esp32_data *data = dev->data;
291 	uint32_t timeout = I2C_ESP32_TIMEOUT_USEC;
292 
293 	if (wait_cmd) {
294 		while (!wait_cmd->done) {
295 			if (i2c_esp32_wait_timeout(&timeout)) {
296 				return -ETIMEDOUT;
297 			}
298 		}
299 	}
300 
301 	/* Wait for I2C bus to finish its business */
302 	timeout = I2C_ESP32_TIMEOUT_USEC;
303 	while (sys_read32(I2C_SR_REG(config->index)) & I2C_BUS_BUSY) {
304 		if (i2c_esp32_wait_timeout(&timeout)) {
305 			return -ETIMEDOUT;
306 		}
307 	}
308 
309 	uint32_t status = data->err_status;
310 	if (status & (I2C_ARBITRATION_LOST_INT_RAW | I2C_ACK_ERR_INT_RAW)) {
311 		data->err_status = 0;
312 		return -EIO;
313 	}
314 	if (status & I2C_TIME_OUT_INT_RAW) {
315 		data->err_status = 0;
316 		return -ETIMEDOUT;
317 	}
318 
319 	return 0;
320 }
321 
i2c_esp32_transmit(const struct device * dev,volatile struct i2c_esp32_cmd * wait_cmd)322 static int i2c_esp32_transmit(const struct device *dev, volatile struct i2c_esp32_cmd *wait_cmd)
323 {
324 	const struct i2c_esp32_config *config = dev->config;
325 	struct i2c_esp32_data *data = dev->data;
326 
327 	/* Start transmission and wait for the ISR to give the semaphore */
328 	sys_set_bit(I2C_CTR_REG(config->index), I2C_TRANS_START_S);
329 	if (k_sem_take(&data->fifo_sem, K_MSEC(I2C_ESP32_TRANSFER_TIMEOUT_MS)) < 0) {
330 		return -ETIMEDOUT;
331 	}
332 
333 	return i2c_esp32_wait(dev, wait_cmd);
334 }
335 
336 static volatile struct i2c_esp32_cmd *
i2c_esp32_write_addr(const struct device * dev,volatile struct i2c_esp32_cmd * cmd,struct i2c_msg * msg,uint16_t addr)337 i2c_esp32_write_addr(const struct device *dev,
338 		     volatile struct i2c_esp32_cmd *cmd,
339 		     struct i2c_msg *msg,
340 		     uint16_t addr)
341 {
342 	const struct i2c_esp32_config *config = dev->config;
343 	struct i2c_esp32_data *data = dev->data;
344 	uint32_t addr_len = 1U;
345 
346 	i2c_esp32_reset_fifo(config);
347 
348 	sys_write32(addr & I2C_FIFO_RDATA, I2C_DATA_APB_REG(config->index));
349 	if (data->dev_config & I2C_ADDR_10_BITS) {
350 		sys_write32(I2C_DATA_APB_REG(config->index),
351 			    (addr >> 8) & I2C_FIFO_RDATA);
352 		addr_len++;
353 	}
354 
355 	if ((msg->flags & I2C_MSG_RW_MASK) != I2C_MSG_WRITE) {
356 		*cmd++ = (struct i2c_esp32_cmd) {
357 			.opcode = I2C_ESP32_OP_WRITE,
358 			.ack_en = true,
359 			.num_bytes = addr_len,
360 		};
361 	} else {
362 		msg->len += addr_len;
363 	}
364 
365 	return cmd;
366 }
367 
i2c_esp32_read_msg(const struct device * dev,uint16_t addr,struct i2c_msg msg)368 static int i2c_esp32_read_msg(const struct device *dev, uint16_t addr,
369 			      struct i2c_msg msg)
370 {
371 	const struct i2c_esp32_config *config = dev->config;
372 	volatile struct i2c_esp32_cmd *cmd =
373 		(void *)I2C_COMD0_REG(config->index);
374 	uint32_t i;
375 	int ret;
376 
377 	/* Set the R/W bit to R */
378 	addr |= BIT(0);
379 
380 	*cmd++ = (struct i2c_esp32_cmd) {
381 		.opcode = I2C_ESP32_OP_RSTART
382 	};
383 
384 	cmd = i2c_esp32_write_addr(dev, cmd, &msg, addr);
385 
386 	for (; msg.len; cmd = (void *)I2C_COMD0_REG(config->index)) {
387 		volatile struct i2c_esp32_cmd *wait_cmd = NULL;
388 		uint32_t to_read = MIN(I2C_ESP32_BUFFER_SIZE, msg.len - 1);
389 
390 		/* Might be the last byte, in which case, `to_read` will
391 		 * be 0 here.  See comment below.
392 		 */
393 		if (to_read) {
394 			*cmd++ = (struct i2c_esp32_cmd) {
395 				.opcode = I2C_ESP32_OP_READ,
396 				.num_bytes = to_read,
397 			};
398 		}
399 
400 		/* I2C master won't acknowledge the last byte read from the
401 		 * slave device.  Divide the read command in two segments as
402 		 * recommended by the ESP32 Technical Reference Manual.
403 		 */
404 		if (msg.len - to_read <= 1U) {
405 			/* Read the last byte and explicitly ask for an
406 			 * acknowledgment.
407 			 */
408 			*cmd++ = (struct i2c_esp32_cmd) {
409 				.opcode = I2C_ESP32_OP_READ,
410 				.num_bytes = 1,
411 				.ack_val = true,
412 			};
413 
414 			/* Account for the `msg.len - 1` when clamping
415 			 * transmission length to FIFO buffer size.
416 			 */
417 			to_read++;
418 
419 			if (msg.flags & I2C_MSG_STOP) {
420 				wait_cmd = cmd;
421 				*cmd++ = (struct i2c_esp32_cmd) {
422 					.opcode = I2C_ESP32_OP_STOP
423 				};
424 			}
425 		}
426 		if (!wait_cmd) {
427 			*cmd++ = (struct i2c_esp32_cmd) {
428 				.opcode = I2C_ESP32_OP_END
429 			};
430 		}
431 
432 		ret = i2c_esp32_transmit(dev, wait_cmd);
433 		if (ret < 0) {
434 			return ret;
435 		}
436 
437 		for (i = 0U; i < to_read; i++) {
438 			uint32_t v = sys_read32(I2C_DATA_APB_REG(config->index));
439 
440 			*msg.buf++ = v & I2C_FIFO_RDATA;
441 		}
442 		msg.len -= to_read;
443 
444 		i2c_esp32_reset_fifo(config);
445 	}
446 
447 	return 0;
448 }
449 
i2c_esp32_write_msg(const struct device * dev,uint16_t addr,struct i2c_msg msg)450 static int i2c_esp32_write_msg(const struct device *dev, uint16_t addr,
451 			       struct i2c_msg msg)
452 {
453 	const struct i2c_esp32_config *config = dev->config;
454 	volatile struct i2c_esp32_cmd *cmd =
455 		(void *)I2C_COMD0_REG(config->index);
456 
457 	*cmd++ = (struct i2c_esp32_cmd) {
458 		.opcode = I2C_ESP32_OP_RSTART
459 	};
460 
461 	cmd = i2c_esp32_write_addr(dev, cmd, &msg, addr);
462 
463 	for (; msg.len; cmd = (void *)I2C_COMD0_REG(config->index)) {
464 		uint32_t to_send = MIN(I2C_ESP32_BUFFER_SIZE, msg.len);
465 		uint32_t i;
466 		int ret;
467 
468 		/* Copy data to TX fifo */
469 		for (i = 0U; i < to_send; i++) {
470 			sys_write32(*msg.buf++,
471 				    I2C_DATA_APB_REG(config->index));
472 		}
473 		*cmd++ = (struct i2c_esp32_cmd) {
474 			.opcode = I2C_ESP32_OP_WRITE,
475 			.num_bytes = to_send,
476 			.ack_en = true,
477 		};
478 		msg.len -= to_send;
479 
480 		if (!msg.len || (msg.flags & I2C_MSG_STOP)) {
481 			*cmd = (struct i2c_esp32_cmd) {
482 				.opcode = I2C_ESP32_OP_STOP
483 			};
484 		} else {
485 			*cmd = (struct i2c_esp32_cmd) {
486 				.opcode = I2C_ESP32_OP_END
487 			};
488 		}
489 
490 		ret = i2c_esp32_transmit(dev, cmd);
491 		if (ret < 0) {
492 			return ret;
493 		}
494 
495 		i2c_esp32_reset_fifo(config);
496 	}
497 
498 	return 0;
499 }
500 
i2c_esp32_transfer(const struct device * dev,struct i2c_msg * msgs,uint8_t num_msgs,uint16_t addr)501 static int i2c_esp32_transfer(const struct device *dev, struct i2c_msg *msgs,
502 			      uint8_t num_msgs, uint16_t addr)
503 {
504 	struct i2c_esp32_data *data = dev->data;
505 	int ret = 0;
506 	uint8_t i;
507 
508 	k_sem_take(&data->transfer_sem, K_FOREVER);
509 
510 	/* Mask out unused address bits, and make room for R/W bit */
511 	addr &= BIT_MASK(data->dev_config & I2C_ADDR_10_BITS ? 10 : 7);
512 	addr <<= 1;
513 
514 	for (i = 0U; i < num_msgs; i++) {
515 		if ((msgs[i].flags & I2C_MSG_RW_MASK) == I2C_MSG_WRITE) {
516 			ret = i2c_esp32_write_msg(dev, addr, msgs[i]);
517 		} else {
518 			ret = i2c_esp32_read_msg(dev, addr, msgs[i]);
519 		}
520 
521 		if (ret < 0) {
522 			break;
523 		}
524 	}
525 
526 	k_sem_give(&data->transfer_sem);
527 
528 	return ret;
529 }
530 
i2c_esp32_isr(void * arg)531 static void i2c_esp32_isr(void *arg)
532 {
533 	struct device *dev = (struct device *)arg;
534 	const int fifo_give_mask = I2C_ACK_ERR_INT_ST |
535 				   I2C_TIME_OUT_INT_ST |
536 				   I2C_TRANS_COMPLETE_INT_ST |
537 				   I2C_ARBITRATION_LOST_INT_ST;
538 	const struct i2c_esp32_config *config = dev->config;
539 	uint32_t status = sys_read32(I2C_INT_STATUS_REG(config->index));
540 
541 	if (status & fifo_give_mask) {
542 		struct i2c_esp32_data *data = dev->data;
543 
544 		/* Only give the semaphore if a watched interrupt happens.
545 		 * Error checking is performed at the other side of the
546 		 * semaphore, by reading the status register.
547 		 */
548 		if (status & I2C_ACK_ERR_INT_ST) {
549 			data->err_status |= I2C_ACK_ERR_INT_ST;
550 		}
551 		if (status & I2C_ARBITRATION_LOST_INT_ST) {
552 			data->err_status |= I2C_ARBITRATION_LOST_INT_ST;
553 		}
554 		if (status & I2C_TIME_OUT_INT_ST) {
555 			data->err_status |= I2C_TIME_OUT_INT_ST;
556 		}
557 		k_sem_give(&data->fifo_sem);
558 	}
559 
560 	/* Acknowledge all I2C interrupts */
561 	sys_write32(~0, I2C_INT_CLR_REG(config->index));
562 }
563 
564 static int i2c_esp32_init(const struct device *dev);
565 
566 static const struct i2c_driver_api i2c_esp32_driver_api = {
567 	.configure = i2c_esp32_configure,
568 	.transfer = i2c_esp32_transfer,
569 };
570 
571 #if DT_NODE_HAS_STATUS(DT_DRV_INST(0), okay)
572 static const struct i2c_esp32_config i2c_esp32_config_0 = {
573 	.index = 0,
574 	.clock_dev = DEVICE_DT_GET(DT_INST_CLOCKS_CTLR(0)),
575 	.peripheral_id = (clock_control_subsys_t)DT_INST_CLOCKS_CELL(0, offset),
576 	.sig = {
577 		.sda_out = I2CEXT0_SDA_OUT_IDX,
578 		.sda_in = I2CEXT0_SDA_IN_IDX,
579 		.scl_out = I2CEXT0_SCL_OUT_IDX,
580 		.scl_in = I2CEXT0_SCL_IN_IDX,
581 	},
582 	.pins = {
583 		.scl = DT_INST_PROP(0, scl_pin),
584 		.sda = DT_INST_PROP(0, sda_pin),
585 	},
586 	.mode = {
587 		.tx_lsb_first =
588 			IS_ENABLED(CONFIG_I2C_ESP32_0_TX_LSB_FIRST),
589 		.rx_lsb_first =
590 			IS_ENABLED(CONFIG_I2C_ESP32_0_RX_LSB_FIRST),
591 	},
592 	.irq_source = DT_IRQN(DT_NODELABEL(i2c0)),
593 	.default_config = I2C_MODE_MASTER, /* FIXME: Zephyr don't support I2C_SLAVE_MODE */
594 	.bitrate = DT_INST_PROP(0, clock_frequency),
595 };
596 
597 static struct i2c_esp32_data i2c_esp32_data_0;
598 
599 DEVICE_DT_INST_DEFINE(0, &i2c_esp32_init, NULL,
600 		    &i2c_esp32_data_0, &i2c_esp32_config_0,
601 		    POST_KERNEL, CONFIG_I2C_INIT_PRIORITY,
602 		    &i2c_esp32_driver_api);
603 #endif /* DT_NODE_HAS_STATUS(DT_DRV_INST(0), okay) */
604 
605 #if DT_NODE_HAS_STATUS(DT_DRV_INST(1), okay)
606 static const struct i2c_esp32_config i2c_esp32_config_1 = {
607 	.index = 1,
608 	.clock_dev = DEVICE_DT_GET(DT_INST_CLOCKS_CTLR(1)),
609 	.peripheral_id = (clock_control_subsys_t)DT_INST_CLOCKS_CELL(1, offset),
610 	.sig = {
611 		.sda_out = I2CEXT1_SDA_OUT_IDX,
612 		.sda_in = I2CEXT1_SDA_IN_IDX,
613 		.scl_out = I2CEXT1_SCL_OUT_IDX,
614 		.scl_in = I2CEXT1_SCL_IN_IDX,
615 	},
616 	.pins = {
617 		.scl = DT_INST_PROP(1, scl_pin),
618 		.sda = DT_INST_PROP(1, sda_pin),
619 	},
620 	.mode = {
621 		.tx_lsb_first =
622 			IS_ENABLED(CONFIG_I2C_ESP32_1_TX_LSB_FIRST),
623 		.rx_lsb_first =
624 			IS_ENABLED(CONFIG_I2C_ESP32_1_RX_LSB_FIRST),
625 	},
626 	.irq_source = DT_IRQN(DT_NODELABEL(i2c1)),
627 	.default_config = I2C_MODE_MASTER, /* FIXME: Zephyr don't support I2C_SLAVE_MODE */
628 	.bitrate = DT_INST_PROP(1, clock_frequency),
629 };
630 
631 static struct i2c_esp32_data i2c_esp32_data_1;
632 
633 DEVICE_DT_INST_DEFINE(1, &i2c_esp32_init, NULL,
634 		    &i2c_esp32_data_1, &i2c_esp32_config_1,
635 		    POST_KERNEL, CONFIG_I2C_INIT_PRIORITY,
636 		    &i2c_esp32_driver_api);
637 #endif /* DT_NODE_HAS_STATUS(DT_DRV_INST(1), okay) */
638 
i2c_esp32_init(const struct device * dev)639 static int i2c_esp32_init(const struct device *dev)
640 {
641 	const struct i2c_esp32_config *config = dev->config;
642 	struct i2c_esp32_data *data = dev->data;
643 	uint32_t bitrate_cfg = i2c_map_dt_bitrate(config->bitrate);
644 
645 	unsigned int key = irq_lock();
646 
647 	k_sem_init(&data->fifo_sem, 1, 1);
648 	k_sem_init(&data->transfer_sem, 1, 1);
649 
650 	/* Even if irq_enable() is called on config->irq.line, disable
651 	 * interrupt sources in the I2C controller.
652 	 */
653 	sys_write32(0, I2C_INT_ENA_REG(config->index));
654 	data->irq_line = esp_intr_alloc(config->irq_source, 0, i2c_esp32_isr, (void *)dev, NULL);
655 	irq_unlock(key);
656 
657 	return i2c_esp32_configure(dev, config->default_config | bitrate_cfg);
658 }
659