diff --git a/drivers/gpio/CMakeLists.txt b/drivers/gpio/CMakeLists.txt index cd441db164e5fe..1f2947184af1fa 100644 --- a/drivers/gpio/CMakeLists.txt +++ b/drivers/gpio/CMakeLists.txt @@ -34,6 +34,7 @@ zephyr_library_sources_ifdef(CONFIG_GPIO_IMX gpio_imx.c) zephyr_library_sources_ifdef(CONFIG_GPIO_INFINEON_CAT1 gpio_ifx_cat1.c) zephyr_library_sources_ifdef(CONFIG_GPIO_INTEL gpio_intel.c) zephyr_library_sources_ifdef(CONFIG_GPIO_IPROC gpio_iproc.c) +zephyr_library_sources_ifdef(CONFIG_GPIO_ITE_IT8801 gpio_ite_it8801.c) zephyr_library_sources_ifdef(CONFIG_GPIO_ITE_IT8XXX2 gpio_ite_it8xxx2.c) zephyr_library_sources_ifdef(CONFIG_GPIO_ITE_IT8XXX2_V2 gpio_ite_it8xxx2_v2.c) zephyr_library_sources_ifdef(CONFIG_GPIO_KSCAN_ITE_IT8XXX2 gpio_kscan_ite_it8xxx2.c) diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig index 90cad25cebe96a..0f61746543dfb7 100644 --- a/drivers/gpio/Kconfig +++ b/drivers/gpio/Kconfig @@ -127,6 +127,7 @@ source "drivers/gpio/Kconfig.ifx_cat1" source "drivers/gpio/Kconfig.imx" source "drivers/gpio/Kconfig.intel" source "drivers/gpio/Kconfig.iproc" +source "drivers/gpio/Kconfig.it8801" source "drivers/gpio/Kconfig.it8xxx2" source "drivers/gpio/Kconfig.litex" source "drivers/gpio/Kconfig.lmp90xxx" diff --git a/drivers/gpio/Kconfig.it8801 b/drivers/gpio/Kconfig.it8801 new file mode 100644 index 00000000000000..70252ea90d4ce1 --- /dev/null +++ b/drivers/gpio/Kconfig.it8801 @@ -0,0 +1,22 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +config GPIO_ITE_IT8801 + bool "ITE IT8801 GPIO device driver" + default y + depends on DT_HAS_ITE_IT8801_GPIO_ENABLED + select I2C + select MFD + help + Enable driver for ITE IT8801 I2C-based GPIO. + +if GPIO_ITE_IT8801 + +config GPIO_IT8801_INIT_PRIORITY + int "IT8801 GPIO port init priority" + default 85 + help + IT8801 GPIO port device driver initialization priority. The priority + must be lower than MFD_INIT_PRIORITY device. + +endif # GPIO_ITE_IT8801 diff --git a/drivers/gpio/gpio_ite_it8801.c b/drivers/gpio/gpio_ite_it8801.c new file mode 100644 index 00000000000000..4eee2f6a74b74f --- /dev/null +++ b/drivers/gpio/gpio_ite_it8801.c @@ -0,0 +1,486 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT ite_it8801_gpio + +#include +#include +#include +#include +#include +#include + +#include +LOG_MODULE_REGISTER(gpio_ite_it8801, CONFIG_GPIO_LOG_LEVEL); + +struct gpio_it8801_config { + /* gpio_driver_config needs to be first */ + struct gpio_driver_config common; + /* IT8801 controller dev */ + const struct device *mfd; + /* I2C device for the MFD parent */ + const struct i2c_dt_spec i2c_dev; + /* GPIO input pin status register */ + uint8_t reg_ipsr; + /* GPIO set output value register */ + uint8_t reg_sovr; + /* GPIO control register */ + uint8_t reg_gpcr; + /* GPIO interrupt status register */ + uint8_t reg_gpisr; + /* GPIO interrupt enable register */ + uint8_t reg_gpier; + uint8_t pin_mask; +}; + +struct gpio_it8801_data { + struct gpio_driver_data common; + const struct device *gpio_dev; + sys_slist_t callbacks; + uint8_t level_high_trig; + uint8_t level_low_trig; +}; + +static int ioex_check_is_not_valid(const struct device *dev, gpio_pin_t pin) +{ + const struct gpio_it8801_config *config = dev->config; + int ret = 0; + + if (BIT(pin) & ~(config->pin_mask)) { + LOG_ERR("GPIO port%d-%d is not support", config->reg_ipsr, pin); + return -ENOTSUP; + } + + return ret; +} + +static int gpio_it8801_configure(const struct device *dev, gpio_pin_t pin, gpio_flags_t flags) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + uint8_t reg_gpcr = config->reg_gpcr + pin; + uint8_t mask = BIT(pin); + uint8_t new_value = 0, control; + + /* Don't support "open source" mode */ + if (((flags & GPIO_SINGLE_ENDED) != 0) && ((flags & GPIO_LINE_OPEN_DRAIN) == 0)) { + return -ENOTSUP; + } + + if (ioex_check_is_not_valid(dev, pin)) { + return -ENOTSUP; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, reg_gpcr, &control); + if (ret) { + LOG_ERR("Failed to read control value (ret %d)", ret); + return ret; + } + + if (flags == GPIO_DISCONNECTED) { + control &= ~(IT8801_GPIODIR | IT8801_GPIOPDE | IT8801_GPIOPUE); + + goto write_and_return; + } + + /* If output, set level before changing type to an output. */ + if (flags & GPIO_OUTPUT) { + if (flags & GPIO_OUTPUT_INIT_HIGH) { + new_value = mask; + } else if (flags & GPIO_OUTPUT_INIT_LOW) { + new_value = 0; + } + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_sovr, mask, new_value); + if (ret) { + LOG_ERR("Failed to set output value (ret %d)", ret); + return ret; + } + /* Set output */ + control |= IT8801_GPIODIR; + /* Select open drain 0:push-pull 1:open-drain */ + if (flags & GPIO_OPEN_DRAIN) { + control |= IT8801_GPIOIOT_OD; + } else { + control &= ~IT8801_GPIOIOT_OD; + } + } else { + /* Set input */ + control &= ~IT8801_GPIODIR; + } + + /* Handle pullup / pulldown */ + if (flags & GPIO_PULL_UP) { + control = (control | IT8801_GPIOPUE) & ~IT8801_GPIOPDE; + } else if (flags & GPIO_PULL_DOWN) { + control = (control | IT8801_GPIOPDE) & ~IT8801_GPIOPUE; + } else { + /* No pull up/down */ + control &= ~(IT8801_GPIOPUE | IT8801_GPIOPDE); + } + +write_and_return: + /* Set GPIO control */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, reg_gpcr, control); + if (ret) { + LOG_ERR("Failed to set control value (ret %d)", ret); + return ret; + } + + return ret; +} + +#ifdef CONFIG_GPIO_GET_CONFIG +static int gpio_it8801_get_config(const struct device *dev, gpio_pin_t pin, gpio_flags_t *out_flags) +{ + const struct gpio_it8801_config *config = dev->config; + gpio_flags_t flags = 0; + int ret; + uint8_t reg_gpcr = config->reg_gpcr + pin; + uint8_t mask = BIT(pin); + uint8_t control, value; + + if (ioex_check_is_not_valid(dev, pin)) { + return -ENOTSUP; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, reg_gpcr, &control); + if (ret) { + LOG_ERR("Failed to read control value (ret %d)", ret); + return ret; + } + + /* Get GPIO direction */ + if (control & IT8801_GPIODIR) { + flags |= GPIO_OUTPUT; + + /* Get GPIO type, 0:push-pull 1:open-drain */ + if (control & IT8801_GPIOIOT_OD) { + flags |= GPIO_OPEN_DRAIN; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_ipsr, &value); + if (ret) { + LOG_ERR("Failed to read pin status (ret %d)", ret); + return ret; + } + + /* Get GPIO output level */ + if (value & mask) { + flags |= GPIO_OUTPUT_HIGH; + } else { + flags |= GPIO_OUTPUT_LOW; + } + } else { + flags |= GPIO_INPUT; + } + + /* pullup / pulldown */ + if (control & IT8801_GPIOPUE) { + flags |= GPIO_PULL_UP; + } else if (control & IT8801_GPIOPDE) { + flags |= GPIO_PULL_DOWN; + } + + *out_flags = flags; + + return 0; +} +#endif + +static int gpio_it8801_port_get_raw(const struct device *dev, gpio_port_value_t *value) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + uint8_t val; + + /* Get raw bits of GPIO mirror register */ + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_ipsr, &val); + if (ret) { + LOG_ERR("Failed to get port mask (ret %d)", ret); + return ret; + } + + *value = val; + + return ret; +} + +static int gpio_it8801_port_set_masked_raw(const struct device *dev, gpio_port_pins_t mask, + gpio_port_value_t value) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_sovr, mask, value); + if (ret) { + LOG_ERR("Failed to set port mask (ret %d)", ret); + return ret; + } + + return ret; +} + +static int gpio_it8801_port_set_bits_raw(const struct device *dev, gpio_port_pins_t pins) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + + /* Set raw bits of GPIO data register */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_sovr, pins, pins); + if (ret) { + LOG_ERR("Failed to set bits raw (ret %d)", ret); + return ret; + } + + return ret; +} + +static int gpio_it8801_port_clear_bits_raw(const struct device *dev, gpio_port_pins_t pins) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + + /* Clear raw bits of GPIO data register */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_sovr, pins, 0); + if (ret) { + LOG_ERR("Failed to clear bits raw (ret %d)", ret); + return ret; + } + + return ret; +} + +static int gpio_it8801_port_toggle_bits(const struct device *dev, gpio_port_pins_t pins) +{ + const struct gpio_it8801_config *config = dev->config; + int ret; + uint8_t val, new_val; + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_sovr, &val); + if (ret) { + return ret; + } + /* Toggle raw bits of GPIO data register */ + new_val = val ^ pins; + if (new_val != val) { + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_sovr, new_val); + if (ret) { + LOG_ERR("Failed to write toggle value (ret %d)", ret); + return ret; + } + } + + return ret; +} + +static int gpio_it8801_manage_callback(const struct device *dev, struct gpio_callback *callback, + bool set) +{ + struct gpio_it8801_data *data = dev->data; + int rc; + + rc = gpio_manage_callback(&data->callbacks, callback, set); + + return rc; +} + +void it8801_gpio_alert_handler(const struct device *dev) +{ + const struct gpio_it8801_config *config = dev->config; + struct gpio_it8801_data *data = dev->data; + int ret; + gpio_port_value_t value; + gpio_port_value_t interrupted_pins_level = 0; + uint8_t isr_val, ier_val; + + /* + * When the irq_gpios of the mfd is triggered, if the passed dev + * does not match the dev stored in the data struct of GPIO, + * further execution will be halted. + */ + if (dev != data->gpio_dev) { + return; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_gpisr, &isr_val); + if (ret) { + LOG_ERR("Failed to read GPIO interrupt status (ret %d)", ret); + return; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_gpier, &ier_val); + if (ret) { + LOG_ERR("Failed to read GPIO interrupt pin set (ret %d)", ret); + return; + } + + gpio_it8801_port_get_raw(dev, &value); + interrupted_pins_level |= (value & data->level_high_trig); + interrupted_pins_level |= ((~value) & data->level_low_trig); + + if ((isr_val & ier_val) || interrupted_pins_level) { + /* Clear pending interrupt */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_gpisr, isr_val); + if (ret) { + LOG_ERR("Failed to clear GPIO interrupt (ret %d)", ret); + return; + } + + gpio_fire_callbacks(&data->callbacks, dev, isr_val); + /* Level trigger handler again */ + it8801_gpio_alert_handler(dev); + } +} + +static int gpio_it8801_pin_interrupt_configure(const struct device *dev, gpio_pin_t pin, + enum gpio_int_mode mode, enum gpio_int_trig trig) +{ + const struct gpio_it8801_config *config = dev->config; + struct gpio_it8801_data *data = dev->data; + int ret; + uint8_t reg_gpcr = config->reg_gpcr + pin; + uint8_t new_value = 0, control; + uint8_t mask = BIT(pin); + + if (ioex_check_is_not_valid(dev, pin)) { + return -ENOTSUP; + } + + /* Disable irq before configuring it */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_gpier, mask, new_value); + if (ret) { + LOG_ERR("Failed to disable irq (ret %d)", ret); + return ret; + } + + if (mode == GPIO_INT_MODE_DISABLED) { + data->level_high_trig &= ~BIT(pin); + data->level_low_trig &= ~BIT(pin); + + return ret; + } + + /* Set input pin */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, reg_gpcr, IT8801_GPIODIR, 0); + if (ret) { + LOG_ERR("Failed to set input pin (ret %d)", ret); + return ret; + } + + /* Clear trigger type */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, reg_gpcr, GENMASK(4, 3), 0); + if (ret) { + LOG_ERR("Failed to clear trigger type (ret %d)", ret); + return ret; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, reg_gpcr, &control); + if (ret) { + LOG_ERR("Failed to read gpio control (ret %d)", ret); + return ret; + } + + if (mode == GPIO_INT_MODE_EDGE) { + /* Set edge trigger */ + if ((trig & GPIO_INT_TRIG_BOTH) == GPIO_INT_TRIG_BOTH) { + control |= IT8801_GPIOIOT_INT_FALL | IT8801_GPIOIOT_INT_RISE; + } else if (trig & GPIO_INT_TRIG_LOW) { + control |= IT8801_GPIOIOT_INT_FALL; + } else if (trig & GPIO_INT_TRIG_HIGH) { + control |= IT8801_GPIOIOT_INT_RISE; + } else { + LOG_ERR("Invalid interrupt trigger type %d", trig); + return -EINVAL; + } + } else if (mode == GPIO_INT_MODE_LEVEL) { + /* Set level trigger */ + if (trig & GPIO_INT_TRIG_LOW) { + control &= ~IT8801_GPIOPOL; + data->level_low_trig |= BIT(pin); + data->level_high_trig &= ~BIT(pin); + } else { + control |= IT8801_GPIOPOL; + data->level_high_trig |= BIT(pin); + data->level_low_trig &= ~BIT(pin); + } + } + + /* Set control value */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, reg_gpcr, control); + if (ret) { + LOG_ERR("Failed to write trigger state (ret %d)", ret); + return ret; + } + + /* Clear pending interrupt */ + new_value = mask; + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_gpisr, mask, new_value); + if (ret) { + LOG_ERR("Failed to clear pending interrupt (ret %d)", ret); + return ret; + } + + /* Enable GPIO interrupt */ + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_gpier, mask, new_value); + if (ret) { + LOG_ERR("Failed to enable interrupt (ret %d)", ret); + return ret; + } + + /* Gather GPIO interrupt enable */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, IT8801_REG_GIECR, IT8801_REG_MASK_GGPIOIE); + + return ret; +} + +static const struct gpio_driver_api gpio_it8801_driver_api = { + .pin_configure = gpio_it8801_configure, +#ifdef CONFIG_GPIO_GET_CONFIG + .pin_get_config = gpio_it8801_get_config, +#endif + .port_get_raw = gpio_it8801_port_get_raw, + .port_set_masked_raw = gpio_it8801_port_set_masked_raw, + .port_set_bits_raw = gpio_it8801_port_set_bits_raw, + .port_clear_bits_raw = gpio_it8801_port_clear_bits_raw, + .port_toggle_bits = gpio_it8801_port_toggle_bits, + .pin_interrupt_configure = gpio_it8801_pin_interrupt_configure, + .manage_callback = gpio_it8801_manage_callback, +}; + +static int gpio_it8801_init(const struct device *dev) +{ + const struct gpio_it8801_config *config = dev->config; + struct gpio_it8801_data *data = dev->data; + + /* Verify multi-function parent is ready */ + if (!device_is_ready(config->mfd)) { + LOG_ERR("(gpio)%s is not ready", config->mfd->name); + return -ENODEV; + } + + data->gpio_dev = dev; + + return 0; +} + +#define GPIO_IT8801_DEVICE_INST(inst) \ + static struct gpio_it8801_data gpio_it8801_data_##inst; \ + static const struct gpio_it8801_config gpio_it8801_cfg_##inst = { \ + .common = {.port_pin_mask = GPIO_PORT_PIN_MASK_FROM_DT_INST(inst)}, \ + .mfd = DEVICE_DT_GET(DT_INST_PARENT(inst)), \ + .i2c_dev = I2C_DT_SPEC_GET(DT_INST_PARENT(inst)), \ + .reg_ipsr = DT_INST_REG_ADDR_BY_IDX(inst, 0), \ + .reg_sovr = DT_INST_REG_ADDR_BY_IDX(inst, 1), \ + .reg_gpcr = DT_INST_REG_ADDR_BY_IDX(inst, 2), \ + .reg_gpisr = DT_INST_REG_ADDR_BY_IDX(inst, 3), \ + .reg_gpier = DT_INST_REG_ADDR_BY_IDX(inst, 4), \ + .pin_mask = DT_INST_PROP(inst, pin_mask), \ + }; \ + DEVICE_DT_INST_DEFINE(inst, gpio_it8801_init, NULL, &gpio_it8801_data_##inst, \ + &gpio_it8801_cfg_##inst, POST_KERNEL, \ + CONFIG_GPIO_IT8801_INIT_PRIORITY, &gpio_it8801_driver_api); + +DT_INST_FOREACH_STATUS_OKAY(GPIO_IT8801_DEVICE_INST) diff --git a/drivers/input/CMakeLists.txt b/drivers/input/CMakeLists.txt index aa1f843476288c..765974422c16e7 100644 --- a/drivers/input/CMakeLists.txt +++ b/drivers/input/CMakeLists.txt @@ -17,6 +17,7 @@ zephyr_library_sources_ifdef(CONFIG_INPUT_GPIO_KBD_MATRIX input_gpio_kbd_matrix. zephyr_library_sources_ifdef(CONFIG_INPUT_GPIO_KEYS input_gpio_keys.c) zephyr_library_sources_ifdef(CONFIG_INPUT_GPIO_QDEC input_gpio_qdec.c) zephyr_library_sources_ifdef(CONFIG_INPUT_GT911 input_gt911.c) +zephyr_library_sources_ifdef(CONFIG_INPUT_ITE_IT8801_KBD input_ite_it8801_kbd.c) zephyr_library_sources_ifdef(CONFIG_INPUT_ITE_IT8XXX2_KBD input_ite_it8xxx2_kbd.c) zephyr_library_sources_ifdef(CONFIG_INPUT_KBD_MATRIX input_kbd_matrix.c) zephyr_library_sources_ifdef(CONFIG_INPUT_NPCX_KBD input_npcx_kbd.c) diff --git a/drivers/input/Kconfig b/drivers/input/Kconfig index e76d3fc6fc76bd..abb0d4c2e266b6 100644 --- a/drivers/input/Kconfig +++ b/drivers/input/Kconfig @@ -19,6 +19,7 @@ source "drivers/input/Kconfig.gpio_kbd_matrix" source "drivers/input/Kconfig.gpio_keys" source "drivers/input/Kconfig.gpio_qdec" source "drivers/input/Kconfig.gt911" +source "drivers/input/Kconfig.it8801" source "drivers/input/Kconfig.it8xxx2" source "drivers/input/Kconfig.kbd_matrix" source "drivers/input/Kconfig.npcx" diff --git a/drivers/input/Kconfig.it8801 b/drivers/input/Kconfig.it8801 new file mode 100644 index 00000000000000..eb88ce65c0eca6 --- /dev/null +++ b/drivers/input/Kconfig.it8801 @@ -0,0 +1,14 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +config INPUT_ITE_IT8801_KBD + bool "ITE IT8801 keyboard matrix scan controller" + default y + depends on DT_HAS_ITE_IT8801_KBD_ENABLED + select I2C + select INPUT_KBD_MATRIX + select MFD + help + Enable driver for ITE IT8801 I2C-based keyboard matrix scan. + IT8801 support 8 KSI pins and 19 KSO pins [22:11] [6:0], + KSO[22:18]can be configured to GPIO mode. diff --git a/drivers/input/input_ite_it8801_kbd.c b/drivers/input/input_ite_it8801_kbd.c new file mode 100644 index 00000000000000..9756955d0d0a6e --- /dev/null +++ b/drivers/input/input_ite_it8801_kbd.c @@ -0,0 +1,227 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT ite_it8801_kbd + +#include +#include +#include +#include +#include +#include + +#include +LOG_MODULE_REGISTER(input_ite_it8801_kbd, CONFIG_INPUT_LOG_LEVEL); + +struct it8801_mfd_input_altctrl_cfg { + /* GPIO control device structure */ + const struct device *gpiocr; + /* GPIO control pin */ + uint8_t pin; + /* GPIO function select */ + uint8_t alt_func; +}; + +struct kbd_it8801_config { + struct input_kbd_matrix_common_config common; + /* IT8801 controller dev */ + const struct device *mfd; + /* KSO alternate configuration */ + const struct it8801_mfd_input_altctrl_cfg *altctrl; + /* I2C device for the MFD parent */ + const struct i2c_dt_spec i2c_dev; + int mfdctrl_len; + uint8_t kso_mapping[DT_INST_PROP(0, col_size)]; + /* Keyboard scan out mode control register */ + uint8_t reg_ksomcr; + /* Keyboard scan in data register */ + uint8_t reg_ksidr; + /* Keyboard scan in edge event register */ + uint8_t reg_ksieer; + /* Keyboard scan in interrupt enable register */ + uint8_t reg_ksiier; +}; + +struct kbd_it8801_data { + struct input_kbd_matrix_common_data common; + const struct device *kbd_dev; +}; + +INPUT_KBD_STRUCT_CHECK(struct kbd_it8801_config, struct kbd_it8801_data); + +static void kbd_it8801_drive_column(const struct device *dev, int col) +{ + const struct kbd_it8801_config *config = dev->config; + int ret; + uint8_t kso_val; + + /* Tri-state all outputs */ + if (col == INPUT_KBD_MATRIX_COLUMN_DRIVE_NONE) { + /* KSO[22:11, 6:0] output high */ + kso_val = IT8801_REG_MASK_KSOSDIC | IT8801_REG_MASK_AKSOSC; + } + /* Assert all outputs */ + else if (col == INPUT_KBD_MATRIX_COLUMN_DRIVE_ALL) { + /* KSO[22:11, 6:0] output low */ + kso_val = IT8801_REG_MASK_AKSOSC; + } else { + /* + * Selected KSO[22:11, 6:0] output low, + * all others KSO output high + */ + kso_val = config->kso_mapping[col]; + } + + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksomcr, kso_val); + if (ret != 0) { + LOG_ERR("Failed to drive column (ret %d)", ret); + return; + } +} + +static kbd_row_t kbd_it8801_read_row(const struct device *dev) +{ + const struct kbd_it8801_config *const config = dev->config; + int ret; + uint8_t value; + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_ksidr, &value); + if (ret != 0) { + LOG_ERR("Failed to read row (ret %d)", ret); + } + + /* Bits are active-low, so invert returned levels */ + return (~value) & 0xff; +} + +void it8801_input_alert_handler(const struct device *dev) +{ + const struct kbd_it8801_config *const config = dev->config; + struct kbd_it8801_data *data = dev->data; + int ret; + uint8_t ksieer_val; + + /* + * When the irq_gpios of the mfd is triggered, if the passed dev + * does not match the dev stored in the data struct of GPIO, + * further execution will be halted. + */ + if (dev != data->kbd_dev) { + return; + } + + ret = i2c_reg_read_byte_dt(&config->i2c_dev, config->reg_ksieer, &ksieer_val); + if (ret != 0) { + LOG_ERR("Failed to read KBD interrupt status (ret %d)", ret); + } + + if (ksieer_val != 0) { + /* Clear pending interrupts */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksieer, GENMASK(7, 0)); + if (ret != 0) { + LOG_ERR("Failed to clear pending interrupts (ret %d)", ret); + } + + input_kbd_matrix_poll_start(data->kbd_dev); + } +} + +static void kbd_it8801_set_detect_mode(const struct device *dev, bool enable) +{ + const struct kbd_it8801_config *const config = dev->config; + int ret; + + if (enable) { + /* Clear pending interrupts */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksieer, GENMASK(7, 0)); + /* Enable KSI falling edge event trigger interrupt */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksiier, GENMASK(7, 0)); + } else { + /* Disable KSI falling edge event trigger interrupt */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksiier, 0x00); + } + + if (ret != 0) { + LOG_ERR("Failed to set detect mode (ret %d)", ret); + return; + } +} + +static int kbd_it8801_init(const struct device *dev) +{ + const struct kbd_it8801_config *const config = dev->config; + struct kbd_it8801_data *data = dev->data; + int ret, status; + + /* Verify multi-function parent is ready */ + if (!device_is_ready(config->mfd)) { + LOG_ERR("(input)%s is not ready", config->mfd->name); + return -ENODEV; + } + + data->kbd_dev = dev; + + for (int i = 0; i < config->mfdctrl_len; i++) { + /* Switching the pin to KSO alternate function (KSO[21:18]) */ + status = mfd_it8801_configure_pins(&config->i2c_dev, config->altctrl[i].gpiocr, + config->altctrl[i].pin, + config->altctrl[i].alt_func); + if (status != 0) { + LOG_ERR("Failed to configure KSO[21:18] pins"); + return status; + } + } + + /* Disable wakeup and interrupt of KSI pins before configuring */ + kbd_it8801_set_detect_mode(dev, false); + + /* Start with KEYBOARD_COLUMN_ALL, KSO[22:11, 6:0] output low */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_ksomcr, IT8801_REG_MASK_AKSOSC); + /* Gather KSI interrupt enable */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, IT8801_REG_GIECR, IT8801_REG_MASK_GKSIIE); + /* Alert response enable */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, IT8801_REG_SMBCR, IT8801_REG_MASK_ARE); + if (ret != 0) { + LOG_ERR("Failed to initialization setting (ret %d)", ret); + return ret; + } + + return input_kbd_matrix_common_init(dev); +} + +static const struct input_kbd_matrix_api kbd_it8801_api = { + .drive_column = kbd_it8801_drive_column, + .read_row = kbd_it8801_read_row, + .set_detect_mode = kbd_it8801_set_detect_mode, +}; + +#define INPUT_IT8801_INIT(inst) \ + INPUT_KBD_MATRIX_DT_INST_DEFINE(inst); \ + PM_DEVICE_DT_INST_DEFINE(inst, input_kbd_matrix_pm_action); \ + static const struct it8801_mfd_input_altctrl_cfg \ + it8801_input_altctrl##inst[IT8801_DT_INST_MFDCTRL_LEN(inst)] = \ + IT8801_DT_MFD_ITEMS_LIST(inst); \ + static struct kbd_it8801_data kbd_it8801_data_##inst; \ + static const struct kbd_it8801_config kbd_it8801_cfg_##inst = { \ + .common = INPUT_KBD_MATRIX_DT_INST_COMMON_CONFIG_INIT(inst, &kbd_it8801_api), \ + .mfd = DEVICE_DT_GET(DT_INST_PARENT(inst)), \ + .i2c_dev = I2C_DT_SPEC_GET(DT_INST_PARENT(inst)), \ + .altctrl = it8801_input_altctrl##inst, \ + .mfdctrl_len = IT8801_DT_INST_MFDCTRL_LEN(inst), \ + .kso_mapping = DT_INST_PROP(inst, kso_mapping), \ + .reg_ksomcr = DT_INST_REG_ADDR_BY_IDX(inst, 0), \ + .reg_ksidr = DT_INST_REG_ADDR_BY_IDX(inst, 1), \ + .reg_ksieer = DT_INST_REG_ADDR_BY_IDX(inst, 2), \ + .reg_ksiier = DT_INST_REG_ADDR_BY_IDX(inst, 3), \ + }; \ + \ + DEVICE_DT_INST_DEFINE(inst, &kbd_it8801_init, PM_DEVICE_DT_INST_GET(inst), \ + &kbd_it8801_data_##inst, &kbd_it8801_cfg_##inst, POST_KERNEL, \ + CONFIG_INPUT_INIT_PRIORITY, NULL); \ + BUILD_ASSERT(IN_RANGE(DT_INST_PROP(inst, row_size), 1, 8), "invalid row-size"); \ + BUILD_ASSERT(IN_RANGE(DT_INST_PROP(inst, col_size), 1, 19), "invalid col-size"); + +DT_INST_FOREACH_STATUS_OKAY(INPUT_IT8801_INIT) diff --git a/drivers/mfd/CMakeLists.txt b/drivers/mfd/CMakeLists.txt index fa6ab5ddceda01..bc4d37cbd22c50 100644 --- a/drivers/mfd/CMakeLists.txt +++ b/drivers/mfd/CMakeLists.txt @@ -16,3 +16,5 @@ zephyr_library_sources_ifdef(CONFIG_MFD_MAX31790 mfd_max31790.c) zephyr_library_sources_ifdef(CONFIG_NXP_LP_FLEXCOMM mfd_nxp_lp_flexcomm.c) zephyr_library_sources_ifdef(CONFIG_MFD_BD8LB600FS mfd_bd8lb600fs.c) zephyr_library_sources_ifdef(CONFIG_MFD_TLE9104 mfd_tle9104.c) +zephyr_library_sources_ifdef(CONFIG_MFD_ITE_IT8801 mfd_ite_it8801.c) +zephyr_library_sources_ifdef(CONFIG_MFD_ITE_IT8801_ALTCTRL mfd_it8801_altctrl.c) diff --git a/drivers/mfd/Kconfig b/drivers/mfd/Kconfig index c384249daed3e1..13c1dff795c83d 100644 --- a/drivers/mfd/Kconfig +++ b/drivers/mfd/Kconfig @@ -29,5 +29,6 @@ source "drivers/mfd/Kconfig.npm1300" source "drivers/mfd/Kconfig.npm6001" source "drivers/mfd/Kconfig.lpflexcomm" source "drivers/mfd/Kconfig.tle9104" +source "drivers/mfd/Kconfig.it8801" endif # MFD diff --git a/drivers/mfd/Kconfig.it8801 b/drivers/mfd/Kconfig.it8801 new file mode 100644 index 00000000000000..2108555a3054c2 --- /dev/null +++ b/drivers/mfd/Kconfig.it8801 @@ -0,0 +1,23 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +config MFD_ITE_IT8801 + bool "ITE IT8801 ioexpander multi-function device driver" + default y + depends on DT_HAS_ITE_IT8801_MFD_ENABLED + select I2C + help + Enable the ITE IT8801 ioexpander multi-function device driver. + This ioexpander provides a GPIO/PWM/Keyboard function via I2C bus. + +if MFD_ITE_IT8801 + +config MFD_ITE_IT8801_ALTCTRL + bool "ITE IT8801 MFD alternate controller" + default y + +config MFD_IT8801_ALTCTRL_INIT_PRIORITY + int "IT8801 GPIO port init priority" + default 81 + +endif # MFD_ITE_IT8801 diff --git a/drivers/mfd/mfd_it8801_altctrl.c b/drivers/mfd/mfd_it8801_altctrl.c new file mode 100644 index 00000000000000..c44aad05173209 --- /dev/null +++ b/drivers/mfd/mfd_it8801_altctrl.c @@ -0,0 +1,66 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT ite_it8801_altctrl + +#include +#include +#include + +#include +LOG_MODULE_REGISTER(mfd_it8801_altctrl, LOG_LEVEL_ERR); + +struct mfd_altfunc_config { + /* gpiocr register */ + uint8_t reg_gpiocr; +}; + +int mfd_it8801_configure_pins(const struct i2c_dt_spec *i2c_dev, const struct device *dev, + uint8_t pin, uint8_t func) +{ + const struct mfd_altfunc_config *config = dev->config; + int ret; + uint8_t reg_gpiocr = config->reg_gpiocr + pin; + uint8_t alt_val; + + switch (func) { + case IT8801_ALT_FUNC_1: + /* Func1: Default GPIO setting */ + alt_val = IT8801_GPIOAFS_FUN1; + break; + case IT8801_ALT_FUNC_2: + /* Func2: KSO or PWM setting */ + alt_val = IT8801_GPIOAFS_FUN2; + break; + case IT8801_ALT_FUNC_3: + /* Func3: PWM setting */ + alt_val = IT8801_GPIOAFS_FUN3; + break; + case IT8801_ALT_DEFAULT: + alt_val = IT8801_GPIOAFS_FUN1; + break; + default: + LOG_ERR("This function is not supported."); + return -EINVAL; + } + + /* Common settings for alternate function. */ + ret = i2c_reg_update_byte_dt(i2c_dev, reg_gpiocr, GENMASK(7, 6), alt_val << 6); + if (ret != 0) { + LOG_ERR("Failed to update gpiocr (ret %d)", ret); + return ret; + } + + return 0; +} + +#define MFD_IT8801_ALTCTRL_INIT(inst) \ + static const struct mfd_altfunc_config it8801_mfd_alt_cfg_##inst = { \ + .reg_gpiocr = DT_INST_REG_ADDR(inst), \ + }; \ + DEVICE_DT_INST_DEFINE(inst, NULL, NULL, NULL, &it8801_mfd_alt_cfg_##inst, POST_KERNEL, \ + CONFIG_MFD_IT8801_ALTCTRL_INIT_PRIORITY, NULL); +DT_INST_FOREACH_STATUS_OKAY(MFD_IT8801_ALTCTRL_INIT) diff --git a/drivers/mfd/mfd_ite_it8801.c b/drivers/mfd/mfd_ite_it8801.c new file mode 100644 index 00000000000000..1e5e33609bd06c --- /dev/null +++ b/drivers/mfd/mfd_ite_it8801.c @@ -0,0 +1,143 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT ite_it8801_mfd + +#include +#include +#include + +#include +LOG_MODULE_REGISTER(mfd_ite_it8801, CONFIG_MFD_LOG_LEVEL); + +struct mfd_it8801_config { + const struct i2c_dt_spec i2c_dev; + /* Alert GPIO pin */ + const struct gpio_dt_spec irq_gpios; + /* MFD sub device */ + const struct device **sub_mfd_dev; + /* MFD sub device count */ + uint8_t sub_mfd_node_num; +}; + +struct mfd_it8801_data { + struct k_work gpio_isr_worker; + /* Alert pin callback */ + struct gpio_callback gpio_cb; + const struct device *mfd_dev; +}; + +static int it8801_check_vendor_id(const struct device *dev) +{ + const struct mfd_it8801_config *config = dev->config; + int i, ret; + uint8_t val; + + /* Verify vendor ID registers(16-bits). */ + for (i = 0; i < ARRAY_SIZE(it8801_id_verify); i++) { + ret = i2c_reg_read_byte_dt(&config->i2c_dev, it8801_id_verify[i].reg, &val); + + if (ret != 0) { + LOG_ERR("Failed to read vendoer ID (ret %d)", ret); + return ret; + } + + if (val != it8801_id_verify[i].chip_id) { + LOG_ERR("The IT8801 vendor ID is wrong"); + return -ENODEV; + } + } + + return ret; +} + +void it8801_gpio_callback(const struct device *dev, struct gpio_callback *cb, uint32_t pins) +{ + ARG_UNUSED(pins); + struct mfd_it8801_data *data = CONTAINER_OF(cb, struct mfd_it8801_data, gpio_cb); + + k_work_submit(&data->gpio_isr_worker); +} + +static void it8801_gpio_alert_worker(struct k_work *work) +{ + struct mfd_it8801_data *data = CONTAINER_OF(work, struct mfd_it8801_data, gpio_isr_worker); + const struct mfd_it8801_config *config = data->mfd_dev->config; + int i; + + for (i = 0; i < config->sub_mfd_node_num; i++) { + /* + * When the registered GPIO is triggered, the parent MFD driver + * will scan all the subdevices, and call the subdevice handler + * to determine which device was triggered. + */ +#ifdef CONFIG_INPUT_ITE_IT8801_KBD + it8801_input_alert_handler(config->sub_mfd_dev[i]); +#endif +#ifdef CONFIG_GPIO_ITE_IT8801 + it8801_gpio_alert_handler(config->sub_mfd_dev[i]); +#endif + } +} + +static int mfd_it8801_init(const struct device *dev) +{ + const struct mfd_it8801_config *config = dev->config; + struct mfd_it8801_data *data = dev->data; + int ret; + + if (!i2c_is_ready_dt(&config->i2c_dev)) { + LOG_ERR("I2C bus %s is not ready", config->i2c_dev.bus->name); + return -ENODEV; + } + + /* Verify Vendor ID registers. */ + ret = it8801_check_vendor_id(dev); + if (ret) { + LOG_ERR("Failed to read IT8801 vendor id %x", ret); + return ret; + } + + data->mfd_dev = dev; + + k_work_init(&data->gpio_isr_worker, it8801_gpio_alert_worker); + + /* Alert response enable */ + ret = i2c_reg_write_byte_dt(&config->i2c_dev, IT8801_REG_SMBCR, IT8801_REG_MASK_ARE); + if (ret != 0) { + LOG_ERR("Failed to initialization setting (ret %d)", ret); + return ret; + } + + gpio_pin_configure_dt(&config->irq_gpios, GPIO_INPUT); + + /* Initialize GPIO interrupt callback */ + gpio_init_callback(&data->gpio_cb, it8801_gpio_callback, BIT(config->irq_gpios.pin)); + + ret = gpio_add_callback(config->irq_gpios.port, &data->gpio_cb); + if (ret != 0) { + LOG_ERR("Failed to add INT callback: %d", ret); + return ret; + } + gpio_pin_interrupt_configure_dt(&config->irq_gpios, GPIO_INT_MODE_EDGE | GPIO_INT_TRIG_LOW); + + return 0; +} + +#define MFD_IT8801_DEFINE(inst) \ + static const struct device *sub_mfd_dev_##inst[] = { \ + DT_INST_FOREACH_CHILD_STATUS_OKAY_SEP(inst, DEVICE_DT_GET, (,))}; \ + static struct mfd_it8801_data it8801_data_##inst; \ + static const struct mfd_it8801_config it8801_cfg_##inst = { \ + .i2c_dev = I2C_DT_SPEC_INST_GET(inst), \ + .irq_gpios = GPIO_DT_SPEC_INST_GET(inst, irq_gpios), \ + .sub_mfd_dev = sub_mfd_dev_##inst, \ + .sub_mfd_node_num = ARRAY_SIZE(sub_mfd_dev_##inst), \ + }; \ + DEVICE_DT_INST_DEFINE(inst, mfd_it8801_init, NULL, &it8801_data_##inst, \ + &it8801_cfg_##inst, POST_KERNEL, CONFIG_MFD_INIT_PRIORITY, NULL); + +DT_INST_FOREACH_STATUS_OKAY(MFD_IT8801_DEFINE) diff --git a/drivers/pwm/CMakeLists.txt b/drivers/pwm/CMakeLists.txt index 2d229bd6bb280f..aa59e63db69422 100644 --- a/drivers/pwm/CMakeLists.txt +++ b/drivers/pwm/CMakeLists.txt @@ -13,6 +13,7 @@ zephyr_library_sources_ifdef(CONFIG_PWM_NRFX pwm_nrfx.c) zephyr_library_sources_ifdef(CONFIG_PWM_MCUX_FTM pwm_mcux_ftm.c) zephyr_library_sources_ifdef(CONFIG_PWM_IMX pwm_imx.c) zephyr_library_sources_ifdef(CONFIG_PWM_ITE_IT8XXX2 pwm_ite_it8xxx2.c) +zephyr_library_sources_ifdef(CONFIG_PWM_ITE_IT8801 pwm_ite_it8801.c) zephyr_library_sources_ifdef(CONFIG_PWM_LED_ESP32 pwm_led_esp32.c) zephyr_library_sources_ifdef(CONFIG_MCPWM_ESP32 pwm_mc_esp32.c) zephyr_library_sources_ifdef(CONFIG_PWM_SAM pwm_sam.c) diff --git a/drivers/pwm/Kconfig b/drivers/pwm/Kconfig index b99ba35dafc230..f034af4dcd9d06 100644 --- a/drivers/pwm/Kconfig +++ b/drivers/pwm/Kconfig @@ -50,6 +50,8 @@ source "drivers/pwm/Kconfig.imx" source "drivers/pwm/Kconfig.it8xxx2" +source "drivers/pwm/Kconfig.it8801" + source "drivers/pwm/Kconfig.esp32" source "drivers/pwm/Kconfig.sam" diff --git a/drivers/pwm/Kconfig.it8801 b/drivers/pwm/Kconfig.it8801 new file mode 100644 index 00000000000000..1f50fc90351a6d --- /dev/null +++ b/drivers/pwm/Kconfig.it8801 @@ -0,0 +1,23 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +config PWM_ITE_IT8801 + bool "ITE IT8801 PWM device driver" + default y + depends on DT_HAS_ITE_IT8801_PWM_ENABLED + select I2C + select MFD + help + Enable driver for ITE IT8801 I2C-based PWM. + Supports 7 open-drain/push-pull outputs. + +if PWM_ITE_IT8801 + +config PWM_IT8801_INIT_PRIORITY + int "IT8801 PWM port init priority" + default 85 + help + IT8801 PWM device driver initialization priority. The priority + must be lower than MFD_INIT_PRIORITY device. + +endif # PWM_ITE_IT8801 diff --git a/drivers/pwm/pwm_ite_it8801.c b/drivers/pwm/pwm_ite_it8801.c new file mode 100644 index 00000000000000..60ccee22406054 --- /dev/null +++ b/drivers/pwm/pwm_ite_it8801.c @@ -0,0 +1,174 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT ite_it8801_pwm + +#include +#include +#include +#include + +#include +LOG_MODULE_REGISTER(pwm_ite_it8801, CONFIG_PWM_LOG_LEVEL); + +struct it8801_pwm_map { + int pushpull_en; +}; +const static struct it8801_pwm_map it8801_pwm_gpio_map[] = { + [1] = {.pushpull_en = BIT(0)}, [2] = {.pushpull_en = BIT(1)}, [3] = {.pushpull_en = BIT(2)}, + [4] = {.pushpull_en = BIT(3)}, [7] = {.pushpull_en = BIT(4)}, [8] = {.pushpull_en = BIT(5)}, + [9] = {.pushpull_en = BIT(6)}, +}; + +struct it8801_mfd_pwm_altctrl_cfg { + /* GPIO control device structure */ + const struct device *gpiocr; + /* GPIO control pin */ + uint8_t pin; + /* GPIO function select */ + uint8_t alt_func; +}; + +struct pwm_it8801_config { + /* IT8801 controller dev */ + const struct device *mfd; + /* I2C device for the MFD parent */ + const struct i2c_dt_spec i2c_dev; + /* PWM alternate configuration */ + const struct it8801_mfd_pwm_altctrl_cfg *altctrl; + int mfdctrl_len; + int channel; + /* PWM mode control register */ + uint8_t reg_mcr; + /* PWM duty cycle register */ + uint8_t reg_dcr; + /* PWM prescale LSB register */ + uint8_t reg_prslr; + /* PWM prescale MSB register */ + uint8_t reg_prsmr; +}; + +static void pwm_enable(const struct device *dev, int enabled) +{ + const struct pwm_it8801_config *config = dev->config; + int ret; + + if (enabled) { + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_mcr, + IT8801_PWMMCR_MCR_MASK, IT8801_PWMMCR_MCR_BLINKING); + } else { + ret = i2c_reg_update_byte_dt(&config->i2c_dev, config->reg_mcr, + IT8801_PWMMCR_MCR_MASK, 0); + } + if (ret != 0) { + LOG_ERR("Failed to enable pwm (ret %d)", ret); + return; + } +} + +static int pwm_it8801_get_cycles_per_sec(const struct device *dev, uint32_t channel, + uint64_t *cycles) +{ + ARG_UNUSED(dev); + ARG_UNUSED(channel); + + *cycles = (uint64_t)PWM_IT8801_FREQ; + + return 0; +} + +static int pwm_it8801_set_cycles(const struct device *dev, uint32_t channel, uint32_t period_cycles, + uint32_t pulse_cycles, pwm_flags_t flags) +{ + ARG_UNUSED(channel); + + const struct pwm_it8801_config *config = dev->config; + int ch = config->channel, ret; + uint8_t duty, mask; + + /* Enable PWM output push-pull */ + if (flags & PWM_IT8801_PUSH_PULL) { + mask = it8801_pwm_gpio_map[ch].pushpull_en; + + ret = i2c_reg_update_byte_dt(&config->i2c_dev, IT8801_REG_PWMODDSR, mask, mask); + if (ret != 0) { + LOG_ERR("Failed to set push-pull (ret %d)", ret); + return ret; + } + } + + /* Set PWM channel duty cycle */ + if (pulse_cycles == 0) { + duty = 0; + } else { + duty = pulse_cycles * 256 / period_cycles - 1; + } + LOG_DBG("IT8801 pwm duty cycles = %d", duty); + + ret = i2c_reg_write_byte_dt(&config->i2c_dev, config->reg_dcr, duty); + if (ret != 0) { + LOG_ERR("Failed to set cycles (ret %d)", ret); + return ret; + } + + /* PWM channel clock source not gating */ + pwm_enable(dev, 1); + + return 0; +} + +static int pwm_it8801_init(const struct device *dev) +{ + const struct pwm_it8801_config *config = dev->config; + int ret; + + /* Verify multi-function parent is ready */ + if (!device_is_ready(config->mfd)) { + LOG_ERR("(pwm)%s is not ready", config->mfd->name); + return -ENODEV; + } + + /* PWM channel clock source gating before configuring */ + pwm_enable(dev, 0); + + for (int i = 0; i < config->mfdctrl_len; i++) { + /* Switching the pin to PWM alternate function */ + ret = mfd_it8801_configure_pins(&config->i2c_dev, config->altctrl[i].gpiocr, + config->altctrl[i].pin, + config->altctrl[i].alt_func); + if (ret != 0) { + LOG_ERR("Failed to configure pins (ret %d)", ret); + return ret; + } + } + + return 0; +} + +static const struct pwm_driver_api pwm_it8801_api = { + .set_cycles = pwm_it8801_set_cycles, + .get_cycles_per_sec = pwm_it8801_get_cycles_per_sec, +}; + +#define PWM_IT8801_INIT(inst) \ + static const struct it8801_mfd_pwm_altctrl_cfg \ + it8801_pwm_altctrl##inst[IT8801_DT_INST_MFDCTRL_LEN(inst)] = \ + IT8801_DT_MFD_ITEMS_LIST(inst); \ + static const struct pwm_it8801_config pwm_it8801_cfg_##inst = { \ + .mfd = DEVICE_DT_GET(DT_INST_PARENT(inst)), \ + .i2c_dev = I2C_DT_SPEC_GET(DT_INST_PARENT(inst)), \ + .altctrl = it8801_pwm_altctrl##inst, \ + .mfdctrl_len = IT8801_DT_INST_MFDCTRL_LEN(inst), \ + .channel = DT_INST_PROP(inst, channel), \ + .reg_mcr = DT_INST_REG_ADDR_BY_IDX(inst, 0), \ + .reg_dcr = DT_INST_REG_ADDR_BY_IDX(inst, 1), \ + .reg_prslr = DT_INST_REG_ADDR_BY_IDX(inst, 2), \ + .reg_prsmr = DT_INST_REG_ADDR_BY_IDX(inst, 3), \ + }; \ + DEVICE_DT_INST_DEFINE(inst, &pwm_it8801_init, NULL, NULL, &pwm_it8801_cfg_##inst, \ + POST_KERNEL, CONFIG_PWM_IT8801_INIT_PRIORITY, &pwm_it8801_api); + +DT_INST_FOREACH_STATUS_OKAY(PWM_IT8801_INIT) diff --git a/dts/bindings/gpio/ite,it8801-gpio.yaml b/dts/bindings/gpio/ite,it8801-gpio.yaml new file mode 100644 index 00000000000000..2e78fa9917a870 --- /dev/null +++ b/dts/bindings/gpio/ite,it8801-gpio.yaml @@ -0,0 +1,23 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: ITE IT8801 I2C-based GPIO device driver + +compatible: "ite,it8801-gpio" + +include: [base.yaml, gpio-controller.yaml] + +properties: + reg: + required: true + + pin-mask: + type: int + required: true + description: | + Not every GPIO pins are usable for IT8801. This property + indicates the usable GPIO pin mask. + +gpio-cells: + - pin + - flags diff --git a/dts/bindings/input/ite,it8801-kbd.yaml b/dts/bindings/input/ite,it8801-kbd.yaml new file mode 100644 index 00000000000000..859beb405af3af --- /dev/null +++ b/dts/bindings/input/ite,it8801-kbd.yaml @@ -0,0 +1,26 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: ITE IT8801 I2C-based keyboard matrix scan controller + +compatible: "ite,it8801-kbd" + +include: [kbd-matrix-common.yaml, pinctrl-device.yaml] + +properties: + reg: + required: true + + mfdctrl: + type: phandles + description: | + Switching the pin to KSO alternate function. + + kso-mapping: + type: array + + row-size: + required: true + + col-size: + required: true diff --git a/dts/bindings/mfd/ite,it8801-altctrl.yaml b/dts/bindings/mfd/ite,it8801-altctrl.yaml new file mode 100644 index 00000000000000..21fd0e9061ffb8 --- /dev/null +++ b/dts/bindings/mfd/ite,it8801-altctrl.yaml @@ -0,0 +1,12 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: ITE IT8801 GPIO controller node + +compatible: "ite,it8801-altctrl" + +include: base.yaml + +altctrl-cells: + - pin + - alt_func diff --git a/dts/bindings/mfd/ite,it8801-mfd-map.yaml b/dts/bindings/mfd/ite,it8801-mfd-map.yaml new file mode 100644 index 00000000000000..aaa8a35c9901dd --- /dev/null +++ b/dts/bindings/mfd/ite,it8801-mfd-map.yaml @@ -0,0 +1,13 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: ITE IT8801 alternate controller node + +compatible: "ite,it8801-mfd-map" + +child-binding: + description: Child node to present the mapping of IT8801 altternate function + properties: + altctrls: + type: phandle-array + required: true diff --git a/dts/bindings/mfd/ite,it8801-mfd.yaml b/dts/bindings/mfd/ite,it8801-mfd.yaml new file mode 100644 index 00000000000000..99d7c45e07351f --- /dev/null +++ b/dts/bindings/mfd/ite,it8801-mfd.yaml @@ -0,0 +1,109 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: | + ITE IT8801 ioexpander multi-function device drivers. + This ioexpander provides a GPIO/PWM/Keyboard function via I2C bus. + + An example configuration: + + &i2c4 { + status = "okay"; + clock-frequency = ; + pinctrl-0 = <&i2c4_clk_gpe0_default + &i2c4_data_gpe7_default>; + pinctrl-names = "default"; + + it8801_mfd: it8801@38 { + compatible = "ite,it8801-mfd"; + /* + * SMBus address (7-bit without R/W) + * SMB_ADDR pin is 0, SMBus address is 0x38 + * SMB_ADDR pin is 1, SMBus address is 0x39 + */ + reg = <0x38>; + irq-gpios = <&gpioa 1 0>; /* SMB_INT# */ + #address-cells = <1>; + #size-cells = <1>; + + ioex_it8801_port0: it8801_port@0 { + compatible = "ite,it8801-gpio"; + reg = <0x00 1 /* GPIPSR */ + 0x05 1 /* GPSOVR */ + 0x0a 8 /* GPCR */ + 0x32 1 /* GPISR */ + 0x37 1>; /* GPIER */ + gpio-controller; + #gpio-cells = <2>; + ngpios = <8>; + pin-mask = <0xdb>; + }; + + ioex_it8801_port1: it8801_port@1 { + compatible = "ite,it8801-gpio"; + reg = <0x01 1 /* GPIPSR */ + 0x06 1 /* GPSOVR */ + 0x12 8 /* GPCR */ + 0x33 1 /* GPISR */ + 0x38 1>; /* GPIER */ + gpio-controller; + #gpio-cells = <2>; + ngpios = <8>; + pin-mask = <0x3f>; + }; + + ioex_it8801_port2: it8801_port@2 { + compatible = "ite,it8801-gpio"; + reg = <0x02 1 /* GPIPSR */ + 0x07 1 /* GPSOVR */ + 0x1a 8 /* GPCR */ + 0x34 1 /* GPISR */ + 0x39 1>; /* GPIER */ + gpio-controller; + #gpio-cells = <2>; + ngpios = <8>; + pin-mask = <0x0f>; + }; + + ioex_it8801_kbd: it8801_kbd@40 { + compatible = "ite,it8801-kbd"; + reg = <0x40 1 /* KSOMCR */ + 0x41 1 /* KSIDR */ + 0x42 1 /* KSIEER */ + 0x43 1>; /* KSIIER */ + kso-mapping = <0 1 20 3 4 5 6 + 17 18 16 15 11 12>; + mfdctrl = <&kso18_gp01_default + &kso20_gp23_default>; + row-size = <8>; + col-size = <13>; + + kscan_input: kscan-input { + compatible = "zephyr,kscan-input"; + }; + }; + + ioex_it8801_pwm: it8801_pwm@90 { + compatible = "ite,it8801-pwm"; + mfdctrl = <&pwm7_gp20_default>; + reg = <0x90 1 /* PWMMCR */ + 0x94 1>; /* PWMDCR */ + channel = <7>; + #pwm-cells = <3>; + }; + }; + }; + +compatible: "ite,it8801-mfd" + +include: i2c-device.yaml + +properties: + reg: + required: true + + irq-gpios: + type: phandle-array + description: | + An interrupt can be asserted on SMB_INT# pin to notify + the host-side since an effective interrupt occurs. diff --git a/dts/bindings/pwm/ite,it8801-pwm.yaml b/dts/bindings/pwm/ite,it8801-pwm.yaml new file mode 100644 index 00000000000000..04b9ce8f10a719 --- /dev/null +++ b/dts/bindings/pwm/ite,it8801-pwm.yaml @@ -0,0 +1,39 @@ +# Copyright (c) 2024 ITE Corporation. All Rights Reserved. +# SPDX-License-Identifier: Apache-2.0 + +description: ITE IT8801 I2C-based PWM device driver + +compatible: "ite,it8801-pwm" + +include: [base.yaml, pinctrl-device.yaml, pwm-controller.yaml] + +properties: + reg: + required: true + + mfdctrl: + type: phandle + required: true + description: | + Switching the pin to PWM alternate function. + + channel: + type: int + required: true + enum: + - 1 + - 2 + - 3 + - 4 + - 7 + - 8 + - 9 + description: | + 1 = PWM_CHANNEL_1, 2 = PWM_CHANNEL_2, 3 = PWM_CHANNEL_3, + 4 = PWM_CHANNEL_4, 7 = PWM_CHANNEL_7, 8 = PWM_CHANNEL_8, + 9 = PWM_CHANNEL_9 + +pwm-cells: + - channel + - period + - flags diff --git a/dts/riscv/ite/it8801-mfd-gpiocr.dtsi b/dts/riscv/ite/it8801-mfd-gpiocr.dtsi new file mode 100644 index 00000000000000..6bae68189e2fcb --- /dev/null +++ b/dts/riscv/ite/it8801-mfd-gpiocr.dtsi @@ -0,0 +1,30 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/ { + it8801_mfd { + #address-cells = <1>; + #size-cells = <1>; + + it8801_gpio0: gpiocr@0a { + compatible = "ite,it8801-altctrl"; + reg = <0x0a 8>; + #altctrl-cells = <2>; + }; + + it8801_gpio1: gpiocr@12 { + compatible = "ite,it8801-altctrl"; + reg = <0x12 6>; + #altctrl-cells = <2>; + }; + + it8801_gpio2: gpiocr@1a { + compatible = "ite,it8801-altctrl"; + reg = <0x1a 4>; + #altctrl-cells = <2>; + }; + }; +}; diff --git a/dts/riscv/ite/it8801-mfd-map.dtsi b/dts/riscv/ite/it8801-mfd-map.dtsi new file mode 100644 index 00000000000000..2de58ed44bc06b --- /dev/null +++ b/dts/riscv/ite/it8801-mfd-map.dtsi @@ -0,0 +1,56 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include + + +/ { + /* GPIO pin mapping to alternate function */ + it8801-mfd-map { + compatible = "ite,it8801-mfd-map"; + + /* PWM alternate function */ + pwm1_gp12_default: pwm1_gp12_default { + altctrls = <&it8801_gpio1 2 IT8801_ALT_FUNC_2>; + }; + pwm2_gp13_default: pwm2_gp13_default { + altctrls = <&it8801_gpio1 3 IT8801_ALT_FUNC_2>; + }; + pwm3_gp14_default: pwm3_gp14_default { + altctrls = <&it8801_gpio1 4 IT8801_ALT_FUNC_2>; + }; + pwm4_gp15_default: pwm4_gp15_default { + altctrls = <&it8801_gpio1 5 IT8801_ALT_FUNC_2>; + }; + pwm7_gp20_default: pwm7_gp20_default { + altctrls = <&it8801_gpio2 0 IT8801_ALT_FUNC_2>; + }; + pwm8_gp23_default: pwm8_gp23_default { + altctrls = <&it8801_gpio2 3 IT8801_ALT_FUNC_3>; + }; + pwm9_gp22_default: pwm9_gp22_default { + altctrls = <&it8801_gpio2 2 IT8801_ALT_FUNC_3>; + }; + + /* Keyboard alternate function */ + kso18_gp01_default: kso18_gp01_default { + altctrls = <&it8801_gpio0 1 IT8801_ALT_FUNC_2>; + }; + kso19_gp00_default: kso19_gp00_default { + altctrls = <&it8801_gpio0 0 IT8801_ALT_FUNC_2>; + }; + kso20_gp23_default: kso20_gp23_default { + altctrls = <&it8801_gpio2 3 IT8801_ALT_FUNC_2>; + }; + kso21_gp22_default: kso21_gp22_default { + altctrls = <&it8801_gpio2 2 IT8801_ALT_FUNC_2>; + }; + kso22_gp21_default: kso22_gp21_default { + altctrls = <&it8801_gpio2 1 IT8801_ALT_FUNC_2>; + }; + }; +}; diff --git a/include/zephyr/drivers/mfd/mfd_ite_it8801.h b/include/zephyr/drivers/mfd/mfd_ite_it8801.h new file mode 100644 index 00000000000000..813db86fc6fefe --- /dev/null +++ b/include/zephyr/drivers/mfd/mfd_ite_it8801.h @@ -0,0 +1,129 @@ +/* + * Copyright (c) 2024 ITE Corporation. All Rights Reserved. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_INCLUDE_DRIVERS_MFD_ITE_IT8801_H_ +#define ZEPHYR_INCLUDE_DRIVERS_MFD_ITE_IT8801_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/* + * IC clock and power management controller register fields + */ +/* 0xf9: Gather interrupt status register */ +#define IT8801_REG_GISR 0xf9 +#define IT8801_REG_MASK_GISR_GKSIIS BIT(6) +/* 0xfb: Gather interrupt enable control register */ +#define IT8801_REG_GIECR 0xfb +#define IT8801_REG_MASK_GKSIIE BIT(3) +#define IT8801_REG_MASK_GGPIOIE BIT(2) + +/* + * General control register fields + */ +#define IT8801_REG_LBVIDR 0xfe +#define IT8801_REG_HBVIDR 0xff + +struct it8801_vendor_id_t { + uint8_t chip_id; + uint8_t reg; +}; + +static const struct it8801_vendor_id_t it8801_id_verify[] = { + {0x12, IT8801_REG_HBVIDR}, + {0x83, IT8801_REG_LBVIDR}, +}; + +/* + * SMbus interface register fields + */ +/* 0xfa: SMBus control register */ +#define IT8801_REG_SMBCR 0xfa +#define IT8801_REG_MASK_ARE BIT(4) + +/* + * GPIO register fields + */ +#define IT8801_GPIOAFS_FUN1 0x0 +#define IT8801_GPIOAFS_FUN2 0x01 +#define IT8801_GPIOAFS_FUN3 0x02 +/* GPIO control register */ +/* GPIO direction */ +#define IT8801_GPIODIR BIT(5) +/* GPIO input and output type */ +#define IT8801_GPIOIOT_OD BIT(4) +#define IT8801_GPIOIOT_INT_FALL BIT(4) +#define IT8801_GPIOIOT_INT_RISE BIT(3) +/* GPIO polarity */ +#define IT8801_GPIOPOL BIT(2) +/* GPIO pull-down enable */ +#define IT8801_GPIOPDE BIT(1) +/* GPIO pull-up enable */ +#define IT8801_GPIOPUE BIT(0) + +/* + * Keyboard matrix scan controller register fields + */ +/* 0x40: Keyboard scan out mode control register */ +#define IT8801_REG_MASK_KSOSDIC BIT(7) +#define IT8801_REG_MASK_KSE BIT(6) +#define IT8801_REG_MASK_AKSOSC BIT(5) + +/* + * PWM register fields + */ +#define PWM_IT8801_FREQ 32895 +/* Control push-pull flag */ +#define PWM_IT8801_PUSH_PULL BIT(8) +/* 0x5f: PWM output open-drain disable register */ +#define IT8801_REG_PWMODDSR 0x5f +/* PWM mode control register */ +#define IT8801_PWMMCR_MCR_MASK GENMASK(1, 0) +#define IT8801_PWMMCR_MCR_OFF 0 +#define IT8801_PWMMCR_MCR_BLINKING 1 +#define IT8801_PWMMCR_MCR_BREATHING 2 +#define IT8801_PWMMCR_MCR_ON 3 + +/* + * For IT8801 MFD alternate function controller + */ +#define IT8801_DT_INST_MFDCTRL(inst, idx) DT_INST_PHANDLE_BY_IDX(inst, mfdctrl, idx) + +#define IT8801_DT_INST_MFDCTRL_LEN(inst) DT_INST_PROP_LEN_OR(inst, mfdctrl, 0) + +#define IT8801_DEV_MFD(idx, inst) \ + DEVICE_DT_GET(DT_PHANDLE(IT8801_DT_INST_MFDCTRL(inst, idx), altctrls)) +#define IT8801_DEV_MFD_PIN(idx, inst) DT_PHA(IT8801_DT_INST_MFDCTRL(inst, idx), altctrls, pin) +#define IT8801_DEV_MFD_FUNC(idx, inst) DT_PHA(IT8801_DT_INST_MFDCTRL(inst, idx), altctrls, alt_func) + +#define IT8801_DT_MFD_ITEMS_FUNC(idx, inst) \ + { \ + .gpiocr = IT8801_DEV_MFD(idx, inst), \ + .pin = IT8801_DEV_MFD_PIN(idx, inst), \ + .alt_func = IT8801_DEV_MFD_FUNC(idx, inst), \ + } + +#define IT8801_DT_MFD_ITEMS_LIST(inst) \ + {LISTIFY(IT8801_DT_INST_MFDCTRL_LEN(inst), \ + IT8801_DT_MFD_ITEMS_FUNC, (,), \ + inst) } + +/* + * Configure alternate function pin + */ +int mfd_it8801_configure_pins(const struct i2c_dt_spec *i2c_dev, const struct device *dev, + uint8_t pin, uint8_t func); + +void it8801_input_alert_handler(const struct device *dev); + +void it8801_gpio_alert_handler(const struct device *dev); + +#ifdef __cplusplus +} +#endif + +#endif /* ZEPHYR_INCLUDE_DRIVERS_MFD_ITE_IT8801_H_ */ diff --git a/include/zephyr/dt-bindings/mfd/mfd_it8801_altctrl.h b/include/zephyr/dt-bindings/mfd/mfd_it8801_altctrl.h new file mode 100644 index 00000000000000..673cb5d25dc01e --- /dev/null +++ b/include/zephyr/dt-bindings/mfd/mfd_it8801_altctrl.h @@ -0,0 +1,17 @@ +/* + * Copyright (c) 2024 ITE Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ +#ifndef ZEPHYR_INCLUDE_DT_BINDINGS_MFD_IT8801_ALTCTRL_H_ +#define ZEPHYR_INCLUDE_DT_BINDINGS_MFD_IT8801_ALTCTRL_H_ + +/** + * @brief PIN alternate function. + */ +#define IT8801_ALT_FUNC_1 0U +#define IT8801_ALT_FUNC_2 1U +#define IT8801_ALT_FUNC_3 2U +#define IT8801_ALT_DEFAULT 3U + +#endif /* ZEPHYR_INCLUDE_DT_BINDINGS_MFD_IT8801_ALTCTRL_H_ */