1 /*
2 * Copyright (c) 2018 Aapo Vienamo
3 * Copyright (c) 2018 Peter Bigot Consulting, LLC
4 * Copyright (c) 2019-2020 Nordic Semiconductor ASA
5 * Copyright (c) 2020 ZedBlox Ltd.
6 *
7 * SPDX-License-Identifier: Apache-2.0
8 */
9
10 #define DT_DRV_COMPAT semtech_sx1509b
11
12 #include <errno.h>
13
14 #include <zephyr/kernel.h>
15 #include <zephyr/device.h>
16 #include <zephyr/init.h>
17 #include <zephyr/drivers/gpio.h>
18 #include <zephyr/drivers/gpio/gpio_sx1509b.h>
19 #include <zephyr/dt-bindings/gpio/semtech-sx1509b.h>
20 #include <zephyr/drivers/i2c.h>
21 #include <zephyr/sys/byteorder.h>
22 #include <zephyr/sys/util.h>
23
24 #include <zephyr/logging/log.h>
25 LOG_MODULE_REGISTER(sx1509b, CONFIG_GPIO_LOG_LEVEL);
26
27 #include <zephyr/drivers/gpio/gpio_utils.h>
28
29 /* Number of pins supported by the device */
30 #define NUM_PINS 16
31
32 /* Max to select all pins supported on the device. */
33 #define ALL_PINS ((uint16_t)BIT_MASK(NUM_PINS))
34
35 /* Reset delay is 2.5 ms, round up for Zephyr resolution */
36 #define RESET_DELAY_MS 3
37
38 /** Cache of the output configuration and data of the pins. */
39 struct sx1509b_pin_state {
40 uint16_t input_disable; /* 0x00 */
41 uint16_t long_slew; /* 0x02 */
42 uint16_t low_drive; /* 0x04 */
43 uint16_t pull_up; /* 0x06 */
44 uint16_t pull_down; /* 0x08 */
45 uint16_t open_drain; /* 0x0A */
46 uint16_t polarity; /* 0x0C */
47 uint16_t dir; /* 0x0E */
48 uint16_t data; /* 0x10 */
49 } __packed;
50
51 struct sx1509b_irq_state {
52 uint16_t interrupt_mask; /* 0x12 */
53 uint32_t interrupt_sense; /* 0x14, 0x16 */
54 } __packed;
55
56 struct sx1509b_debounce_state {
57 uint8_t debounce_config; /* 0x22 */
58 uint16_t debounce_enable; /* 0x23 */
59 } __packed;
60
61 /** Runtime driver data */
62 struct sx1509b_drv_data {
63 /* gpio_driver_data needs to be first */
64 struct gpio_driver_data common;
65 struct sx1509b_pin_state pin_state;
66 uint16_t led_drv_enable;
67 struct sx1509b_debounce_state debounce_state;
68 struct k_sem lock;
69
70 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
71 struct gpio_callback gpio_cb;
72 struct k_work work;
73 struct sx1509b_irq_state irq_state;
74 const struct device *dev;
75 /* user ISR cb */
76 sys_slist_t cb;
77 #endif /* CONFIG_GPIO_SX1509B_INTERRUPT */
78
79 };
80
81 /** Configuration data */
82 struct sx1509b_config {
83 /* gpio_driver_config needs to be first */
84 struct gpio_driver_config common;
85 struct i2c_dt_spec bus;
86 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
87 struct gpio_dt_spec nint_gpio;
88 #endif /* CONFIG_GPIO_SX1509B_INTERRUPT */
89 };
90
91 /* General configuration register addresses */
92 enum {
93 /* TODO: Add rest of the regs */
94 SX1509B_REG_CLOCK = 0x1e,
95 SX1509B_REG_RESET = 0x7d,
96 };
97
98 /* Magic values for softreset */
99 enum {
100 SX1509B_REG_RESET_MAGIC0 = 0x12,
101 SX1509B_REG_RESET_MAGIC1 = 0x34,
102 };
103
104 /* Register bits for SX1509B_REG_CLOCK */
105 enum {
106 SX1509B_REG_CLOCK_FOSC_OFF = 0 << 5,
107 SX1509B_REG_CLOCK_FOSC_EXT = 1 << 5,
108 SX1509B_REG_CLOCK_FOSC_INT_2MHZ = 2 << 5,
109 };
110
111 /* Register bits for SX1509B_REG_MISC */
112 enum {
113 SX1509B_REG_MISC_LOG_A = 1 << 3,
114 SX1509B_REG_MISC_LOG_B = 1 << 7,
115 /* ClkX = fOSC */
116 SX1509B_REG_MISC_FREQ = 1 << 4,
117 };
118
119 /* Pin configuration register addresses */
120 enum {
121 SX1509B_REG_INPUT_DISABLE = 0x00,
122 SX1509B_REG_PULL_UP = 0x06,
123 SX1509B_REG_PULL_DOWN = 0x08,
124 SX1509B_REG_OPEN_DRAIN = 0x0a,
125 SX1509B_REG_DIR = 0x0e,
126 SX1509B_REG_DATA = 0x10,
127 SX1509B_REG_INTERRUPT_MASK = 0x12,
128 SX1509B_REG_INTERRUPT_SENSE = 0x14,
129 SX1509B_REG_INTERRUPT_SENSE_B = 0x14,
130 SX1509B_REG_INTERRUPT_SENSE_A = 0x16,
131 SX1509B_REG_INTERRUPT_SOURCE = 0x18,
132 SX1509B_REG_MISC = 0x1f,
133 SX1509B_REG_LED_DRV_ENABLE = 0x20,
134 SX1509B_REG_DEBOUNCE_CONFIG = 0x22,
135 SX1509B_REG_DEBOUNCE_ENABLE = 0x23,
136 };
137
138 /* Edge sensitivity types */
139 enum {
140 SX1509B_EDGE_NONE = 0x00,
141 SX1509B_EDGE_RISING = 0x01,
142 SX1509B_EDGE_FALLING = 0x02,
143 SX1509B_EDGE_BOTH = 0x03,
144 };
145
146 /* Intensity register addresses for all 16 pins */
147 static const uint8_t intensity_registers[16] = { 0x2a, 0x2d, 0x30, 0x33,
148 0x36, 0x3b, 0x40, 0x45,
149 0x4a, 0x4d, 0x50, 0x53,
150 0x56, 0x5b, 0x60, 0x65 };
151
152 /**
153 * @brief Write a big-endian word to an internal address of an I2C slave.
154 *
155 * @param dev Pointer to the I2C bus spec.
156 * @param reg_addr Address of the internal register being written.
157 * @param value Value to be written to internal register.
158 *
159 * @retval 0 If successful.
160 * @retval -EIO General input / output error.
161 */
i2c_reg_write_word_be(const struct i2c_dt_spec * bus,uint8_t reg_addr,uint16_t value)162 static inline int i2c_reg_write_word_be(const struct i2c_dt_spec *bus,
163 uint8_t reg_addr, uint16_t value)
164 {
165 uint8_t tx_buf[3] = { reg_addr, value >> 8, value & 0xff };
166
167 return i2c_write_dt(bus, tx_buf, 3);
168 }
169
170 /**
171 * @brief Write a big-endian byte to an internal address of an I2C slave.
172 *
173 * @param bus Pointer to the I2C bus spec.
174 * @param reg_addr Address of the internal register being written.
175 * @param value Value to be written to internal register.
176 *
177 * @retval 0 If successful.
178 * @retval -EIO General input / output error.
179 */
i2c_reg_write_byte_be(const struct i2c_dt_spec * bus,uint8_t reg_addr,uint8_t value)180 static inline int i2c_reg_write_byte_be(const struct i2c_dt_spec *bus,
181 uint8_t reg_addr, uint8_t value)
182 {
183 uint8_t tx_buf[3] = { reg_addr, value };
184
185 return i2c_write_dt(bus, tx_buf, 2);
186 }
187
188 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
sx1509b_handle_interrupt(const struct device * dev)189 static int sx1509b_handle_interrupt(const struct device *dev)
190 {
191 const struct sx1509b_config *cfg = dev->config;
192 struct sx1509b_drv_data *drv_data = dev->data;
193 int ret = 0;
194 uint16_t int_source;
195 uint8_t cmd = SX1509B_REG_INTERRUPT_SOURCE;
196
197 k_sem_take(&drv_data->lock, K_FOREVER);
198
199 ret = i2c_write_read_dt(&cfg->bus, &cmd, sizeof(cmd),
200 (uint8_t *)&int_source, sizeof(int_source));
201 if (ret != 0) {
202 goto out;
203 }
204
205 int_source = sys_be16_to_cpu(int_source);
206
207 /* reset interrupts before invoking callbacks */
208 ret = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_INTERRUPT_SOURCE,
209 int_source);
210
211 out:
212 k_sem_give(&drv_data->lock);
213
214 if (ret == 0) {
215 gpio_fire_callbacks(&drv_data->cb, dev, int_source);
216 }
217
218 return ret;
219 }
220
sx1509b_work_handler(struct k_work * work)221 static void sx1509b_work_handler(struct k_work *work)
222 {
223 struct sx1509b_drv_data *drv_data =
224 CONTAINER_OF(work, struct sx1509b_drv_data, work);
225
226 sx1509b_handle_interrupt(drv_data->dev);
227 }
228
sx1509_int_cb(const struct device * dev,struct gpio_callback * gpio_cb,uint32_t pins)229 static void sx1509_int_cb(const struct device *dev,
230 struct gpio_callback *gpio_cb,
231 uint32_t pins)
232 {
233 struct sx1509b_drv_data *drv_data = CONTAINER_OF(gpio_cb,
234 struct sx1509b_drv_data, gpio_cb);
235
236 ARG_UNUSED(pins);
237
238 k_work_submit(&drv_data->work);
239 }
240 #endif
241
write_pin_state(const struct sx1509b_config * cfg,struct sx1509b_drv_data * drv_data,struct sx1509b_pin_state * pins,bool data_first)242 static int write_pin_state(const struct sx1509b_config *cfg,
243 struct sx1509b_drv_data *drv_data,
244 struct sx1509b_pin_state *pins, bool data_first)
245 {
246 struct {
247 uint8_t reg;
248 struct sx1509b_pin_state pins;
249 } __packed pin_buf;
250 int rc;
251
252 pin_buf.reg = SX1509B_REG_INPUT_DISABLE;
253 pin_buf.pins.input_disable = sys_cpu_to_be16(pins->input_disable);
254 pin_buf.pins.long_slew = sys_cpu_to_be16(pins->long_slew);
255 pin_buf.pins.low_drive = sys_cpu_to_be16(pins->low_drive);
256 pin_buf.pins.pull_up = sys_cpu_to_be16(pins->pull_up);
257 pin_buf.pins.pull_down = sys_cpu_to_be16(pins->pull_down);
258 pin_buf.pins.open_drain = sys_cpu_to_be16(pins->open_drain);
259 pin_buf.pins.polarity = sys_cpu_to_be16(pins->polarity);
260 pin_buf.pins.dir = sys_cpu_to_be16(pins->dir);
261 pin_buf.pins.data = sys_cpu_to_be16(pins->data);
262
263 if (data_first) {
264 rc = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_DATA,
265 pins->data);
266 if (rc == 0) {
267 rc = i2c_write_dt(&cfg->bus, &pin_buf.reg,
268 sizeof(pin_buf) - sizeof(pins->data));
269 }
270 } else {
271 rc = i2c_write_dt(&cfg->bus, &pin_buf.reg, sizeof(pin_buf));
272 }
273
274 return rc;
275 }
276
sx1509b_config(const struct device * dev,gpio_pin_t pin,gpio_flags_t flags)277 static int sx1509b_config(const struct device *dev,
278 gpio_pin_t pin,
279 gpio_flags_t flags)
280 {
281 const struct sx1509b_config *cfg = dev->config;
282 struct sx1509b_drv_data *drv_data = dev->data;
283 struct sx1509b_pin_state *pins = &drv_data->pin_state;
284 struct sx1509b_debounce_state *debounce = &drv_data->debounce_state;
285 int rc = 0;
286 bool data_first = false;
287
288 /* Can't do I2C bus operations from an ISR */
289 if (k_is_in_isr()) {
290 return -EWOULDBLOCK;
291 }
292
293 k_sem_take(&drv_data->lock, K_FOREVER);
294
295 if (drv_data->led_drv_enable & BIT(pin)) {
296 /* Disable LED driver */
297 drv_data->led_drv_enable &= ~BIT(pin);
298 rc = i2c_reg_write_word_be(&cfg->bus,
299 SX1509B_REG_LED_DRV_ENABLE,
300 drv_data->led_drv_enable);
301
302 if (rc) {
303 goto out;
304 }
305 }
306
307 pins->open_drain &= ~BIT(pin);
308 if ((flags & GPIO_SINGLE_ENDED) != 0) {
309 if ((flags & GPIO_LINE_OPEN_DRAIN) != 0) {
310 pins->open_drain |= BIT(pin);
311 } else {
312 /* Open source not supported */
313 rc = -ENOTSUP;
314 goto out;
315 }
316 }
317
318 if ((flags & GPIO_PULL_UP) != 0) {
319 pins->pull_up |= BIT(pin);
320 } else {
321 pins->pull_up &= ~BIT(pin);
322 }
323 if ((flags & GPIO_PULL_DOWN) != 0) {
324 pins->pull_down |= BIT(pin);
325 } else {
326 pins->pull_down &= ~BIT(pin);
327 }
328
329 if ((flags & GPIO_INPUT) != 0) {
330 pins->input_disable &= ~BIT(pin);
331 } else {
332 pins->input_disable |= BIT(pin);
333 }
334
335 if ((flags & GPIO_OUTPUT) != 0) {
336 pins->dir &= ~BIT(pin);
337 if ((flags & GPIO_OUTPUT_INIT_LOW) != 0) {
338 pins->data &= ~BIT(pin);
339 data_first = true;
340 } else if ((flags & GPIO_OUTPUT_INIT_HIGH) != 0) {
341 pins->data |= BIT(pin);
342 data_first = true;
343 }
344 } else {
345 pins->dir |= BIT(pin);
346 }
347
348 if ((flags & SX1509B_GPIO_DEBOUNCE) != 0) {
349 debounce->debounce_enable |= BIT(pin);
350 } else {
351 debounce->debounce_enable &= ~BIT(pin);
352 }
353
354 LOG_DBG("CFG %u %x : ID %04x ; PU %04x ; PD %04x ; DIR %04x ; DAT %04x",
355 pin, flags,
356 pins->input_disable, pins->pull_up, pins->pull_down,
357 pins->dir, pins->data);
358
359 rc = write_pin_state(cfg, drv_data, pins, data_first);
360
361 if (rc == 0) {
362 struct {
363 uint8_t reg;
364 struct sx1509b_debounce_state debounce;
365 } __packed debounce_buf;
366
367 debounce_buf.reg = SX1509B_REG_DEBOUNCE_CONFIG;
368 debounce_buf.debounce.debounce_config
369 = debounce->debounce_config;
370 debounce_buf.debounce.debounce_enable
371 = sys_cpu_to_be16(debounce->debounce_enable);
372
373 rc = i2c_write_dt(&cfg->bus, &debounce_buf.reg,
374 sizeof(debounce_buf));
375 }
376
377 out:
378 k_sem_give(&drv_data->lock);
379 return rc;
380 }
381
port_get(const struct device * dev,gpio_port_value_t * value)382 static int port_get(const struct device *dev,
383 gpio_port_value_t *value)
384 {
385 const struct sx1509b_config *cfg = dev->config;
386 struct sx1509b_drv_data *drv_data = dev->data;
387 uint16_t pin_data;
388 int rc = 0;
389
390 /* Can't do I2C bus operations from an ISR */
391 if (k_is_in_isr()) {
392 return -EWOULDBLOCK;
393 }
394
395 k_sem_take(&drv_data->lock, K_FOREVER);
396
397 uint8_t cmd = SX1509B_REG_DATA;
398
399 rc = i2c_write_read_dt(&cfg->bus, &cmd, sizeof(cmd), &pin_data,
400 sizeof(pin_data));
401 LOG_DBG("read %04x got %d", sys_be16_to_cpu(pin_data), rc);
402 if (rc != 0) {
403 goto out;
404 }
405
406 *value = sys_be16_to_cpu(pin_data);
407
408 out:
409 k_sem_give(&drv_data->lock);
410 return rc;
411 }
412
port_write(const struct device * dev,gpio_port_pins_t mask,gpio_port_value_t value,gpio_port_value_t toggle)413 static int port_write(const struct device *dev,
414 gpio_port_pins_t mask,
415 gpio_port_value_t value,
416 gpio_port_value_t toggle)
417 {
418 /* Can't do I2C bus operations from an ISR */
419 if (k_is_in_isr()) {
420 return -EWOULDBLOCK;
421 }
422
423 const struct sx1509b_config *cfg = dev->config;
424 struct sx1509b_drv_data *drv_data = dev->data;
425 void *data = &drv_data->pin_state.data;
426 uint16_t *outp = data;
427
428 __ASSERT_NO_MSG(IS_PTR_ALIGNED(data, uint16_t));
429
430 k_sem_take(&drv_data->lock, K_FOREVER);
431
432 uint16_t orig_out = *outp;
433 uint16_t out = ((orig_out & ~mask) | (value & mask)) ^ toggle;
434 int rc = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_DATA, out);
435 if (rc == 0) {
436 *outp = out;
437 }
438
439 k_sem_give(&drv_data->lock);
440
441 LOG_DBG("write %04x msk %04x val %04x => %04x: %d", orig_out, mask, value, out, rc);
442
443 return rc;
444 }
445
port_set_masked(const struct device * dev,gpio_port_pins_t mask,gpio_port_value_t value)446 static int port_set_masked(const struct device *dev,
447 gpio_port_pins_t mask,
448 gpio_port_value_t value)
449 {
450 return port_write(dev, mask, value, 0);
451 }
452
port_set_bits(const struct device * dev,gpio_port_pins_t pins)453 static int port_set_bits(const struct device *dev,
454 gpio_port_pins_t pins)
455 {
456 return port_write(dev, pins, pins, 0);
457 }
458
port_clear_bits(const struct device * dev,gpio_port_pins_t pins)459 static int port_clear_bits(const struct device *dev,
460 gpio_port_pins_t pins)
461 {
462 return port_write(dev, pins, 0, 0);
463 }
464
port_toggle_bits(const struct device * dev,gpio_port_pins_t pins)465 static int port_toggle_bits(const struct device *dev,
466 gpio_port_pins_t pins)
467 {
468 return port_write(dev, 0, 0, pins);
469 }
470
471 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
pin_interrupt_configure(const struct device * dev,gpio_pin_t pin,enum gpio_int_mode mode,enum gpio_int_trig trig)472 static int pin_interrupt_configure(const struct device *dev,
473 gpio_pin_t pin,
474 enum gpio_int_mode mode,
475 enum gpio_int_trig trig)
476 {
477 int rc = 0;
478
479 /* Device does not support level-triggered interrupts. */
480 if (mode == GPIO_INT_MODE_LEVEL) {
481 return -ENOTSUP;
482 }
483
484 const struct sx1509b_config *cfg = dev->config;
485 struct sx1509b_drv_data *drv_data = dev->data;
486 struct sx1509b_irq_state *irq = &drv_data->irq_state;
487 struct {
488 uint8_t reg;
489 struct sx1509b_irq_state irq;
490 } __packed irq_buf;
491
492 /* Only level triggered interrupts are supported, and those
493 * only if interrupt support is enabled.
494 */
495 if (IS_ENABLED(CONFIG_GPIO_SX1509B_INTERRUPT)) {
496 if (mode == GPIO_INT_MODE_LEVEL) {
497 return -ENOTSUP;
498 }
499 } else if (mode != GPIO_INT_MODE_DISABLED) {
500 return -ENOTSUP;
501 }
502
503 k_sem_take(&drv_data->lock, K_FOREVER);
504
505 irq->interrupt_sense &= ~(SX1509B_EDGE_BOTH << (pin * 2));
506 if (mode == GPIO_INT_MODE_DISABLED) {
507 irq->interrupt_mask |= BIT(pin);
508 } else { /* GPIO_INT_MODE_EDGE */
509 irq->interrupt_mask &= ~BIT(pin);
510 if (trig == GPIO_INT_TRIG_BOTH) {
511 irq->interrupt_sense |= (SX1509B_EDGE_BOTH <<
512 (pin * 2));
513 } else if (trig == GPIO_INT_TRIG_LOW) {
514 irq->interrupt_sense |= (SX1509B_EDGE_FALLING <<
515 (pin * 2));
516 } else if (trig == GPIO_INT_TRIG_HIGH) {
517 irq->interrupt_sense |= (SX1509B_EDGE_RISING <<
518 (pin * 2));
519 }
520 }
521
522 irq_buf.reg = SX1509B_REG_INTERRUPT_MASK;
523 irq_buf.irq.interrupt_mask = sys_cpu_to_be16(irq->interrupt_mask);
524 irq_buf.irq.interrupt_sense = sys_cpu_to_be32(irq->interrupt_sense);
525
526 rc = i2c_write_dt(&cfg->bus, &irq_buf.reg, sizeof(irq_buf));
527
528 k_sem_give(&drv_data->lock);
529
530 return rc;
531 }
532 #endif /* CONFIG_GPIO_SX1509B_INTERRUPT */
533
534 /**
535 * @brief Initialization function of SX1509B
536 *
537 * @param dev Device struct
538 * @return 0 if successful, failed otherwise.
539 */
sx1509b_init(const struct device * dev)540 static int sx1509b_init(const struct device *dev)
541 {
542 const struct sx1509b_config *cfg = dev->config;
543 struct sx1509b_drv_data *drv_data = dev->data;
544 int rc;
545
546 if (!device_is_ready(cfg->bus.bus)) {
547 LOG_ERR("I2C bus not ready");
548 rc = -ENODEV;
549 goto out;
550 }
551
552 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
553 drv_data->dev = dev;
554
555 if (!gpio_is_ready_dt(&cfg->nint_gpio)) {
556 rc = -ENODEV;
557 goto out;
558 }
559 k_work_init(&drv_data->work, sx1509b_work_handler);
560
561 gpio_pin_configure_dt(&cfg->nint_gpio, GPIO_INPUT);
562 gpio_pin_interrupt_configure_dt(&cfg->nint_gpio,
563 GPIO_INT_EDGE_TO_ACTIVE);
564
565 gpio_init_callback(&drv_data->gpio_cb, sx1509_int_cb,
566 BIT(cfg->nint_gpio.pin));
567 gpio_add_callback(cfg->nint_gpio.port, &drv_data->gpio_cb);
568
569 drv_data->irq_state = (struct sx1509b_irq_state) {
570 .interrupt_mask = ALL_PINS,
571 };
572 #endif
573
574 rc = i2c_reg_write_byte_dt(&cfg->bus, SX1509B_REG_RESET,
575 SX1509B_REG_RESET_MAGIC0);
576 if (rc != 0) {
577 LOG_ERR("%s: reset m0 failed: %d\n", dev->name, rc);
578 goto out;
579 }
580 rc = i2c_reg_write_byte_dt(&cfg->bus, SX1509B_REG_RESET,
581 SX1509B_REG_RESET_MAGIC1);
582 if (rc != 0) {
583 goto out;
584 }
585
586 k_sleep(K_MSEC(RESET_DELAY_MS));
587
588 /* Reset state mediated by initial configuration */
589 drv_data->pin_state = (struct sx1509b_pin_state) {
590 .dir = (ALL_PINS
591 & ~(DT_INST_PROP(0, init_out_low)
592 | DT_INST_PROP(0, init_out_high))),
593 .data = (ALL_PINS
594 & ~DT_INST_PROP(0, init_out_low)),
595 };
596 drv_data->debounce_state = (struct sx1509b_debounce_state) {
597 .debounce_config = CONFIG_GPIO_SX1509B_DEBOUNCE_TIME,
598 };
599
600 rc = i2c_reg_write_byte_dt(&cfg->bus, SX1509B_REG_CLOCK,
601 SX1509B_REG_CLOCK_FOSC_INT_2MHZ);
602 if (rc == 0) {
603 rc = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_DATA,
604 drv_data->pin_state.data);
605 }
606 if (rc == 0) {
607 rc = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_DIR,
608 drv_data->pin_state.dir);
609 }
610 if (rc == 0) {
611 rc = i2c_reg_write_byte_be(&cfg->bus, SX1509B_REG_MISC,
612 SX1509B_REG_MISC_LOG_A |
613 SX1509B_REG_MISC_LOG_B |
614 SX1509B_REG_MISC_FREQ);
615 }
616
617 out:
618 if (rc != 0) {
619 LOG_ERR("%s init failed: %d", dev->name, rc);
620 } else {
621 LOG_INF("%s init ok", dev->name);
622 }
623 k_sem_give(&drv_data->lock);
624 return rc;
625 }
626
627 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
gpio_sx1509b_manage_callback(const struct device * dev,struct gpio_callback * callback,bool set)628 static int gpio_sx1509b_manage_callback(const struct device *dev,
629 struct gpio_callback *callback,
630 bool set)
631 {
632 struct sx1509b_drv_data *data = dev->data;
633
634 return gpio_manage_callback(&data->cb, callback, set);
635 }
636 #endif
637
638 static const struct gpio_driver_api api_table = {
639 .pin_configure = sx1509b_config,
640 .port_get_raw = port_get,
641 .port_set_masked_raw = port_set_masked,
642 .port_set_bits_raw = port_set_bits,
643 .port_clear_bits_raw = port_clear_bits,
644 .port_toggle_bits = port_toggle_bits,
645 #ifdef CONFIG_GPIO_SX1509B_INTERRUPT
646 .pin_interrupt_configure = pin_interrupt_configure,
647 .manage_callback = gpio_sx1509b_manage_callback,
648 #endif
649 };
650
sx1509b_led_intensity_pin_configure(const struct device * dev,gpio_pin_t pin)651 int sx1509b_led_intensity_pin_configure(const struct device *dev,
652 gpio_pin_t pin)
653 {
654 const struct sx1509b_config *cfg = dev->config;
655 struct sx1509b_drv_data *drv_data = dev->data;
656 struct sx1509b_pin_state *pins = &drv_data->pin_state;
657 int rc;
658
659 /* Can't do I2C bus operations from an ISR */
660 if (k_is_in_isr()) {
661 return -EWOULDBLOCK;
662 }
663
664 if (pin >= ARRAY_SIZE(intensity_registers)) {
665 return -ERANGE;
666 }
667
668 k_sem_take(&drv_data->lock, K_FOREVER);
669
670 /* Enable LED driver */
671 drv_data->led_drv_enable |= BIT(pin);
672 rc = i2c_reg_write_word_be(&cfg->bus, SX1509B_REG_LED_DRV_ENABLE,
673 drv_data->led_drv_enable);
674
675 /* Set intensity to 0 */
676 if (rc == 0) {
677 rc = i2c_reg_write_byte_be(&cfg->bus, intensity_registers[pin], 0);
678 } else {
679 goto out;
680 }
681
682 pins->input_disable |= BIT(pin);
683 pins->pull_up &= ~BIT(pin);
684 pins->dir &= ~BIT(pin);
685 pins->data &= ~BIT(pin);
686
687 if (rc == 0) {
688 rc = write_pin_state(cfg, drv_data, pins, false);
689 }
690
691 out:
692 k_sem_give(&drv_data->lock);
693 return rc;
694 }
695
sx1509b_led_intensity_pin_set(const struct device * dev,gpio_pin_t pin,uint8_t intensity_val)696 int sx1509b_led_intensity_pin_set(const struct device *dev, gpio_pin_t pin,
697 uint8_t intensity_val)
698 {
699 const struct sx1509b_config *cfg = dev->config;
700 struct sx1509b_drv_data *drv_data = dev->data;
701 int rc;
702
703 /* Can't do I2C bus operations from an ISR */
704 if (k_is_in_isr()) {
705 return -EWOULDBLOCK;
706 }
707
708 if (pin >= ARRAY_SIZE(intensity_registers)) {
709 return -ERANGE;
710 }
711
712 k_sem_take(&drv_data->lock, K_FOREVER);
713
714 rc = i2c_reg_write_byte_be(&cfg->bus, intensity_registers[pin],
715 intensity_val);
716
717 k_sem_give(&drv_data->lock);
718
719 return rc;
720 }
721
722 #define GPIO_SX1509B_DEFINE(inst) \
723 static const struct sx1509b_config sx1509b_cfg##inst = { \
724 .common = { \
725 .port_pin_mask = GPIO_PORT_PIN_MASK_FROM_DT_INST(inst),\
726 }, \
727 .bus = I2C_DT_SPEC_INST_GET(inst), \
728 IF_ENABLED(CONFIG_GPIO_SX1509B_INTERRUPT, \
729 (GPIO_DT_SPEC_INST_GET(inst, nint_gpios))) \
730 }; \
731 \
732 static struct sx1509b_drv_data sx1509b_drvdata##inst = { \
733 .lock = Z_SEM_INITIALIZER(sx1509b_drvdata##inst.lock, 1, 1), \
734 }; \
735 \
736 DEVICE_DT_INST_DEFINE(inst, sx1509b_init, NULL, &sx1509b_drvdata##inst,\
737 &sx1509b_cfg##inst, POST_KERNEL, \
738 CONFIG_GPIO_SX1509B_INIT_PRIORITY, &api_table);
739
740 DT_INST_FOREACH_STATUS_OKAY(GPIO_SX1509B_DEFINE)
741