diff --git a/drivers/ps2/CMakeLists.txt b/drivers/ps2/CMakeLists.txt index fb0ec2f36cc..006c70d63f6 100644 --- a/drivers/ps2/CMakeLists.txt +++ b/drivers/ps2/CMakeLists.txt @@ -4,3 +4,5 @@ zephyr_library() zephyr_library_sources_ifdef(CONFIG_PS2_XEC ps2_mchp_xec.c) zephyr_library_sources_ifdef(CONFIG_USERSPACE ps2_handlers.c) +zephyr_library_sources_ifdef(CONFIG_PS2_NPCX ps2_npcx_channel.c) +zephyr_library_sources_ifdef(CONFIG_PS2_NPCX ps2_npcx_controller.c) diff --git a/drivers/ps2/Kconfig b/drivers/ps2/Kconfig index eff7b0416ad..8677ada4830 100644 --- a/drivers/ps2/Kconfig +++ b/drivers/ps2/Kconfig @@ -11,6 +11,7 @@ menuconfig PS2 if PS2 source "drivers/ps2/Kconfig.xec" +source "drivers/ps2/Kconfig.npcx" module = PS2 module-str = ps2 diff --git a/drivers/ps2/Kconfig.npcx b/drivers/ps2/Kconfig.npcx new file mode 100644 index 00000000000..e14e680eb3a --- /dev/null +++ b/drivers/ps2/Kconfig.npcx @@ -0,0 +1,27 @@ +# NPCX PS2 configuration options + +# Copyright (c) 2021 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +menuconfig PS2_NPCX + bool "Nuvoton NPCX embedded controller (EC) PS2 driver" + depends on SOC_FAMILY_NPCX && ESPI_PERIPHERAL_8042_KBC + help + Enable the NPCX family PS2 driver. It provides four PS/2 channels. + Each channel has two quasi-bidirectional signals that serve as + direct interfaces to an external keyboard, mouse or any other + PS/2-compatible pointing device.The driver also depends on the KBC + 8042 keyboard controller. + +if PS2_NPCX + +config PS2_CHANNEL_INIT_PRIORITY + int "PS/2 channel driver init priority" + default 41 + help + PS/2 channel device driver initialization priority. + This should be lower than the PS2_INIT_PRIORITY as + NPCX PS/2 controller device driver should initialize + prior to channel device driver. + +endif # PS2_NPCX diff --git a/drivers/ps2/ps2_npcx_channel.c b/drivers/ps2/ps2_npcx_channel.c new file mode 100644 index 00000000000..ef7c2ace1bb --- /dev/null +++ b/drivers/ps2/ps2_npcx_channel.c @@ -0,0 +1,148 @@ +/* + * Copyright (c) 2021 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT nuvoton_npcx_ps2_channel + +/** + * @file + * @brief Nuvoton NPCX PS/2 driver + * + * This file contains the driver of PS/2 buses (channels) which provides the + * connection between Zephyr PS/2 API fucntions and NPCX PS/2 controller driver + * to support PS/2 transactions. + * + */ + +#include +#include +#include + +#include +LOG_MODULE_REGISTER(ps2_npcx_channel, CONFIG_PS2_LOG_LEVEL); + +#include "ps2_npcx_controller.h" + +/* Device config */ +struct ps2_npcx_ch_config { + /* pinmux configuration */ + const uint8_t alts_size; + const struct npcx_alt *alts_list; + /* Indicate the channel's number of the PS/2 channel device */ + uint8_t channel_id; +}; + +/* Driver data */ +struct ps2_npcx_ch_data { + const struct device *ps2_ctrl; +}; + +/* Driver convenience defines */ +#define DRV_CONFIG(dev) ((const struct ps2_npcx_ch_config *)(dev)->config) + +#define DRV_DATA(dev) ((struct ps2_npcx_ch_data *)(dev)->data) + +/* PS/2 api functions */ +static int ps2_npcx_ch_configure(const struct device *dev, + ps2_callback_t callback_isr) +{ + const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev); + struct ps2_npcx_ch_data *const data = DRV_DATA(dev); + int ret; + + ret = ps2_npcx_ctrl_configure(data->ps2_ctrl, config->channel_id, + callback_isr); + if (ret != 0) + return ret; + + return ps2_npcx_ctrl_enable_interface(data->ps2_ctrl, + config->channel_id, 1); +} + +static int ps2_npcx_ch_write(const struct device *dev, uint8_t value) +{ + const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev); + struct ps2_npcx_ch_data *const data = DRV_DATA(dev); + + return ps2_npcx_ctrl_write(data->ps2_ctrl, config->channel_id, value); +} + +static int ps2_npcx_ch_enable_interface(const struct device *dev) +{ + const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev); + struct ps2_npcx_ch_data *const data = DRV_DATA(dev); + + return ps2_npcx_ctrl_enable_interface(data->ps2_ctrl, + config->channel_id, 1); +} + +static int ps2_npcx_ch_inhibit_interface(const struct device *dev) +{ + const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev); + struct ps2_npcx_ch_data *const data = DRV_DATA(dev); + + return ps2_npcx_ctrl_enable_interface(data->ps2_ctrl, + config->channel_id, 0); +} + +/* PS/2 driver registration */ +static int ps2_npcx_channel_init(const struct device *dev) +{ + const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev); + + /* Configure pin-mux for PS/2 device */ + npcx_pinctrl_mux_configure(config->alts_list, config->alts_size, 1); + + return 0; +} + +static const struct ps2_driver_api ps2_channel_npcx_driver_api = { + .config = ps2_npcx_ch_configure, + .read = NULL, + .write = ps2_npcx_ch_write, + .disable_callback = ps2_npcx_ch_inhibit_interface, + .enable_callback = ps2_npcx_ch_enable_interface, +}; + +/* PS/2 channel initialization macro functions */ +#define NPCX_PS2_CHANNEL_INIT_FUNC(inst) _CONCAT(ps2_npcx_channel_init_, inst) +#define NPCX_PS2_CHANNEL_INIT_FUNC_DECL(inst) \ + static int ps2_npcx_channel_init_##inst(const struct device *dev) + +#define NPCX_PS2_CHANNEL_INIT_FUNC_IMPL(inst) \ + static int ps2_npcx_channel_init_##inst(const struct device *dev) \ + { \ + struct ps2_npcx_ch_data *const data = DRV_DATA(dev); \ + \ + data->ps2_ctrl = device_get_binding(DT_INST_BUS_LABEL(inst)); \ + return ps2_npcx_channel_init(dev); \ + } + +#define NPCX_PS2_CHANNEL_INIT(inst) \ + NPCX_PS2_CHANNEL_INIT_FUNC_DECL(inst); \ + \ + static const struct npcx_alt ps2_channel_alts##inst[] = \ + NPCX_DT_ALT_ITEMS_LIST(inst); \ + \ + static const struct ps2_npcx_ch_config ps2_npcx_ch_cfg_##inst = { \ + .channel_id = DT_INST_PROP(inst, channel), \ + .alts_size = ARRAY_SIZE(ps2_channel_alts##inst), \ + .alts_list = ps2_channel_alts##inst, \ + }; \ + \ + static struct ps2_npcx_ch_data ps2_npcx_ch_data_##inst; \ + \ + DEVICE_DT_INST_DEFINE(inst, NPCX_PS2_CHANNEL_INIT_FUNC(inst), NULL, \ + &ps2_npcx_ch_data_##inst, \ + &ps2_npcx_ch_cfg_##inst, POST_KERNEL, \ + CONFIG_PS2_CHANNEL_INIT_PRIORITY, \ + &ps2_channel_npcx_driver_api); \ + \ + NPCX_PS2_CHANNEL_INIT_FUNC_IMPL(inst) + +DT_INST_FOREACH_STATUS_OKAY(NPCX_PS2_CHANNEL_INIT) + +/* PS/2 channel driver must be initialized after PS/2 controller driver */ +BUILD_ASSERT(CONFIG_PS2_CHANNEL_INIT_PRIORITY > CONFIG_PS2_INIT_PRIORITY); diff --git a/drivers/ps2/ps2_npcx_controller.c b/drivers/ps2/ps2_npcx_controller.c new file mode 100644 index 00000000000..3aec844a56b --- /dev/null +++ b/drivers/ps2/ps2_npcx_controller.c @@ -0,0 +1,373 @@ +/* + * Copyright (c) 2021 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT nuvoton_npcx_ps2_ctrl + +/** + * @file + * @brief Nuvoton NPCX PS/2 module (controller) driver + * + * This file contains the driver of PS/2 module (controller) which provides a + * hardware accelerator mechanism to handle both incoming and outgoing data. + * The hardware accelerator mechanism is shared by four PS/2 channels. + */ + +#include +#include +#include + +#include +LOG_MODULE_REGISTER(ps2_npcx_ctrl, CONFIG_PS2_LOG_LEVEL); + +#define NPCX_PS2_CH_COUNT 4 + +/* + * Set WDAT3-0 and clear CLK3-0 in the PSOSIG register to + * reset the shift mechanism. + */ +#define NPCX_PS2_SHIFT_MECH_RESET (uint8_t)~NPCX_PSOSIG_CLK_MASK_ALL + +/* in 50us units */ +#define PS2_RETRY_COUNT 10000 + +/* + * The max duration of a PS/2 clock is about 100 micro-seconds. + * A PS/2 transaction needs 11 clock cycles. It will take about 1.1 ms for a + * complete transaction. + */ +#define PS2_TRANSACTION_TIMEOUT K_MSEC(2) + +/* Device config */ +struct ps2_npcx_ctrl_config { + uintptr_t base; + struct npcx_clk_cfg clk_cfg; +}; + +/* Driver data */ +struct ps2_npcx_ctrl_data { + /* + * Bit mask to record the enabled PS/2 channels. + * Only bit[7] and bit[5:3] are used + * (i.e. the bit position of CLK3-0 in the PS2_PSOSIG register) + */ + uint8_t channel_enabled_mask; + /* The mutex of the PS/2 controller */ + struct k_sem lock; + /* The semaphore to synchronize the Tx transaction */ + struct k_sem tx_sync_sem; + /* + * The callback function to handle the data received from PS/2 device + */ + ps2_callback_t callback_isr[NPCX_PS2_CH_COUNT]; +}; + +/* Driver convenience defines */ +#define DRV_CONFIG(dev) ((const struct ps2_npcx_ctrl_config *)(dev)->config) + +#define DRV_DATA(dev) ((struct ps2_npcx_ctrl_data *)(dev)->data) + +#define HAL_PS2_INSTANCE(dev) (struct ps2_reg *)(DRV_CONFIG(dev)->base) + +static uint8_t ps2_npcx_ctrl_get_ch_clk_mask(uint8_t channel_id) +{ + return BIT(NPCX_PSOSIG_CLK(channel_id)); +} + +int ps2_npcx_ctrl_configure(const struct device *dev, uint8_t channel_id, + ps2_callback_t callback_isr) +{ + struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev); + + if (channel_id >= NPCX_PS2_CH_COUNT) { + LOG_ERR("unexpected channel ID: %d", channel_id); + return -EINVAL; + } + + if (callback_isr == NULL) { + return -EINVAL; + } + + k_sem_take(&data->lock, K_FOREVER); + data->callback_isr[channel_id] = callback_isr; + k_sem_give(&data->lock); + + return 0; +} + +int ps2_npcx_ctrl_enable_interface(const struct device *dev, uint8_t channel_id, + bool enable) +{ + struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev); + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + uint8_t ch_clk_mask; + + k_sem_take(&data->lock, K_FOREVER); + /* + * Disable the interrupt during changing the enabled channel mask to + * prevent from preemption. + */ + irq_disable(DT_INST_IRQN(0)); + + if (channel_id >= NPCX_PS2_CH_COUNT) { + LOG_ERR("unexpected channel ID: %d", channel_id); + irq_enable(DT_INST_IRQN(0)); + k_sem_give(&data->lock); + return -EINVAL; + } + + ch_clk_mask = ps2_npcx_ctrl_get_ch_clk_mask(channel_id); + if (enable) { + data->channel_enabled_mask |= ch_clk_mask; + /* Enable the relevant channel clock */ + inst->PSOSIG |= ch_clk_mask; + } else { + data->channel_enabled_mask &= ~ch_clk_mask; + /* Disable the relevant channel clock */ + inst->PSOSIG &= ~ch_clk_mask; + } + + irq_enable(DT_INST_IRQN(0)); + k_sem_give(&data->lock); + + return 0; +} + +static int ps2_npcx_ctrl_bus_busy(const struct device *dev) +{ + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + + /* + * The driver pulls the CLK for non-active channels to low when Start + * bit is detected and pull the CLK of the active channel low after + * Stop bit detected. The EOT bit is set when Stop bit is detected, + * but both SOT and EOT are cleared when all CLKs are pull low + * (due to Shift Mechanism is reset) + */ + return (IS_BIT_SET(inst->PSTAT, NPCX_PSTAT_SOT) || + IS_BIT_SET(inst->PSTAT, NPCX_PSTAT_EOT)) ? + -EBUSY : + 0; +} + +int ps2_npcx_ctrl_write(const struct device *dev, uint8_t channel_id, + uint8_t value) +{ + struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev); + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + int i = 0; + + if (channel_id >= NPCX_PS2_CH_COUNT) { + LOG_ERR("unexpected channel ID: %d", channel_id); + return -EINVAL; + } + + if (!(ps2_npcx_ctrl_get_ch_clk_mask(channel_id) & + data->channel_enabled_mask)) { + LOG_ERR("channel %d is not enabled", channel_id); + return -EINVAL; + } + + k_sem_take(&data->lock, K_FOREVER); + + while (ps2_npcx_ctrl_bus_busy(dev) && (i < PS2_RETRY_COUNT)) { + k_busy_wait(50); + i++; + } + + if (unlikely(i == PS2_RETRY_COUNT)) { + LOG_ERR("PS2 write attempt timed out"); + goto timeout_invalid; + } + + /* Set PS/2 in transmit mode */ + inst->PSCON |= BIT(NPCX_PSCON_XMT); + /* Enable Start Of Transaction interrupt */ + inst->PSIEN |= BIT(NPCX_PSIEN_SOTIE); + + /* Reset the shift mechanism */ + inst->PSOSIG = NPCX_PS2_SHIFT_MECH_RESET; + /* Inhibit communication should last at least 100 micro-seconds */ + k_busy_wait(100); + + /* Write the data to be transmitted */ + inst->PSDAT = value; + /* Apply the Request-to-send */ + inst->PSOSIG &= ~BIT(NPCX_PSOSIG_WDAT(channel_id)); + inst->PSOSIG |= ps2_npcx_ctrl_get_ch_clk_mask(channel_id); + if (k_sem_take(&data->tx_sync_sem, PS2_TRANSACTION_TIMEOUT) != 0) { + irq_disable(DT_INST_IRQN(0)); + LOG_ERR("PS/2 Tx timeout"); + /* Reset the shift mechanism */ + inst->PSOSIG = NPCX_PS2_SHIFT_MECH_RESET; + /* Change the PS/2 module to receive mode */ + inst->PSCON &= ~BIT(NPCX_PSCON_XMT); + /* + * Restore the channel back to enable according to + * channel_enabled_mask. + */ + inst->PSOSIG |= data->channel_enabled_mask; + irq_enable(DT_INST_IRQN(0)); + goto timeout_invalid; + } + + k_sem_give(&data->lock); + return 0; + +timeout_invalid: + k_sem_give(&data->lock); + return -ETIMEDOUT; +} + +static int ps2_npcx_ctrl_is_rx_error(const struct device *dev) +{ + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + uint8_t status; + + status = inst->PSTAT & (BIT(NPCX_PSTAT_PERR) | BIT(NPCX_PSTAT_RFERR)); + if (status) { + if (status & BIT(NPCX_PSTAT_PERR)) + LOG_ERR("RX parity error"); + if (status & BIT(NPCX_PSTAT_RFERR)) + LOG_ERR("RX Frame error"); + return -EIO; + } + + return 0; +} + +static void ps2_npcx_ctrl_isr(const struct device *dev) +{ + uint8_t active_ch, mask; + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev); + + /* + * ACH = 1 : Channel 0 + * ACH = 2 : Channel 1 + * ACH = 4 : Channel 2 + * ACH = 5 : Channel 3 + */ + active_ch = GET_FIELD(inst->PSTAT, NPCX_PSTAT_ACH); + active_ch = active_ch > 2 ? (active_ch - 2) : (active_ch - 1); + LOG_DBG("ACH: %d\n", active_ch); + + /* + * Inhibit PS/2 transaction of the other non-active channels by + * pulling down the clock signal + */ + mask = ~NPCX_PSOSIG_CLK_MASK_ALL | BIT(NPCX_PSOSIG_CLK(active_ch)); + inst->PSOSIG &= mask; + + /* PS/2 Start of Transaction */ + if (IS_BIT_SET(inst->PSTAT, NPCX_PSTAT_SOT) && + IS_BIT_SET(inst->PSIEN, NPCX_PSIEN_SOTIE)) { + /* + * Once set, SOT is not cleared until the shift mechanism + * is reset. Therefore, SOTIE should be cleared on the + * first occurrence of an SOT interrupt. + */ + inst->PSIEN &= ~BIT(NPCX_PSIEN_SOTIE); + LOG_DBG("SOT"); + /* PS/2 End of Transaction */ + } else if (IS_BIT_SET(inst->PSTAT, NPCX_PSTAT_EOT)) { + inst->PSIEN &= ~BIT(NPCX_PSIEN_EOTIE); + + /* + * Clear the CLK of active channel to reset + * the shift mechanism + */ + inst->PSOSIG &= ~BIT(NPCX_PSOSIG_CLK(active_ch)); + + /* Tx is done */ + if (IS_BIT_SET(inst->PSCON, NPCX_PSCON_XMT)) { + /* Change the PS/2 module to receive mode */ + inst->PSCON &= ~BIT(NPCX_PSCON_XMT); + k_sem_give(&data->tx_sync_sem); + } else { + if (ps2_npcx_ctrl_is_rx_error(dev) == 0) { + ps2_callback_t callback; + uint8_t data_in = inst->PSDAT; + + LOG_DBG("Recv:0x%02x", data_in); + callback = data->callback_isr[active_ch]; + if (callback != NULL) + callback(dev, data_in); + } + } + + /* Restore the enabled channel */ + inst->PSOSIG |= data->channel_enabled_mask; + /* + * Re-enable the Start Of Transaction interrupt when + * the shift mechanism is reset + */ + inst->PSIEN |= BIT(NPCX_PSIEN_SOTIE); + inst->PSIEN |= BIT(NPCX_PSIEN_EOTIE); + LOG_DBG("EOT"); + } +} + +/* PS/2 driver registration */ +static int ps2_npcx_ctrl_init(const struct device *dev); + +static struct ps2_npcx_ctrl_data ps2_npcx_ctrl_data_0; + +static const struct ps2_npcx_ctrl_config ps2_npcx_ctrl_config_0 = { + .base = DT_INST_REG_ADDR(0), + .clk_cfg = NPCX_DT_CLK_CFG_ITEM(0), +}; + +DEVICE_DT_INST_DEFINE(0, &ps2_npcx_ctrl_init, NULL, &ps2_npcx_ctrl_data_0, + &ps2_npcx_ctrl_config_0, POST_KERNEL, + CONFIG_PS2_INIT_PRIORITY, NULL); + +static int ps2_npcx_ctrl_init(const struct device *dev) +{ + const struct ps2_npcx_ctrl_config *const config = DRV_CONFIG(dev); + struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev); + struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev); + const struct device *clk_dev = device_get_binding(NPCX_CLK_CTRL_NAME); + int ret; + + /* Turn on PS/2 controller device clock */ + ret = clock_control_on(clk_dev, + (clock_control_subsys_t *)&config->clk_cfg); + if (ret < 0) { + LOG_ERR("Turn on PS/2 clock fail %d", ret); + return ret; + } + + /* Disable shift mechanism and configure PS/2 to received mode. */ + inst->PSCON = 0x0; + /* Set WDAT3-0 and clear CLK3-0 before enabling shift mechanism */ + inst->PSOSIG = NPCX_PS2_SHIFT_MECH_RESET; + /* + * PS/2 interrupt enable register + * [0] - : SOTIE = 1: Start Of Transaction Interrupt Enable + * [1] - : EOTIE = 1: End Of Transaction Interrupt Enable + * [4] - : WUE = 1: Wake-Up Enable + * [7] - : CLK_SEL = 1: Select Free-Run clock as the basic clock + * 0: Select APB1 clock as the basic clock + */ + inst->PSIEN = BIT(NPCX_PSIEN_SOTIE) | BIT(NPCX_PSIEN_EOTIE) | + BIT(NPCX_PSIEN_PS2_WUE); + if (config->clk_cfg.bus == NPCX_CLOCK_BUS_FREERUN) + inst->PSIEN |= BIT(NPCX_PSIEN_PS2_CLK_SEL); + /* Enable weak internal pull-up */ + inst->PSCON |= BIT(NPCX_PSCON_WPUED); + /* Enable shift mechanism */ + inst->PSCON |= BIT(NPCX_PSCON_EN); + + k_sem_init(&data->lock, 1, 1); + k_sem_init(&data->tx_sync_sem, 0, 1); + + IRQ_CONNECT(DT_INST_IRQN(0), DT_INST_IRQ(0, priority), + ps2_npcx_ctrl_isr, DEVICE_DT_INST_GET(0), 0); + + irq_enable(DT_INST_IRQN(0)); + + return 0; +} diff --git a/drivers/ps2/ps2_npcx_controller.h b/drivers/ps2/ps2_npcx_controller.h new file mode 100644 index 00000000000..10eed41bd1a --- /dev/null +++ b/drivers/ps2/ps2_npcx_controller.h @@ -0,0 +1,59 @@ +/* + * Copyright (c) 2021 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef ZEPHYR_DRIVERS_PS2_PS2_NPCX_CONTROLLER_H_ +#define ZEPHYR_DRIVERS_PS2_PS2_NPCX_CONTROLLER_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief Write @p value to a PS/2 device via the PS/2 controller. + * + * @param dev Pointer to the device structure for PS/2 controller instance. + * @param channel_id Channel ID of the PS/2 to write data. + * @param value the data write to the PS/2 device. + * + * @retval 0 If successful. + * @retval -EINVAL Channel ID is invlaid. + * @retval -ETIMEDOUT Timeout occurred for a PS/2 write transaction. + */ +int ps2_npcx_ctrl_write(const struct device *dev, uint8_t channel_id, + uint8_t value); + +/** + * @brief Set the PS/2 controller to turn on/off the PS/2 channel. + * + * @param dev Pointer to the device structure for PS/2 controller instance. + * @param channel_id Channel ID of the PS/2 to enable or disable. + * @param enable True to enable channel, false to disable channel. + * + * @retval 0 If successful. + * @retval -EINVAL Channel ID is invlaid. + */ +int ps2_npcx_ctrl_enable_interface(const struct device *dev, uint8_t channel, + bool enable); + +/** + * @brief Record the callback_isr function pointer for the given PS/2 channel. + * + * @param dev Pointer to the device structure for PS/2 controller instance. + * @param channel_id Channel ID of the PS/2 to configure the callback_isr. + * @param callback_isr Pointer to the callback_isr. + * + * @retval 0 If successful. + * @retval -EINVAL callback_isr is NULL. + */ +int ps2_npcx_ctrl_configure(const struct device *dev, uint8_t channel_id, + ps2_callback_t callback_isr); +#ifdef __cplusplus +} +#endif + +#endif /* ZEPHYR_DRIVERS_PS2_PS2_NPCX_CONTROLLER_H_ */ diff --git a/dts/arm/nuvoton/npcx.dtsi b/dts/arm/nuvoton/npcx.dtsi index d64a743dc43..8a97ef0075d 100644 --- a/dts/arm/nuvoton/npcx.dtsi +++ b/dts/arm/nuvoton/npcx.dtsi @@ -621,6 +621,47 @@ pin = <5>; label = "PSL_OUT"; }; + + ps2_ctrl0: ps2@400b1000 { + compatible = "nuvoton,npcx-ps2-ctrl"; + reg = <0x400b1000 0x1000>; + interrupts = <21 4>; + clocks = <&pcc NPCX_CLOCK_BUS_FREERUN NPCX_PWDWN_CTL1 3>; + label = "PS2_CTRL_0"; + + /* PS2 Channels - Please use them as PS2 node */ + ps2_channel0: io_ps2_channel0 { + compatible = "nuvoton,npcx-ps2-channel"; + channel = <0x00>; + pinctrl-0 = <&alt3_ps2_0_sl>; /* PIN67.70 */ + label = "PS2_CHANNEL_0"; + status = "disabled"; + }; + + ps2_channel1: io_ps2_channel1 { + compatible = "nuvoton,npcx-ps2-channel"; + channel = <0x01>; + pinctrl-0 = <&alt3_ps2_1_sl>; /* PIN62.63 */ + label = "PS2_CHANNEL_1"; + status = "disabled"; + }; + + ps2_channel2: io_ps2_channel2 { + compatible = "nuvoton,npcx-ps2-channel"; + channel = <0x02>; + pinctrl-0 = <&alt3_ps2_2_sl>; /* PIN37.34 */ + label = "PS2_CHANNEL_2"; + status = "disabled"; + }; + + ps2_channel3: io_ps2_channel3 { + compatible = "nuvoton,npcx-ps2-channel"; + channel = <0x03>; + pinctrl-0 = <&altc_ps2_3_sl2>; /* PINA6.A7 */ + label = "PS2_CHANNEL_3"; + status = "disabled"; + }; + }; }; }; diff --git a/dts/bindings/ps2/nuvoton,npcx-ps2-channel.yaml b/dts/bindings/ps2/nuvoton,npcx-ps2-channel.yaml new file mode 100644 index 00000000000..f50f26c24e0 --- /dev/null +++ b/dts/bindings/ps2/nuvoton,npcx-ps2-channel.yaml @@ -0,0 +1,19 @@ +# Copyright (c) 2021 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCX-PS/2 channel pads node + +compatible: "nuvoton,npcx-ps2-channel" + +include: base.yaml + +properties: + channel: + type: int + required: true + description: index of i2c channel + + pinctrl-0: + type: phandles + required: true + description: configurations of pinmux controllers diff --git a/dts/bindings/ps2/nuvoton,npcx-ps2-ctrl.yaml b/dts/bindings/ps2/nuvoton,npcx-ps2-ctrl.yaml new file mode 100644 index 00000000000..f1571235f75 --- /dev/null +++ b/dts/bindings/ps2/nuvoton,npcx-ps2-ctrl.yaml @@ -0,0 +1,20 @@ +# Copyright (c) 2021 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCX-PS/2 controller node + +compatible: "nuvoton,npcx-ps2-ctrl" + +include: base.yaml + +bus: ps2 + +properties: + reg: + required: true + + clocks: + required: true + + interrupts: + required: true diff --git a/soc/arm/nuvoton_npcx/common/reg/reg_def.h b/soc/arm/nuvoton_npcx/common/reg/reg_def.h index a3fd83ee747..bec522d0835 100644 --- a/soc/arm/nuvoton_npcx/common/reg/reg_def.h +++ b/soc/arm/nuvoton_npcx/common/reg/reg_def.h @@ -1326,4 +1326,60 @@ struct dbg_reg { /* Debug Interface registers fields */ #define NPCX_DBGFRZEN3_GLBL_FRZ_DIS 7 +/* PS/2 Interface registers */ +struct ps2_reg { + /* 0x000: PS/2 Data */ + volatile uint8_t PSDAT; + volatile uint8_t reserved1; + /* 0x002: PS/2 Status */ + volatile uint8_t PSTAT; + volatile uint8_t reserved2; + /* 0x004: PS/2 Control */ + volatile uint8_t PSCON; + volatile uint8_t reserved3; + /* 0x006: PS/2 Output Signal */ + volatile uint8_t PSOSIG; + volatile uint8_t reserved4; + /* 0x008: PS/2 Iutput Signal */ + volatile uint8_t PSISIG; + volatile uint8_t reserved5; + /* 0x00A: PS/2 Interrupt Enable */ + volatile uint8_t PSIEN; + volatile uint8_t reserved6; +}; + +/* PS/2 Interface registers fields */ +#define NPCX_PSTAT_SOT 0 +#define NPCX_PSTAT_EOT 1 +#define NPCX_PSTAT_PERR 2 +#define NPCX_PSTAT_ACH FIELD(3, 3) +#define NPCX_PSTAT_RFERR 6 + +#define NPCX_PSCON_EN 0 +#define NPCX_PSCON_XMT 1 +#define NPCX_PSCON_HDRV FIELD(2, 2) +#define NPCX_PSCON_IDB FIELD(4, 3) +#define NPCX_PSCON_WPUED 7 + +#define NPCX_PSOSIG_WDAT0 0 +#define NPCX_PSOSIG_WDAT1 1 +#define NPCX_PSOSIG_WDAT2 2 +#define NPCX_PSOSIG_CLK0 3 +#define NPCX_PSOSIG_CLK1 4 +#define NPCX_PSOSIG_CLK2 5 +#define NPCX_PSOSIG_WDAT3 6 +#define NPCX_PSOSIG_CLK3 7 +#define NPCX_PSOSIG_CLK(n) (((n) < 3) ? ((n) + 3) : 7) +#define NPCX_PSOSIG_WDAT(n) (((n) < 3) ? ((n) + 0) : 6) +#define NPCX_PSOSIG_CLK_MASK_ALL \ + (BIT(NPCX_PSOSIG_CLK0) | \ + BIT(NPCX_PSOSIG_CLK1) | \ + BIT(NPCX_PSOSIG_CLK2) | \ + BIT(NPCX_PSOSIG_CLK3)) + +#define NPCX_PSIEN_SOTIE 0 +#define NPCX_PSIEN_EOTIE 1 +#define NPCX_PSIEN_PS2_WUE 4 +#define NPCX_PSIEN_PS2_CLK_SEL 7 + #endif /* _NUVOTON_NPCX_REG_DEF_H */ diff --git a/soc/arm/nuvoton_npcx/common/registers.c b/soc/arm/nuvoton_npcx/common/registers.c index eaf23930aee..7cd4cc6b718 100644 --- a/soc/arm/nuvoton_npcx/common/registers.c +++ b/soc/arm/nuvoton_npcx/common/registers.c @@ -152,3 +152,12 @@ NPCX_REG_SIZE_CHECK(dbg_reg, 0x06); NPCX_REG_OFFSET_CHECK(dbg_reg, DBGCTRL, 0x000); NPCX_REG_OFFSET_CHECK(dbg_reg, DBGFRZEN2, 0x003); NPCX_REG_OFFSET_CHECK(dbg_reg, DBGFRZEN4, 0x005); + +/* PS/2 Interface register structure check */ +NPCX_REG_SIZE_CHECK(ps2_reg, 0x00c); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSDAT, 0x000); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSTAT, 0x002); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSCON, 0x004); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSOSIG, 0x006); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSISIG, 0x008); +NPCX_REG_OFFSET_CHECK(ps2_reg, PSIEN, 0x00a);