diff --git a/boards/nuvoton/npcm400f_evb/doc/index.rst b/boards/nuvoton/npcm400f_evb/doc/index.rst new file mode 100644 index 00000000000000..581235c20278e8 --- /dev/null +++ b/boards/nuvoton/npcm400f_evb/doc/index.rst @@ -0,0 +1,99 @@ +.. _npcm400f_evb: + +Nuvoton NPCM400F_EVB +#################### + +Overview +******** + +The NPCX400F_EVB kit is a development platform to evaluate the +Nuvoton NPCM4 series microcontrollers. This board needs to be mated with +part number NPCM400F. + +.. image:: npcm400f_evb.jpg + :align: center + :alt: NPCM400F Evaluation Board + +Hardware +******** + +- ARM Cortex-M4F Processor +- 768 KB RAM and 64 KB boot ROM +- ADC & GPIO headers +- UART0 and UART1 + +Supported Features +================== + +The following features are supported: + ++-----------+------------+-------------------------------------+ +| Interface | Controller | Driver/Component | ++===========+============+=====================================+ +| NVIC | on-chip | nested vector interrupt controller | ++-----------+------------+-------------------------------------+ +| ADC | on-chip | adc controller | ++-----------+------------+-------------------------------------+ +| CLOCK | on-chip | reset and clock control | ++-----------+------------+-------------------------------------+ +| GPIO | on-chip | gpio | ++-----------+------------+-------------------------------------+ +| I2C | on-chip | i2c port/controller | ++-----------+------------+-------------------------------------+ +| I3C | on-chip | i3c port/controller | ++-----------+------------+-------------------------------------+ +| PINMUX | on-chip | pinmux | ++-----------+------------+-------------------------------------+ +| UART | on-chip | serial port-polling; | +| | | serial port-interrupt | ++-----------+------------+-------------------------------------+ +| WDT | on-chip | watchdog | ++-----------+------------+-------------------------------------+ + +The default configuration can be found in the defconfig file: +:zephyr_file:`boards/nuvoton/npcm400f_evb/npcm400f_evb_defconfig` + + +Connections and IOs +=================== + +Nuvoton to provide the schematic for this board. + +System Clock +============ + +The NPCX400F MCU is configured to use the 96Mhz. + +Serial Port +=========== + +UART0 is configured for serial logs. + +Programming and Debugging +************************* + +This board comes with a Cortex ETM port which facilitates tracing and debugging +using a single physical connection. In addition, it comes with sockets for +JTAG-only sessions. + +Flashing +======== + +If the correct headers are installed, this board supports J-TAG. + +To flash with J-TAG, install the drivers for your programmer, for example: +SEGGER J-link's drivers are at https://www.segger.com/downloads/jlink/ + +Build and flash the shell module sample.:: + + west build -t clean && \ + west build -c -p auto -b npcm400f_evb samples/subsys/shell/shell_module/ && \ + west flash --openocd /usr/local/bin/openocd + +Debugging +========= + +Use JTAG/SWD with a J-Link + +References +********** diff --git a/boards/nuvoton/npcm400f_evb/doc/npcm400f_evb.jpg b/boards/nuvoton/npcm400f_evb/doc/npcm400f_evb.jpg new file mode 100644 index 00000000000000..a9781f7a9fc7ec Binary files /dev/null and b/boards/nuvoton/npcm400f_evb/doc/npcm400f_evb.jpg differ diff --git a/boards/nuvoton/npcm400f_evb/npcm400f_evb.dts b/boards/nuvoton/npcm400f_evb/npcm400f_evb.dts index 1e84578d30feb8..8f2ede6107fcb0 100644 --- a/boards/nuvoton/npcm400f_evb/npcm400f_evb.dts +++ b/boards/nuvoton/npcm400f_evb/npcm400f_evb.dts @@ -7,6 +7,7 @@ /dts-v1/; #include +#include / { model = "Nuvoton NPCM400F evaluation board"; @@ -18,5 +19,4 @@ aliases { }; - }; diff --git a/boards/nuvoton/npcm400f_evb/npcm400f_evb_defconfig b/boards/nuvoton/npcm400f_evb/npcm400f_evb_defconfig index eec39d055095c5..830affe8ab9733 100644 --- a/boards/nuvoton/npcm400f_evb/npcm400f_evb_defconfig +++ b/boards/nuvoton/npcm400f_evb/npcm400f_evb_defconfig @@ -8,8 +8,18 @@ CONFIG_SRAM_VECTOR_TABLE=y CONFIG_BOOTLOADER_SRAM_SIZE=0 # General Kernel Options CONFIG_SYS_CLOCK_HW_CYCLES_PER_SEC=96000000 +# CONFIG_FLASH_LOAD_OFFSET=0x600 CONFIG_XIP=n +# CONFIG_ARM_MPU=y + +# Clock Driver +CONFIG_CLOCK_CONTROL=y +CONFIG_CLOCK_CONTROL_NPCM=y + +# Pinctrl Driver +CONFIG_PINCTRL=y +CONFIG_PINCTRL_NPCM=y # UART Driver CONFIG_SERIAL=n @@ -18,3 +28,7 @@ CONFIG_SERIAL=n # Console Driver CONFIG_CONSOLE=n CONFIG_UART_CONSOLE=n + +# GPIO Driver +CONFIG_GPIO=y +CONFIG_GPIO_NPCM=y diff --git a/drivers/clock_control/CMakeLists.txt b/drivers/clock_control/CMakeLists.txt index 596b07676e0353..7d8ae6fb3612b0 100644 --- a/drivers/clock_control/CMakeLists.txt +++ b/drivers/clock_control/CMakeLists.txt @@ -17,6 +17,7 @@ zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_MCUX_PCC clock_cont zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_MCUX_SCG clock_control_mcux_scg.c) zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_MCUX_SIM clock_control_mcux_sim.c) zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_MCUX_SYSCON clock_control_mcux_syscon.c) +zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_NPCM clock_control_npcm.c) zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_NPCX clock_control_npcx.c) zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_NRF clock_control_nrf.c) zephyr_library_sources_ifdef(CONFIG_CLOCK_CONTROL_NRF_DRIVER_CALIBRATION nrf_clock_calibration.c) diff --git a/drivers/clock_control/Kconfig b/drivers/clock_control/Kconfig index b0c6cf8de48c7d..8188f93e9cc7a4 100644 --- a/drivers/clock_control/Kconfig +++ b/drivers/clock_control/Kconfig @@ -50,6 +50,8 @@ source "drivers/clock_control/Kconfig.mcux_sim" source "drivers/clock_control/Kconfig.mcux_syscon" +source "drivers/clock_control/Kconfig.npcm" + source "drivers/clock_control/Kconfig.npcx" source "drivers/clock_control/Kconfig.rv32m1" diff --git a/drivers/clock_control/Kconfig.npcm b/drivers/clock_control/Kconfig.npcm new file mode 100644 index 00000000000000..cdf96bfb02f825 --- /dev/null +++ b/drivers/clock_control/Kconfig.npcm @@ -0,0 +1,11 @@ +# NPCM Clock controller driver configuration options + +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +config CLOCK_CONTROL_NPCM + bool "NPCM clock controller driver" + default y + depends on DT_HAS_NUVOTON_NPCM_PCC_ENABLED + help + Enable support for NPCM clock controller driver. diff --git a/drivers/clock_control/clock_control_npcm.c b/drivers/clock_control/clock_control_npcm.c new file mode 100644 index 00000000000000..d1c043233d3ec8 --- /dev/null +++ b/drivers/clock_control/clock_control_npcm.c @@ -0,0 +1,157 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT nuvoton_npcm_pcc + +#include +#include +#include + +#include +LOG_MODULE_REGISTER(clock_control_npcm, LOG_LEVEL_ERR); + +/* Driver config */ +struct npcm_pcc_config { + /* cdcg device base address */ + uintptr_t base_cdcg; + /* pmc device base address */ + uintptr_t base_pmc; +}; + +/* Driver convenience defines */ +#define DRV_CONFIG(dev) \ + ((const struct npcm_pcc_config *)(dev)->config) + +#define HAL_CDCG_INST(dev) \ + (struct cdcg_reg *)(DRV_CONFIG(dev)->base_cdcg) + +/* Clock controller local functions */ +static inline int npcm_clock_control_on(const struct device *dev, + clock_control_subsys_t sub_system) +{ + ARG_UNUSED(dev); + struct npcm_clk_cfg *clk_cfg = (struct npcm_clk_cfg *)(sub_system); + const uint32_t pmc_base = DRV_CONFIG(dev)->base_pmc; + + if (clk_cfg->ctrl >= NPCM_PWDWN_CTL_COUNT) + return -EINVAL; + + /* Clear related PD (Power-Down) bit of module to turn on clock */ + NPCM_PWDWN_CTL(pmc_base, clk_cfg->ctrl) &= ~(BIT(clk_cfg->bit)); + return 0; +} + +static inline int npcm_clock_control_off(const struct device *dev, + clock_control_subsys_t sub_system) +{ + ARG_UNUSED(dev); + struct npcm_clk_cfg *clk_cfg = (struct npcm_clk_cfg *)(sub_system); + const uint32_t pmc_base = DRV_CONFIG(dev)->base_pmc; + + if (clk_cfg->ctrl >= NPCM_PWDWN_CTL_COUNT) { + return -EINVAL; + } + + /* Set related PD (Power-Down) bit of module to turn off clock */ + NPCM_PWDWN_CTL(pmc_base, clk_cfg->ctrl) |= BIT(clk_cfg->bit); + return 0; +} + +static int npcm_clock_control_get_subsys_rate(const struct device *dev, + clock_control_subsys_t sub_system, + uint32_t *rate) +{ + ARG_UNUSED(dev); + struct npcm_clk_cfg *clk_cfg = (struct npcm_clk_cfg *)(sub_system); + + switch (clk_cfg->bus) { + case NPCM_CLOCK_BUS_APB1: + *rate = NPCM_APB_CLOCK(1); + break; + case NPCM_CLOCK_BUS_APB2: + *rate = NPCM_APB_CLOCK(2); + break; + case NPCM_CLOCK_BUS_APB3: + *rate = NPCM_APB_CLOCK(3); + break; + case NPCM_CLOCK_BUS_AHB6: + *rate = CORE_CLK/(AHB6DIV_VAL + 1); + break; + case NPCM_CLOCK_BUS_FIU: + *rate = CORE_CLK/(FIUDIV_VAL + 1); + break; + case NPCM_CLOCK_BUS_CORE: + *rate = CORE_CLK; + break; + case NPCM_CLOCK_BUS_LFCLK: + *rate = LFCLK; + break; + case NPCM_CLOCK_BUS_FMCLK: + *rate = FMCLK; + break; + default: + *rate = 0U; + /* Invalid parameters */ + return -EINVAL; + } + + return 0; +} + +/* Clock controller driver registration */ +static struct clock_control_driver_api npcm_clock_control_api = { + .on = npcm_clock_control_on, + .off = npcm_clock_control_off, + .get_rate = npcm_clock_control_get_subsys_rate, +}; + +static int npcm_clock_control_init(const struct device *dev) +{ + struct cdcg_reg *const inst_cdcg = HAL_CDCG_INST(dev); + + /* + * Resetting the OFMCLK (even to the same value) will make the clock + * unstable for a little which can affect peripheral communication like + * eSPI. Skip this if not needed. + */ + if (inst_cdcg->HFCGN != HFCGN_VAL || inst_cdcg->HFCGML != HFCGML_VAL + || inst_cdcg->HFCGMH != HFCGMH_VAL) { + /* + * Configure frequency multiplier M/N values according to + * the requested OFMCLK (Unit:Hz). + */ + inst_cdcg->HFCGN = HFCGN_VAL; + inst_cdcg->HFCGML = HFCGML_VAL; + inst_cdcg->HFCGMH = HFCGMH_VAL; + + /* Load M and N values into the frequency multiplier */ + inst_cdcg->HFCGCTRL |= BIT(NPCM_HFCGCTRL_LOAD); + /* Wait for stable */ + while (IS_BIT_SET(inst_cdcg->HFCGCTRL, NPCM_HFCGCTRL_CLK_CHNG)) + ; + } + + /* Set all clock prescalers of core and peripherals. */ + inst_cdcg->HFCGP = ((FPRED_VAL << 4) | AHB6DIV_VAL); + inst_cdcg->HFCBCD = (APB1DIV_VAL | (APB2DIV_VAL << 4)); + inst_cdcg->HFCBCD1 = FIUDIV_VAL; + inst_cdcg->HFCBCD2 = APB3DIV_VAL; + + return 0; +} + +const struct npcm_pcc_config pcc_config = { + .base_cdcg = DT_INST_REG_ADDR_BY_NAME(0, cdcg), + .base_pmc = DT_INST_REG_ADDR_BY_NAME(0, pmc), +}; + +DEVICE_DT_INST_DEFINE(0, + &npcm_clock_control_init, + NULL, + NULL, &pcc_config, + PRE_KERNEL_1, + CONFIG_KERNEL_INIT_PRIORITY_OBJECTS, + &npcm_clock_control_api); diff --git a/drivers/gpio/CMakeLists.txt b/drivers/gpio/CMakeLists.txt index 787a10d7dd5d41..38d200f750e286 100644 --- a/drivers/gpio/CMakeLists.txt +++ b/drivers/gpio/CMakeLists.txt @@ -52,6 +52,7 @@ zephyr_library_sources_ifdef(CONFIG_GPIO_NCT38XX gpio_nct38xx.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NCT38XX gpio_nct38xx_port.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NCT38XX_ALERT gpio_nct38xx_alert.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NEORV32 gpio_neorv32.c) +zephyr_library_sources_ifdef(CONFIG_GPIO_NPCM gpio_npcm.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NPCX gpio_npcx.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NPM1300 gpio_npm1300.c) zephyr_library_sources_ifdef(CONFIG_GPIO_NPM6001 gpio_npm6001.c) diff --git a/drivers/gpio/Kconfig b/drivers/gpio/Kconfig index 9ce2b7f5859f96..7c967c878cb977 100644 --- a/drivers/gpio/Kconfig +++ b/drivers/gpio/Kconfig @@ -138,6 +138,7 @@ source "drivers/gpio/Kconfig.mcux_rgpio" source "drivers/gpio/Kconfig.mmio32" source "drivers/gpio/Kconfig.nct38xx" source "drivers/gpio/Kconfig.neorv32" +source "drivers/gpio/Kconfig.npcm" source "drivers/gpio/Kconfig.npcx" source "drivers/gpio/Kconfig.npm1300" source "drivers/gpio/Kconfig.npm6001" diff --git a/drivers/gpio/Kconfig.npcm b/drivers/gpio/Kconfig.npcm new file mode 100644 index 00000000000000..6893ee4387a4d4 --- /dev/null +++ b/drivers/gpio/Kconfig.npcm @@ -0,0 +1,13 @@ +# NPCX GPIO driver configuration options + +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +config GPIO_NPCM + bool "Nuvoton NPCM enhance Super I/O (eSIO) gpio driver" + default y + depends on DT_HAS_NUVOTON_NPCM_GPIO_ENABLED + help + This option enables the GPIO driver for NPCM family of + processors. + Say y if you wish to use serial port on NPCM MCU. diff --git a/drivers/gpio/gpio_npcm.c b/drivers/gpio/gpio_npcm.c new file mode 100644 index 00000000000000..e35520ac073bb0 --- /dev/null +++ b/drivers/gpio/gpio_npcm.c @@ -0,0 +1,430 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#define DT_DRV_COMPAT nuvoton_npcm_gpio + +#include +#include +#include +#include + +#include +#include "soc_gpio.h" +#include "soc_miwu.h" + +#include +LOG_MODULE_REGISTER(gpio_npcm, LOG_LEVEL_ERR); + +/* GPIO module instances */ +#define NPCM_GPIO_DEV(inst) DEVICE_DT_INST_GET(inst), +static const struct device *gpio_devs[] = { + DT_INST_FOREACH_STATUS_OKAY(NPCM_GPIO_DEV) +}; + +/* Driver config */ +struct gpio_npcm_config { + /* gpio_driver_config needs to be first */ + struct gpio_driver_config common; + /* GPIO controller base address */ + uintptr_t base; + /* IO port */ + int port; + /* Mapping table between gpio bits and wui */ + struct npcm_wui wui_maps[]; +}; + +/* Driver data */ +struct gpio_npcm_data { + /* gpio_driver_data needs to be first */ + struct gpio_driver_data common; +}; + +struct npcm_scfg_config { + /* scfg device base address */ + uintptr_t base_scfg; +}; + +static const struct npcm_scfg_config npcm_scfg_cfg = { + .base_scfg = DT_REG_ADDR_BY_NAME(DT_NODELABEL(scfg), scfg), +}; + +/* Driver convenience defines */ +#define HAL_INSTANCE(dev) \ + ((struct gpio_reg *)((const struct gpio_npcm_config *)(dev)->config)->base) + +#define HAL_SFCG_INST() (struct scfg_reg *)(npcm_scfg_cfg.base_scfg) + +/* Platform specific GPIO functions */ +const struct device *npcm_get_gpio_dev(int port) +{ + if (port >= ARRAY_SIZE(gpio_devs)) + return NULL; + + return gpio_devs[port]; +} + +#ifdef CONFIG_NPCM_MIWU +void npcm_gpio_enable_io_pads(const struct device *dev, int pin) +{ + const struct gpio_npcm_config *const config = dev->config; + const struct npcm_wui *io_wui = &config->wui_maps[pin]; + + if (io_wui->table == NPCM_MIWU_TABLE_NONE) { + LOG_ERR("Cannot enable GPIO(%x, %d) pad", config->port, pin); + return; + } + + /* + * If this pin is configurred as a GPIO interrupt source, do not + * implement bypass. Or ec cannot wake up via this event. + */ + if (pin < NPCM_GPIO_PORT_PIN_NUM && !npcm_miwu_irq_get_state(io_wui)) { + npcm_miwu_io_enable(io_wui); + } +} + +void npcm_gpio_disable_io_pads(const struct device *dev, int pin) +{ + const struct gpio_npcm_config *const config = dev->config; + const struct npcm_wui *io_wui = &config->wui_maps[pin]; + + if (io_wui->table == NPCM_MIWU_TABLE_NONE) { + LOG_ERR("Cannot enable GPIO(%x, %d) pad", config->port, pin); + return; + } + + /* + * If this pin is configurred as a GPIO interrupt source, do not + * implement bypass. Or ec cannot wake up via this event. + */ + if (pin < NPCM_GPIO_PORT_PIN_NUM && !npcm_miwu_irq_get_state(io_wui)) { + npcm_miwu_io_disable(io_wui); + } +} +#else +void npcm_gpio_enable_io_pads(const struct device *dev, int pin) +{ +} +void npcm_gpio_disable_io_pads(const struct device *dev, int pin) +{ +} +#endif + +/* GPIO api functions */ +static int gpio_npcm_config(const struct device *dev, + gpio_pin_t pin, gpio_flags_t flags) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + struct scfg_reg *inst_scfg = HAL_SFCG_INST(); + uint32_t mask = BIT(pin); + + /* Don't support simultaneous in/out mode */ + if (((flags & GPIO_INPUT) != 0) && ((flags & GPIO_OUTPUT) != 0)) { + return -ENOTSUP; + } + + /* Don't support "open source" mode */ + if (((flags & GPIO_SINGLE_ENDED) != 0) && + ((flags & GPIO_LINE_OPEN_DRAIN) == 0)) { + return -ENOTSUP; + } + + /* + * Configure pin as input, if requested. Output is configured only + * after setting all other attributes, so as not to create a + * temporary incorrect logic state 0:input 1:output + */ + if ((flags & GPIO_OUTPUT) == 0) + inst->PDIR &= ~mask; + + /* Select open drain 0:push-pull 1:open-drain */ + if ((flags & GPIO_OPEN_DRAIN) != 0) + inst->PTYPE |= mask; + else + inst->PTYPE &= ~mask; + + /* Select opend drain with pull up need enable GPIO_PULL_EN */ + if (((flags & GPIO_OPEN_DRAIN) != 0) && + ((flags & GPIO_PULL_UP) != 0)) { + inst_scfg->DEVALTCX |= BIT(NPCM_DEVALTCX_GPIO_PULL_EN); + } + + /* Select pull-up/down of GPIO 0:pull-up 1:pull-down */ + if ((flags & GPIO_PULL_UP) != 0) { + inst->PPUD &= ~mask; + inst->PPULL |= mask; + } else if ((flags & GPIO_PULL_DOWN) != 0) { + inst->PPUD |= mask; + inst->PPULL |= mask; + } else { + /* disable pull down/up */ + inst->PPULL &= ~mask; + } + + /* Set level 0:low 1:high */ + if ((flags & GPIO_OUTPUT_INIT_HIGH) != 0) + inst->PDOUT |= mask; + else if ((flags & GPIO_OUTPUT_INIT_LOW) != 0) + inst->PDOUT &= ~mask; + + /* Configure pin as output, if requested 0:input 1:output */ + if ((flags & GPIO_OUTPUT) != 0) + inst->PDIR |= mask; + + return 0; +} + +#ifdef CONFIG_GPIO_GET_CONFIG +static int gpio_npcm_pin_get_config(const struct device *port, gpio_pin_t pin, + gpio_flags_t *out_flags) +{ + const struct gpio_npcm_config *const config = port->config; + struct gpio_reg *const inst = HAL_INSTANCE(port); + uint32_t mask = BIT(pin); + gpio_flags_t flags = 0; + + /* 0:input 1:output */ + if (inst->PDIR & mask) { + flags |= GPIO_OUTPUT; + + /* 0:push-pull 1:open-drain */ + if (inst->PTYPE & mask) { + flags |= GPIO_OPEN_DRAIN; + } + + /* 0:low 1:high */ + if (inst->PDOUT & mask) { + flags |= GPIO_OUTPUT_HIGH; + } else { + flags |= GPIO_OUTPUT_LOW; + } + } else { + flags |= GPIO_INPUT; + + /* 0:disabled 1:enabled pull */ + if (inst->PPULL & mask) { + /* 0:pull-up 1:pull-down */ + if (inst->PPUD & mask) { + flags |= GPIO_PULL_DOWN; + } else { + flags |= GPIO_PULL_UP; + } + } + } + + *out_flags = flags; + + return 0; +} +#endif + +static int gpio_npcm_port_get_raw(const struct device *dev, + gpio_port_value_t *value) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + + /* Get raw bits of GPIO input registers */ + *value = inst->PDIN; + + return 0; +} + +static int gpio_npcm_port_set_masked_raw(const struct device *dev, + gpio_port_pins_t mask, + gpio_port_value_t value) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + uint8_t out = inst->PDOUT; + + inst->PDOUT = ((out & ~mask) | (value & mask)); + + return 0; +} + +static int gpio_npcm_port_set_bits_raw(const struct device *dev, + gpio_port_value_t mask) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + + /* Set raw bits of GPIO output registers */ + inst->PDOUT |= mask; + + return 0; +} + +static int gpio_npcm_port_clear_bits_raw(const struct device *dev, + gpio_port_value_t mask) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + + /* Clear raw bits of GPIO output registers */ + inst->PDOUT &= ~mask; + + return 0; +} + +static int gpio_npcm_port_toggle_bits(const struct device *dev, + gpio_port_value_t mask) +{ + struct gpio_reg *const inst = HAL_INSTANCE(dev); + + /* Toggle raw bits of GPIO output registers */ + inst->PDOUT ^= mask; + + return 0; +} + +#ifdef CONFIG_NPCM_MIWU +static int gpio_npcm_pin_interrupt_configure(const struct device *dev, + gpio_pin_t pin, + enum gpio_int_mode mode, + enum gpio_int_trig trig) +{ + const struct gpio_npcm_config *const config = dev->config; + + if (config->wui_maps[pin].table == NPCM_MIWU_TABLE_NONE) { + LOG_ERR("Cannot configure GPIO(%x, %d)", config->port, pin); + return -EINVAL; + } + + LOG_DBG("pin_int_conf (%d, %d) match (%d, %d, %d)!!!", + config->port, pin, config->wui_maps[pin].table, + config->wui_maps[pin].group, + config->wui_maps[pin].bit); + + /* Disable irq of wake-up input io-pads before configuring them */ + npcm_miwu_irq_disable(&config->wui_maps[pin]); + + /* Configure and enable interrupt? */ + if (mode != GPIO_INT_MODE_DISABLED) { + enum miwu_int_mode miwu_mode; + enum miwu_int_trig miwu_trig; + int ret = 0; + + /* Determine interrupt is level or edge mode? */ + if (mode == GPIO_INT_MODE_EDGE) { + miwu_mode = NPCM_MIWU_MODE_EDGE; + } else { + miwu_mode = NPCM_MIWU_MODE_LEVEL; + } + + /* Determine trigger mode is low, high or both? */ + if (trig == GPIO_INT_TRIG_LOW) { + miwu_trig = NPCM_MIWU_TRIG_LOW; + } else if (trig == GPIO_INT_TRIG_HIGH) { + miwu_trig = NPCM_MIWU_TRIG_HIGH; + } else if (trig == GPIO_INT_TRIG_BOTH) { + miwu_trig = NPCM_MIWU_TRIG_BOTH; + } else { + LOG_ERR("Invalid interrupt trigger type %d", trig); + return -EINVAL; + } + + /* Call MIWU routine to setup interrupt configuration */ + ret = npcm_miwu_interrupt_configure(&config->wui_maps[pin], + miwu_mode, miwu_trig); + if (ret != 0) { + LOG_ERR("Configure MIWU interrupt failed"); + return ret; + } + + /* Enable it after configuration is completed */ + npcm_miwu_irq_enable(&config->wui_maps[pin]); + } + + return 0; +} +#else +static int gpio_npcm_pin_interrupt_configure(const struct device *dev, + gpio_pin_t pin, + enum gpio_int_mode mode, + enum gpio_int_trig trig) +{ + return -EINVAL; +} +#endif + + +#ifdef CONFIG_NPCM_MIWU +static int gpio_npcm_manage_callback(const struct device *dev, + struct gpio_callback *callback, bool set) +{ + const struct gpio_npcm_config *const config = dev->config; + struct miwu_io_callback *miwu_cb = (struct miwu_io_callback *)callback; + int pin = find_lsb_set(callback->pin_mask) - 1; + + /* pin_mask should not be zero */ + if (pin < 0) { + return -EINVAL; + } + + /* Has the IO pin valid MIWU input source? */ + if (config->wui_maps[pin].table == NPCM_MIWU_TABLE_NONE) { + LOG_ERR("Cannot manage GPIO(%x, %d) callback!", config->port, + pin); + return -EINVAL; + } + + /* Initialize WUI information in unused bits field */ + npcm_miwu_init_gpio_callback(miwu_cb, &config->wui_maps[pin], + config->port); + + /* Insert or remove a IO callback which being called in MIWU ISRs */ + return npcm_miwu_manage_gpio_callback(miwu_cb, set); +} +#else +static int gpio_npcm_manage_callback(const struct device *dev, + struct gpio_callback *callback, bool set) +{ + return -EINVAL; +} +#endif + +/* GPIO driver registration */ +static const struct gpio_driver_api gpio_npcm_driver = { + .pin_configure = gpio_npcm_config, +#ifdef CONFIG_GPIO_GET_CONFIG + .pin_get_config = gpio_npcm_pin_get_config, +#endif + .port_get_raw = gpio_npcm_port_get_raw, + .port_set_masked_raw = gpio_npcm_port_set_masked_raw, + .port_set_bits_raw = gpio_npcm_port_set_bits_raw, + .port_clear_bits_raw = gpio_npcm_port_clear_bits_raw, + .port_toggle_bits = gpio_npcm_port_toggle_bits, + .pin_interrupt_configure = gpio_npcm_pin_interrupt_configure, + .manage_callback = gpio_npcm_manage_callback, +}; + +int gpio_npcm_init(const struct device *dev) +{ + ARG_UNUSED(dev); + + return 0; +} + +#define NPCM_GPIO_DEVICE_INIT(inst) \ + static const struct gpio_npcm_config gpio_npcm_cfg_##inst = { \ + .common = { \ + .port_pin_mask = \ + GPIO_PORT_PIN_MASK_FROM_NGPIOS(NPCM_GPIO_PORT_PIN_NUM), \ + }, \ + .base = DT_INST_REG_ADDR(inst), \ + .port = inst, \ + .wui_maps = NPCM_DT_WUI_ITEMS_LIST(inst), \ + }; \ + BUILD_ASSERT(NPCM_DT_WUI_ITEMS_LEN(inst) == NPCM_GPIO_PORT_PIN_NUM, \ + "size of prop. wui-maps must equal to pin number!"); \ + static struct gpio_npcm_data gpio_npcm_data_##inst; \ + \ + DEVICE_DT_INST_DEFINE(inst, \ + gpio_npcm_init, \ + NULL, \ + &gpio_npcm_data_##inst, \ + &gpio_npcm_cfg_##inst, \ + PRE_KERNEL_1, \ + CONFIG_GPIO_INIT_PRIORITY, \ + &gpio_npcm_driver); +DT_INST_FOREACH_STATUS_OKAY(NPCM_GPIO_DEVICE_INIT) diff --git a/drivers/pinctrl/CMakeLists.txt b/drivers/pinctrl/CMakeLists.txt index 91bbb8b3d51618..fce099bf8c529e 100644 --- a/drivers/pinctrl/CMakeLists.txt +++ b/drivers/pinctrl/CMakeLists.txt @@ -8,6 +8,7 @@ zephyr_library_sources_ifdef(CONFIG_PINCTRL_AMBIQ pinctrl_ambiq.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_GD32_AF pinctrl_gd32_af.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_GD32_AFIO pinctrl_gd32_afio.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_ITE_IT8XXX2 pinctrl_ite_it8xxx2.c) +zephyr_library_sources_ifdef(CONFIG_PINCTRL_NPCM pinctrl_npcm.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_NPCX pinctrl_npcx.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_NUMICRO pinctrl_numicro.c) zephyr_library_sources_ifdef(CONFIG_PINCTRL_NRF pinctrl_nrf.c) diff --git a/drivers/pinctrl/Kconfig b/drivers/pinctrl/Kconfig index ab6ea86bcc9a81..e83f33c1f2435f 100644 --- a/drivers/pinctrl/Kconfig +++ b/drivers/pinctrl/Kconfig @@ -37,6 +37,7 @@ source "drivers/pinctrl/Kconfig.b91" source "drivers/pinctrl/Kconfig.ambiq" source "drivers/pinctrl/Kconfig.gd32" source "drivers/pinctrl/Kconfig.it8xxx2" +source "drivers/pinctrl/Kconfig.npcm" source "drivers/pinctrl/Kconfig.npcx" source "drivers/pinctrl/Kconfig.numicro" source "drivers/pinctrl/Kconfig.nrf" diff --git a/drivers/pinctrl/Kconfig.npcm b/drivers/pinctrl/Kconfig.npcm new file mode 100644 index 00000000000000..d7ff4a73d8e3f0 --- /dev/null +++ b/drivers/pinctrl/Kconfig.npcm @@ -0,0 +1,13 @@ +# NPCM Pin Controller configuration options + +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + + +config PINCTRL_NPCM + bool "Nuvoton NPCM enhanced Super I/O (eSIO) pin controller driver" + default y + depends on DT_HAS_NUVOTON_NPCM_PINCTRL_ENABLED + help + This option enables the pin controller driver for NPCM family of + processors. diff --git a/drivers/pinctrl/pinctrl_npcm.c b/drivers/pinctrl/pinctrl_npcm.c new file mode 100644 index 00000000000000..d287fbfd244f02 --- /dev/null +++ b/drivers/pinctrl/pinctrl_npcm.c @@ -0,0 +1,96 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ +#include +#include +#include + +/* Driver config */ +struct npcm_pinctrl_config { + /* Device base address used for pinctrl driver */ + uintptr_t base_scfg; + uintptr_t base_glue; +}; + +static const struct npcm_pinctrl_config npcm_pinctrl_cfg = { + .base_scfg = NPCM_SCFG_REG_ADDR, + .base_glue = NPCM_GLUE_REG_ADDR, +}; + +static void npcm_periph_pinmux_configure(const struct npcm_periph *alt, bool is_alternate) +{ + const uintptr_t scfg_base = npcm_pinctrl_cfg.base_scfg; + uint8_t alt_mask = BIT(alt->bit); + + /* + * is_alternate == 0 means select GPIO, otherwise Alternate Func. + * inverted == 0: + * Set devalt bit to select Alternate Func. + * inverted == 1: + * Clear devalt bit to select Alternate Func. + */ + if (is_alternate != alt->inverted) { + NPCM_DEVALT(scfg_base, alt->group) |= alt_mask; + } else { + NPCM_DEVALT(scfg_base, alt->group) &= ~alt_mask; + } +} + +static void npcm_periph_pupd_configure(const struct npcm_periph *pupd, + enum npcm_io_bias_type type) +{ + const uintptr_t scfg_base = npcm_pinctrl_cfg.base_scfg; + + if (type == NPCM_BIAS_TYPE_NONE) { + NPCM_PUPD_EN(scfg_base, pupd->group) &= ~BIT(pupd->bit); + } else { + NPCM_PUPD_EN(scfg_base, pupd->group) |= BIT(pupd->bit); + } +} + +static void npcm_periph_configure(const pinctrl_soc_pin_t *pin, uintptr_t reg) +{ + if (pin->cfg.periph.type == NPCM_PINCTRL_TYPE_PERIPH_PINMUX) { + /* Configure peripheral device's pinmux functionality */ + npcm_periph_pinmux_configure(&pin->cfg.periph, + !pin->flags.pinmux_gpio); + } else if (pin->cfg.periph.type == NPCM_PINCTRL_TYPE_PERIPH_PUPD) { + /* Configure peripheral device's internal PU/PD */ + npcm_periph_pupd_configure(&pin->cfg.periph, + pin->flags.io_bias_type); + } +} + +static void npcm_device_control_configure(const pinctrl_soc_pin_t *pin) +{ + const struct npcm_dev_ctl *ctrl = (const struct npcm_dev_ctl *)&pin->cfg.dev_ctl; + const uintptr_t scfg_base = npcm_pinctrl_cfg.base_scfg; + + SET_FIELD(NPCM_DEV_CTL(scfg_base, ctrl->offest), + FIELD(ctrl->field_offset, ctrl->field_size), + ctrl->field_value); +} + +/* Pinctrl API implementation */ +int pinctrl_configure_pins(const pinctrl_soc_pin_t *pins, uint8_t pin_cnt, + uintptr_t reg) +{ + ARG_UNUSED(reg); + + /* Configure all peripheral devices' properties here. */ + for (uint8_t i = 0; i < pin_cnt; i++) { + if (pins[i].flags.type == NPCM_PINCTRL_TYPE_PERIPH) { + /* Configure peripheral device's pinmux functionality */ + npcm_periph_configure(&pins[i], reg); + } else if (pins[i].flags.type == NPCM_PINCTRL_TYPE_DEVICE_CTRL) { + /* Configure device's io characteristics */ + npcm_device_control_configure(&pins[i]); + } else { + return -ENOTSUP; + } + } + + return 0; +} diff --git a/dts/arm/nuvoton/npcm/npcm-alts-map.dtsi b/dts/arm/nuvoton/npcm/npcm-alts-map.dtsi new file mode 100644 index 00000000000000..28da8cb946fbc8 --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm-alts-map.dtsi @@ -0,0 +1,807 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/ { + npcm-alts-map { + compatible = "nuvoton,npcm-pinctrl-conf"; + + /* SCFG device alternative table */ + /* SCFG DEVALT 0 */ + alt0_espi_cs2_sl: alt00 { + alts = <&scfg 0x10 0x0 0>; + }; + alt0_fiu_back_cs_sl: alt02 { + alts = <&scfg 0x10 0x2 0>; + }; + alt0_clkrn_sl: alt05 { + alts = <&scfg 0x10 0x5 0>; + }; + alt0_lpcpd_sl: alt06 { + alts = <&scfg 0x10 0x6 0>; + }; + alt0_serirq_sl: alt07 { + alts = <&scfg 0x10 0x7 0>; + }; + + /* SCFG DEVALT 1 */ + alt1_vin1_sl: alt11 { + alts = <&scfg 0x11 0x1 0>; + }; + alt1_vin2_sl: alt12 { + alts = <&scfg 0x11 0x2 0>; + }; + alt1_vin3_sl: alt13 { + alts = <&scfg 0x11 0x3 0>; + }; + alt1_atx5vsb_sl: alt14 { + alts = <&scfg 0x11 0x4 0>; + }; + alt1_vin5_sl: alt15 { + alts = <&scfg 0x11 0x5 0>; + }; + alt1_vin7_sl: alt17 { + alts = <&scfg 0x11 0x7 0>; + }; + + /* SCFG DEVALT 2 */ + alt2_vin14_sl: alt20 { + alts = <&scfg 0x12 0x0 0>; + }; + alt2_vin15_sl: alt21 { + alts = <&scfg 0x12 0x1 0>; + }; + alt2_vin16_sl: alt22 { + alts = <&scfg 0x12 0x2 0>; + }; + + /* SCFG DEVALT 3 */ + alt3_ta0_sl: alt30 { + alts = <&scfg 0x13 0x0 0>; + }; + alt3_ta1_sl: alt31 { + alts = <&scfg 0x13 0x1 0>; + }; + alt3_ta2_sl: alt32 { + alts = <&scfg 0x13 0x2 0>; + }; + alt3_ta3_sl: alt33 { + alts = <&scfg 0x13 0x3 0>; + }; + alt3_ta4_sl: alt34 { + alts = <&scfg 0x13 0x4 0>; + }; + alt3_ta5_sl: alt35 { + alts = <&scfg 0x13 0x5 0>; + }; + alt3_ta6_sl: alt36 { + alts = <&scfg 0x13 0x6 0>; + }; + alt3_ta7_sl: alt37 { + alts = <&scfg 0x13 0x7 0>; + }; + + + /* SCFG DEVALT 4 */ + alt4_ta8_sl: alt40 { + alts = <&scfg 0x14 0x0 0>; + }; + alt4_ta9_sl: alt41 { + alts = <&scfg 0x14 0x1 0>; + }; + alt4_pwm0_sl: alt42 { + alts = <&scfg 0x14 0x2 0>; + }; + alt4_pwm1_sl: alt43 { + alts = <&scfg 0x14 0x3 0>; + }; + alt4_pwm2_sl: alt44 { + alts = <&scfg 0x14 0x4 0>; + }; + alt4_pwm3_sl: alt45 { + alts = <&scfg 0x14 0x5 0>; + }; + alt4_pwm4_sl: alt46 { + alts = <&scfg 0x14 0x6 0>; + }; + alt4_pwm5_sl: alt47 { + alts = <&scfg 0x14 0x7 0>; + }; + + /* SCFG DEVALT 5 */ + alt5_pwm6_sl: alt50 { + alts = <&scfg 0x15 0x0 0>; + }; + alt5_pwm7_sl: alt51 { + alts = <&scfg 0x15 0x1 0>; + }; + alt5_pwm8_sl: alt52 { + alts = <&scfg 0x15 0x2 0>; + }; + alt5_pwm9_sl: alt53 { + alts = <&scfg 0x15 0x3 0>; + }; + alt5_peci_en: alt54 { + alts = <&scfg 0x15 0x4 0>; + }; + alt5_ecsci_sl: alt55 { + alts = <&scfg 0x15 0x5 0>; + }; + alt5_smi_sl: alt56 { + alts = <&scfg 0x15 0x6 0>; + }; + + /* SCFG DEVALT 6 */ + alt6_p80_d_inv: alt60 { + alts = <&scfg 0x16 0x0 0>; + }; + alt6_prt_sl: alt62 { + alts = <&scfg 0x16 0x2 0>; + }; + alt6_port80_sl: alt63 { + alts = <&scfg 0x16 0x3 0>; + }; + alt6_p80_g_inv: alt64 { + alts = <&scfg 0x16 0x4 0>; + }; + alt6_espi_s5s4_sl: alt65 { + alts = <&scfg 0x16 0x5 0>; + }; + alt6_espi_out_sel: alt66 { + alts = <&scfg 0x16 0x6 0>; + }; + alt6_uart_ext_sel: alt67 { + alts = <&scfg 0x16 0x7 0>; + }; + + /* SCFG DEVALT 7 */ + alt7_fw_rdy_sl: alt70-inv { + alts = <&scfg 0x17 0x0 1>; + }; + alt7_cirrx_sl: alt71 { + alts = <&scfg 0x17 0x1 0>; + }; + alt7_i3c6_sl: alt72 { + alts = <&scfg 0x17 0x2 0>; + }; + alt7_no_gp96: alt73-inv { + alts = <&scfg 0x17 0x3 1>; + }; + alt7_no_gp97: alt74-inv { + alts = <&scfg 0x17 0x4 1>; + }; + alt7_ext32ksl: alt75 { + alts = <&scfg 0x17 0x5 0>; + }; + alt7_clkout_sl: alt76 { + alts = <&scfg 0x17 0x6 0>; + }; + alt7_clkom_rtc32k: alt77 { + alts = <&scfg 0x17 0x7 0>; + }; + + /* SCFG DEVALT 8 */ + alt8_kb_irqtocore_en: alt80 { + alts = <&scfg 0x18 0x0 0>; + }; + alt8_ms_irqtocore_en: alt81 { + alts = <&scfg 0x18 0x1 0>; + }; + alt8_cir_irqtocore_en: alt82 { + alts = <&scfg 0x18 0x2 0>; + }; + alt8_prt_irqtocore_en: alt83 { + alts = <&scfg 0x18 0x3 0>; + }; + + /* SCFG DEVALT 9 */ + alt9_rts2_sl: alt90 { + alts = <&scfg 0x19 0x0 0>; + }; + alt9_sp2i_sl: alt91 { + alts = <&scfg 0x19 0x1 0>; + }; + alt9_sp2o_sl: alt92 { + alts = <&scfg 0x19 0x2 0>; + }; + alt9_sp2ctl_sl: alt93 { + alts = <&scfg 0x19 0x3 0>; + }; + alt9_cts2_sl: alt94 { + alts = <&scfg 0x19 0x4 0>; + }; + alt9_ri2_sl: alt95 { + alts = <&scfg 0x19 0x5 0>; + }; + alt9_dpwrok_sl: alt96 { + alts = <&scfg 0x19 0x6 0>; + }; + alt9_s0ix_sl: alt97 { + alts = <&scfg 0x19 0x7 0>; + }; + + /* SCFG DEVALT A */ + alta_smb1a_sl: alta0 { + alts = <&scfg 0x1A 0x0 0>; + }; + alta_smb3a_sl: alta1 { + alts = <&scfg 0x1A 0x1 0>; + }; + alta_smb4a_sl: alta2 { + alts = <&scfg 0x1A 0x2 0>; + }; + alta_smb5a_sl: alta3 { + alts = <&scfg 0x1A 0x3 0>; + }; + alta_i3c5_sl: alta4 { + alts = <&scfg 0x1A 0x4 0>; + }; + alta_smb1b_sl: alta5 { + alts = <&scfg 0x1A 0x5 0>; + }; + alta_urto1_sl: alta6 { + alts = <&scfg 0x1A 0x6 0>; + }; + alta_urto2_sl: alta7 { + alts = <&scfg 0x1A 0x7 0>; + }; + + /* SCFG DEVALT B */ + altb_rts1_sl: altb0 { + alts = <&scfg 0x1B 0x0 0>; + }; + altb_urti_sl: altb1 { + alts = <&scfg 0x1B 0x1 0>; + }; + altb_sp1i_sl: altb2 { + alts = <&scfg 0x1B 0x2 0>; + }; + altb_sp1o_sl: altb3 { + alts = <&scfg 0x1B 0x3 0>; + }; + altb_sp1ctl_sl: altb4 { + alts = <&scfg 0x1B 0x4 0>; + }; + altb_cts1_sl: altb5 { + alts = <&scfg 0x1B 0x5 0>; + }; + altb_ri1_sl: altb6 { + alts = <&scfg 0x1B 0x6 0>; + }; + altb_ldrq_sl: altb7 { + alts = <&scfg 0x1B 0x7 0>; + }; + + /* SCFG DEVALT C */ + altc_spip1_sl: altc1 { + alts = <&scfg 0x1C 0x1 0>; + }; + altc_shd_spi_quad: altc2 { + alts = <&scfg 0x1C 0x2 0>; + }; + altc_shd_spi: altc3 { + alts = <&scfg 0x1C 0x3 0>; + }; + altc_spip_dio23_gpio: altc4-inv { + alts = <&scfg 0x1C 0x4 1>; + }; + altc_urti1_sl: altc6 { + alts = <&scfg 0x1C 0x6 0>; + }; + altc_souta_p80_sl: altc7 { + alts = <&scfg 0x1C 0x7 0>; + }; + + /* SCFG DEVALT D */ + altd_gpioe0_lv: altd2 { + alts = <&scfg 0x1D 0x2 0>; + }; + altd_gpioe1_lv: altd3 { + alts = <&scfg 0x1D 0x3 0>; + }; + altd_caseopen_lv: altd4 { + alts = <&scfg 0x1D 0x4 0>; + }; + altd_sktocc_lv: altd5 { + alts = <&scfg 0x1D 0x5 0>; + }; + altd_gpioe2_lv: altd6 { + alts = <&scfg 0x1D 0x6 0>; + }; + + /* SCFG DEVALT E */ + alte_kcb_test: alte0 { + alts = <&scfg 0x1E 0x0 0>; + }; + alte_kbc_sl: alte3 { + alts = <&scfg 0x1E 0x3 0>; + }; + alte_kbcrst_sl: alte4 { + alts = <&scfg 0x1E 0x4 0>; + }; + alte_smb2a_sl: alte5 { + alts = <&scfg 0x1E 0x5 0>; + }; + alte_grn_led_sel: alte6 { + alts = <&scfg 0x1E 0x6 0>; + }; + alte_ylw_led_sel: alte7 { + alts = <&scfg 0x1E 0x7 0>; + }; + + /* SCFG DEVALT F */ + altf_gpioe5_lv: altf7 { + alts = <&scfg 0x1F 0x7 0>; + }; + + + /* SCFG DEVALT 10 */ + alt10_crgpio_rst_sl: alt100 { + alts = <&scfg 0x0B 0x0 0>; + }; + alt10_i3c2_sl: alt101 { + alts = <&scfg 0x0B 0x1 0>; + }; + alt10_i3c3_sl: alt102 { + alts = <&scfg 0x0B 0x2 0>; + }; + alt10_i3c4_sl: alt103 { + alts = <&scfg 0x0B 0x3 0>; + }; + alt10_i3c1_sl: alt106 { + alts = <&scfg 0x0B 0x6 0>; + }; + + /* SCFG DEVALT 11 */ + alt11_miwu_acpi_en: alt111 { + alts = <&scfg 0x0C 0x0 0>; + }; + alt11_sib_sync_all: alt112 { + alts = <&scfg 0x0C 0x1 0>; + }; + alt11_sib_sync_address: alt113 { + alts = <&scfg 0x0C 0x2 0>; + }; + + /* SCFG DEVALT 2E */ + alt2e_usbd_phy_en: alt2e4 { + alts = <&scfg 0x2E 0x4 0>; + }; + alt2e_usbd_phy_clk_sel: alt2e6 { + alts = <&scfg 0x2E 0x6 0>; + }; + + /* SCFG DEVALT 30 */ + alt30_vhif_pad_test_d: alt300 { + alts = <&scfg 0x30 0x0 0>; + }; + alt30_vhif_pad_test_en: alt301 { + alts = <&scfg 0x30 0x1 0>; + }; + alt30_vspi_pad_test_d: alt302 { + alts = <&scfg 0x30 0x2 0>; + }; + alt30_vspi_pad_test_en: alt303 { + alts = <&scfg 0x30 0x3 0>; + }; + + /* SCFG DEVALT 31 */ + alt31_fwctrl_cruart1: alt310 { + alts = <&scfg 0x31 0x0 0>; + }; + alt31_fwctrl_cruart1n: alt311 { + alts = <&scfg 0x31 0x1 0>; + }; + alt31_fwctrl_cruart2: alt312 { + alts = <&scfg 0x31 0x2 0>; + }; + alt31_fwctrl_cruart2n: alt313 { + alts = <&scfg 0x31 0x3 0>; + }; + alt31_urti2_sl: alt314 { + alts = <&scfg 0x31 0x4 0>; + }; + alt31_urto3_sl: alt315 { + alts = <&scfg 0x31 0x5 0>; + }; + alt31_urti3_sl: alt316 { + alts = <&scfg 0x31 0x6 0>; + }; + alt31_urto4_sl: alt317 { + alts = <&scfg 0x31 0x7 0>; + }; + + /* SCFG DEVALT 32 */ + alt32_uartf_irq2core_en: alt320 { + alts = <&scfg 0x32 0x0 0>; + }; + alt32_uarte_irq2core_en: alt321 { + alts = <&scfg 0x32 0x1 0>; + }; + alt32_uartd_irq2core_en: alt322 { + alts = <&scfg 0x32 0x2 0>; + }; + alt32_uartc_irq2core_en: alt323 { + alts = <&scfg 0x32 0x3 0>; + }; + alt32_uartb_irq2core_en: alt324 { + alts = <&scfg 0x32 0x4 0>; + }; + alt32_uarta_irq2core_en: alt325 { + alts = <&scfg 0x32 0x5 0>; + }; + + /* SCFG DEVALT 34 */ + alt34_can1_clkstop_req: alt340 { + alts = <&scfg 0x34 0x0 0>; + }; + alt34_can1_cclk_sel: alt341 { + alts = <&scfg 0x34 0x1 0>; + }; + alt34_can2_clkstop_req: alt342 { + alts = <&scfg 0x34 0x2 0>; + }; + alt34_can2_cclk_sel: alt343 { + alts = <&scfg 0x34 0x3 0>; + }; + alt34_can1_sl: alt346 { + alts = <&scfg 0x34 0x6 0>; + }; + alt34_can2_sl: alt347 { + alts = <&scfg 0x34 0x7 0>; + }; + + /* SCFG DEVALT 50 */ + alt50_psin_ctl: alt500 { + alts = <&scfg 0x50 0x0 0>; + }; + alt50_psout_ctl: alt501 { + alts = <&scfg 0x50 0x1 0>; + }; + alt50_pson_ctl: alt502 { + alts = <&scfg 0x50 0x2 0>; + }; + alt50_pme_ctl: alt503 { + alts = <&scfg 0x50 0x3 0>; + }; + alt50_3vsbsw_ctl: alt505 { + alts = <&scfg 0x50 0x5 0>; + }; + + /* SCFG DEVALT 51 */ + alt51_rstout0_ctl: alt510 { + alts = <&scfg 0x51 0x0 0>; + }; + alt51_rstout1_ctl: alt511 { + alts = <&scfg 0x51 0x1 0>; + }; + alt51_rstout2_ctl: alt512 { + alts = <&scfg 0x51 0x2 0>; + }; + + /* SCFG DEVALT 52 */ + alt52_dpwrok_ctl: alt520 { + alts = <&scfg 0x52 0x0 0>; + }; + alt52_rsmrst_ctl: alt521 { + alts = <&scfg 0x52 0x1 0>; + }; + alt52_deep_s5_ctl: alt522 { + alts = <&scfg 0x52 0x2 0>; + }; + alt52_pwrok0_ctl: alt523 { + alts = <&scfg 0x52 0x3 0>; + }; + + /* SCFG DEVALT 53 */ + alt53_psin_val: alt530 { + alts = <&scfg 0x53 0x0 0>; + }; + alt53_psout_val: alt531 { + alts = <&scfg 0x53 0x1 0>; + }; + alt53_pson_val: alt532 { + alts = <&scfg 0x53 0x2 0>; + }; + alt53_pme_val: alt533 { + alts = <&scfg 0x53 0x3 0>; + }; + alt53_3vsbsw_val: alt535 { + alts = <&scfg 0x53 0x5 0>; + }; + + /* SCFG DEVALT 54 */ + alt54_rstout0_val: alt540 { + alts = <&scfg 0x54 0x0 0>; + }; + alt54_rstout1_val: alt541 { + alts = <&scfg 0x54 0x1 0>; + }; + alt54_rstout2_val: alt542 { + alts = <&scfg 0x54 0x2 0>; + }; + + /* SCFG DEVALT 55 */ + alt55_dpwrok_val: alt550 { + alts = <&scfg 0x55 0x0 0>; + }; + alt55_rsmrst_val: alt551 { + alts = <&scfg 0x55 0x1 0>; + }; + alt55_deep_s5_val: alt552 { + alts = <&scfg 0x55 0x2 0>; + }; + alt55_pwrok0_val: alt553 { + alts = <&scfg 0x55 0x4 0>; + }; + + /* SCFG DEVALT 59 */ + alt59_psout_mod: alt591 { + alts = <&scfg 0x59 0x1 0>; + }; + alt59_pson_mod: alt592 { + alts = <&scfg 0x59 0x2 0>; + }; + alt59_pme_mod: alt593 { + alts = <&scfg 0x59 0x3 0>; + }; + alt59_3vsbsw_mod: alt595 { + alts = <&scfg 0x59 0x5 0>; + }; + + /* SCFG DEVALT 5A */ + alt5a_rstout0_mod: alt5a0 { + alts = <&scfg 0x5A 0x0 0>; + }; + alt5a_rstout1_mod: alt5a1 { + alts = <&scfg 0x5A 0x1 0>; + }; + alt5a_rstout2_mod: alt5a2 { + alts = <&scfg 0x5A 0x2 0>; + }; + + /* SCFG DEVALT 5B */ + alt5b_dpwrok_mod: alt5b0 { + alts = <&scfg 0x5B 0x0 0>; + }; + alt5b_rsmrst_mod: alt5b1 { + alts = <&scfg 0x5B 0x1 0>; + }; + alt5b_deep_s5_mod: alt5b2 { + alts = <&scfg 0x5B 0x2 0>; + }; + alt5b_dpwrok0_mod: alt5b3 { + alts = <&scfg 0x5B 0x3 0>; + }; + alt5b_dpwrok_pp: alt5b6 { + alts = <&scfg 0x5B 0x6 0>; + }; + alt5b_rsmrst_pp: alt5b7 { + alts = <&scfg 0x5B 0x7 0>; + }; + + /* SCFG DEVALT 5C */ + alt5c_psin_sel: alt5c0-inv { + alts = <&scfg 0x5C 0x0 1>; + }; + alt5c_psout_sel: alt5c1-inv { + alts = <&scfg 0x5C 0x1 1>; + }; + alt5c_pson_sel: alt5c2-inv { + alts = <&scfg 0x5C 0x2 1>; + }; + alt5c_pme_sel: alt5c3-inv { + alts = <&scfg 0x5C 0x3 1>; + }; + alt5c_3vsbsw_sel: alt5c4 { + alts = <&scfg 0x5C 0x4 0>; + }; + alt5c_slpsus_sel: alt5c5-inv { + alts = <&scfg 0x5C 0x5 1>; + }; + + /* SCFG DEVALT 5D */ + alt5d_rstout0_sel: alt5d0-inv { + alts = <&scfg 0x5D 0x0 1>; + }; + alt5d_rstout1_sel: alt5d1-inv { + alts = <&scfg 0x5D 0x1 1>; + }; + alt5d_rstout2_sel: alt5d2-inv { + alts = <&scfg 0x5D 0x2 1>; + }; + alt5d_sktocc_sel: alt5d4-inv { + alts = <&scfg 0x5D 0x4 1>; + }; + alt5d_caseopen_sel: alt5d5-inv { + alts = <&scfg 0x5D 0x5 1>; + }; + + /* SCFG DEVALT 5E */ + alt5e_dpwrok_sel: alt5e0-inv { + alts = <&scfg 0x5E 0x0 1>; + }; + alt5e_rsmrst_sel: alt5e1-inv { + alts = <&scfg 0x5E 0x1 1>; + }; + alt5e_deep_s5_sel: alt5e2-inv { + alts = <&scfg 0x5E 0x2 1>; + }; + alt5e_pwrok0_sel: alt5e3-inv { + alts = <&scfg 0x5E 0x3 1>; + }; + alt5e_3vsbsw_sel: alt5e5-inv { + alts = <&scfg 0x5E 0x5 1>; + }; + + /* SCFG DEVALT 5F */ + alt5f_slp_s3_sel: alt5f0-inv { + alts = <&scfg 0x5F 0x0 1>; + }; + alt5f_slp_s5_sel: alt5f1-inv { + alts = <&scfg 0x5F 0x1 1>; + }; + alt5f_atxpgd_sel: alt5f2-inv { + alts = <&scfg 0x5F 0x2 1>; + }; + alt5f_resetcon_sel: alt5f3 { + alts = <&scfg 0x5F 0x3 0>; + }; + alt5f_espi_pin_vw_sel: alt5f5 { + alts = <&scfg 0x5F 0x5 0>; + }; + + /* SCFG DEVALT 62 */ + alt62_sinc_sl: alt620 { + alts = <&scfg 0x62 0x0 0>; + }; + alt62_soutc_sl: alt621 { + alts = <&scfg 0x62 0x1 0>; + }; + alt62_rtsc_sl: alt622 { + alts = <&scfg 0x62 0x2 0>; + }; + alt62_ctsc_sl: alt623 { + alts = <&scfg 0x62 0x3 0>; + }; + alt62_sind_sl: alt624 { + alts = <&scfg 0x62 0x4 0>; + }; + alt62_soutd_sl: alt625 { + alts = <&scfg 0x62 0x5 0>; + }; + alt62_rtsd_sl: alt626 { + alts = <&scfg 0x62 0x6 0>; + }; + alt62_ctsd_sl: alt627 { + alts = <&scfg 0x62 0x7 0>; + }; + + /* SCFG DEVALT 66 */ + alt66_sine_sl: alt660 { + alts = <&scfg 0x66 0x0 0>; + }; + alt66_soute_sl: alt661 { + alts = <&scfg 0x66 0x1 0>; + }; + alt66_rtse_sl: alt662 { + alts = <&scfg 0x66 0x2 0>; + }; + alt66_ctse_sl: alt663 { + alts = <&scfg 0x66 0x3 0>; + }; + alt66_sinf_sl: alt664 { + alts = <&scfg 0x66 0x4 0>; + }; + alt66_soutf_sl: alt665 { + alts = <&scfg 0x66 0x5 0>; + }; + alt66_rtsf_sl: alt666 { + alts = <&scfg 0x66 0x6 0>; + }; + alt66_ctsf_sl: alt667 { + alts = <&scfg 0x66 0x7 0>; + }; + + /* SCFG DEVALT 67 */ + alt67_fw_rdy_en: alt670 { + alts = <&scfg 0x67 0x0 0>; + }; + alt67_fw_rdy_sel: alt671 { + alts = <&scfg 0x67 0x1 0>; + }; + alt67_fw_rdy_type: alt672 { + alts = <&scfg 0x67 0x2 0>; + }; + alt67_deeps5_en: alt677 { + alts = <&scfg 0x67 0x7 0>; + }; + + /* SCFG DEVALT 69 */ + alt69_usbd_phy_ponrst: alt695 { + alts = <&scfg 0x69 0x5 0>; + }; + + /* SCFG DEVALT 6A */ + alt6a_siox1_sl: alt6a0 { + alts = <&scfg 0x6A 0x0 0>; + }; + alt6a_siox2_sl: alt6a1 { + alts = <&scfg 0x6A 0x1 0>; + }; + alt6a_siox1_pu_en: alt6a2 { + alts = <&scfg 0x6A 0x2 0>; + }; + alt6a_siox2_pu_en: alt6a3 { + alts = <&scfg 0x6A 0x3 0>; + }; + + /* SCFG DEVALT 6B */ + alt6b_urtb_sin_sl2: alt6b0 { + alts = <&scfg 0x6B 0x0 0>; + }; + alt6b_urtb_sout_sl2: alt6b1 { + alts = <&scfg 0x6B 0x1 0>; + }; + alt6b_urtb_rts_sl2: alt6b2 { + alts = <&scfg 0x6B 0x2 0>; + }; + alt6b_urtb_cts_sl2: alt6b3 { + alts = <&scfg 0x6B 0x3 0>; + }; + alt6b_urtb_dsr_sl2: alt6b4 { + alts = <&scfg 0x6B 0x4 0>; + }; + alt6b_urtb_dtr_sl2: alt6b5 { + alts = <&scfg 0x6B 0x5 0>; + }; + alt6b_urtb_dcd_sl2: alt6b6 { + alts = <&scfg 0x6B 0x6 0>; + }; + alt6b_urtb_ri_sl2: alt6b7 { + alts = <&scfg 0x6B 0x7 0>; + }; + + /* SCFG DEVALT 6C */ + alt6c_urti4_sl: alt6c0 { + alts = <&scfg 0x6C 0x0 0>; + }; + alt6c_urto5_sl: alt6c1 { + alts = <&scfg 0x6C 0x1 0>; + }; + + /* SCFG DEVALT 6D */ + alt6d_smb7a_sl: alt6d0 { + alts = <&scfg 0x6D 0x0 0>; + }; + alt6d_smb8a_sl: alt6d1 { + alts = <&scfg 0x6D 0x1 0>; + }; + alt6d_smb9a_sl: alt6d2 { + alts = <&scfg 0x6D 0x2 0>; + }; + alt6d_smb10a_sl: alt6d3 { + alts = <&scfg 0x6D 0x3 0>; + }; + alt6d_smb11a_sl: alt6d4 { + alts = <&scfg 0x6D 0x4 0>; + }; + alt6d_smb12a_sl: alt6d5 { + alts = <&scfg 0x6D 0x5 0>; + }; + alt6d_smb4b_sl: alt6d6 { + alts = <&scfg 0x6D 0x6 0>; + }; + alt6d_smb6b_sl: alt6d7 { + alts = <&scfg 0x6D 0x7 0>; + }; + + /* SCFG DEVALT CX */ + altcx_gpio_out_pullen: altcx7 { + alts = <&scfg 0x24 0x7 0>; + }; + + }; +}; diff --git a/dts/arm/nuvoton/npcm/npcm-miwus-wui-map.dtsi b/dts/arm/nuvoton/npcm/npcm-miwus-wui-map.dtsi new file mode 100644 index 00000000000000..28ba917a41df0a --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm-miwus-wui-map.dtsi @@ -0,0 +1,555 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/ { + /* Mapping between MIWU wui bits and source device */ + npcm_miwus_wui { + compatible = "nuvoton,npcm-miwu-wui-map"; + + /* MIWU table 0 */ + /* MIWU group A */ + wui_io00: wui0-1-0 { + miwus = <&miwu0 0 0>; /* GPIO00 */ + }; + wui_io01: wui0-1-1 { + miwus = <&miwu0 0 1>; /* GPIO01 */ + }; + wui_io02: wui0-1-2 { + miwus = <&miwu0 0 2>; /* GPIO02 */ + }; + wui_io03: wui0-1-3 { + miwus = <&miwu0 0 3>; /* GPIO03 */ + }; + wui_io04: wui0-1-4 { + miwus = <&miwu0 0 4>; /* GPIO04 */ + }; + wui_io05: wui0-1-5 { + miwus = <&miwu0 0 5>; /* GPIO05 */ + }; + wui_io06: wui0-1-6 { + miwus = <&miwu0 0 6>; /* GPIO06 */ + }; + wui_io07: wui0-1-7 { + miwus = <&miwu0 0 7>; /* GPIO07 */ + }; + + /* MIWU group B */ + wui_io10: wui0-2-0 { + miwus = <&miwu0 1 0>; /* GPIO10 */ + }; + wui_io11: wui0-2-1 { + miwus = <&miwu0 1 1>; /* GPIO11 */ + }; + wui_io12: wui0-2-2 { + miwus = <&miwu0 1 2>; /* GPIO12 */ + }; + wui_io13: wui0-2-3 { + miwus = <&miwu0 1 3>; /* GPIO13 */ + }; + wui_io14: wui0-2-4 { + miwus = <&miwu0 1 4>; /* GPIO14 */ + }; + wui_io15: wui0-2-5 { + miwus = <&miwu0 1 5>; /* GPIO15 */ + }; + wui_io16: wui0-2-6 { + miwus = <&miwu0 1 6>; /* GPIO16 */ + }; + wui_io17: wui0-2-7 { + miwus = <&miwu0 1 7>; /* GPIO17 */ + }; + + /* MIWU group C */ + wui_io20: wui0-3-0 { + miwus = <&miwu0 2 0>; /* GPIO20 */ + }; + wui_io21: wui0-3-1 { + miwus = <&miwu0 2 1>; /* GPIO21 */ + }; + wui_io22: wui0-3-2 { + miwus = <&miwu0 2 2>; /* GPIO22 */ + }; + wui_io23: wui0-3-3 { + miwus = <&miwu0 2 3>; /* GPIO23 */ + }; + wui_io24: wui0-3-4 { + miwus = <&miwu0 2 4>; /* GPIO24 */ + }; + wui_io25: wui0-3-5 { + miwus = <&miwu0 2 5>; /* GPIO25 */ + }; + wui_io26: wui0-3-6 { + miwus = <&miwu0 2 6>; /* GPIO26 */ + }; + wui_io27: wui0-3-7 { + miwus = <&miwu0 2 7>; /* GPIO27 */ + }; + + /* MIWU group D */ + wui_io30: wui0-4-0 { + miwus = <&miwu0 3 0>; /* GPIO30 */ + }; + wui_io31: wui0-4-1 { + miwus = <&miwu0 3 1>; /* GPIO31 */ + }; + wui_io32: wui0-4-2 { + miwus = <&miwu0 3 2>; /* GPIO32 */ + }; + wui_io33: wui0-4-3 { + miwus = <&miwu0 3 3>; /* GPIO33 */ + }; + wui_io34: wui0-4-4 { + miwus = <&miwu0 3 4>; /* GPIO34 */ + }; + wui_io35: wui0-4-5 { + miwus = <&miwu0 3 5>; /* GPIO35 */ + }; + wui_io36: wui0-4-6 { + miwus = <&miwu0 3 6>; /* GPIO36 */ + }; + wui_io37: wui0-4-7 { + miwus = <&miwu0 3 7>; /* GPIO37 */ + }; + + /* MIWU group E */ + wui_io40: wui0-5-0 { + miwus = <&miwu0 4 0>; /* GPIO40 */ + }; + wui_io41: wui0-5-1 { + miwus = <&miwu0 4 1>; /* GPIO41 */ + }; + wui_io42: wui0-5-2 { + miwus = <&miwu0 4 2>; /* GPIO42 */ + }; + wui_io43: wui0-5-3 { + miwus = <&miwu0 4 3>; /* GPIO43 */ + }; + wui_io44: wui0-5-4 { + miwus = <&miwu0 4 4>; /* GPIO44 */ + }; + wui_io45: wui0-5-5 { + miwus = <&miwu0 4 5>; /* GPIO45 */ + }; + wui_io46: wui0-5-6 { + miwus = <&miwu0 4 6>; /* GPIO46 */ + }; + wui_io47: wui0-5-7 { + miwus = <&miwu0 4 7>; /* GPIO47 */ + }; + + /* MIWU group F */ + wui_io50: wui0-6-0 { + miwus = <&miwu0 5 0>; /* GPIO50 */ + }; + wui_io51: wui0-6-1 { + miwus = <&miwu0 5 1>; /* GPIO51 */ + }; + wui_io52: wui0-6-2 { + miwus = <&miwu0 5 2>; /* GPIO52 */ + }; + wui_io53: wui0-6-3 { + miwus = <&miwu0 5 3>; /* GPIO53 */ + }; + wui_io54: wui0-6-4 { + miwus = <&miwu0 5 4>; /* GPIO54 */ + }; + wui_io55: wui0-6-5 { + miwus = <&miwu0 5 5>; /* GPIO55 */ + }; + wui_io56: wui0-6-6 { + miwus = <&miwu0 5 6>; /* GPIO56 */ + }; + wui_io57: wui0-6-7 { + miwus = <&miwu0 5 7>; /* GPIO57 */ + }; + + /* MIWU group G */ + wui_io60: wui0-7-0 { + miwus = <&miwu0 6 0>; /* GPIO60 */ + }; + wui_io61: wui0-7-1 { + miwus = <&miwu0 6 1>; /* GPIO61 */ + }; + wui_io62: wui0-7-2 { + miwus = <&miwu0 6 2>; /* GPIO62 */ + }; + wui_io63: wui0-7-3 { + miwus = <&miwu0 6 3>; /* GPIO63 */ + }; + wui_io64: wui0-7-4 { + miwus = <&miwu0 6 4>; /* GPIO64 */ + }; + wui_io65: wui0-7-5 { + miwus = <&miwu0 6 5>; /* GPIO65 */ + }; + wui_io66: wui0-7-6 { + miwus = <&miwu0 6 6>; /* GPIO66 */ + }; + wui_io67: wui0-7-7 { + miwus = <&miwu0 6 7>; /* GPIO67 */ + }; + + /* MIWU group H */ + wui_io70: wui0-8-0 { + miwus = <&miwu0 7 0>; /* GPIO70 */ + }; + wui_io71: wui0-8-1 { + miwus = <&miwu0 7 1>; /* GPIO71 */ + }; + wui_io72: wui0-8-2 { + miwus = <&miwu0 7 2>; /* GPIO72 */ + }; + wui_io73: wui0-8-3 { + miwus = <&miwu0 7 3>; /* GPIO73 */ + }; + wui_io74: wui0-8-4 { + miwus = <&miwu0 7 4>; /* GPIO74 */ + }; + wui_io75: wui0-8-5 { + miwus = <&miwu0 7 5>; /* GPIO75 */ + }; + wui_io76: wui0-8-6 { + miwus = <&miwu0 7 6>; /* GPIO76 */ + }; + wui_io77: wui0-8-7 { + miwus = <&miwu0 7 7>; /* GPIO77 */ + }; + + /* MIWU table 1 */ + /* MIWU group A */ + wui_io80: wui1-1-0 { + miwus = <&miwu1 0 0>; /* GPIO80 */ + }; + wui_io81: wui1-1-1 { + miwus = <&miwu1 0 1>; /* GPIO81 */ + }; + wui_io82: wui1-1-2 { + miwus = <&miwu1 0 2>; /* GPIO82 */ + }; + wui_io83: wui1-1-3 { + miwus = <&miwu1 0 3>; /* GPIO83 */ + }; + wui_io84: wui1-1-4 { + miwus = <&miwu1 0 4>; /* GPIO84 */ + }; + wui_io85: wui1-1-5 { + miwus = <&miwu1 0 5>; /* GPIO85 */ + }; + wui_io86: wui1-1-6 { + miwus = <&miwu1 0 6>; /* GPIO86 */ + }; + wui_io87: wui1-1-7 { + miwus = <&miwu1 0 7>; /* GPIO87 */ + }; + + /* MIWU group B */ + wui_io90: wui1-2-0 { + miwus = <&miwu1 1 0>; /* GPIO90 */ + }; + wui_io91: wui1-2-1 { + miwus = <&miwu1 1 1>; /* GPIO91 */ + }; + wui_io92: wui1-2-2 { + miwus = <&miwu1 1 2>; /* GPIO92 */ + }; + wui_io93: wui1-2-3 { + miwus = <&miwu1 1 3>; /* GPIO93 */ + }; + wui_io94: wui1-2-4 { + miwus = <&miwu1 1 4>; /* GPIO94 */ + }; + wui_io95: wui1-2-5 { + miwus = <&miwu1 1 5>; /* GPIO95 */ + }; + wui_io96: wui1-2-6 { + miwus = <&miwu1 1 6>; /* GPIO96 */ + }; + wui_io97: wui1-2-7 { + miwus = <&miwu1 1 7>; /* GPIO97 */ + }; + + /* MIWU group C */ + wui_ioa0: wui1-3-0 { + miwus = <&miwu1 2 0>; /* GPIOA0 */ + }; + wui_ioa1: wui1-3-1 { + miwus = <&miwu1 2 1>; /* GPIOA1 */ + }; + wui_ioa2: wui1-3-2 { + miwus = <&miwu1 2 2>; /* GPIOA2 */ + }; + wui_ioa3: wui1-3-3 { + miwus = <&miwu1 2 3>; /* GPIOA3 */ + }; + wui_ioa4: wui1-3-4 { + miwus = <&miwu1 2 4>; /* GPIOA4 */ + }; + wui_ioa5: wui1-3-5 { + miwus = <&miwu1 2 5>; /* GPIOA5 */ + }; + wui_ioa6: wui1-3-6 { + miwus = <&miwu1 2 6>; /* GPIOA6 */ + }; + wui_ioa7: wui1-3-7 { + miwus = <&miwu1 2 7>; /* GPIOA7 */ + }; + + /* MIWU group D */ + wui_cdbg: wui1-4-4 { + miwus = <&miwu1 3 4>; /* CDBGPWRUPREQ */ + }; + wui_lpc_ev: wui1-4-5 { + miwus = <&miwu1 3 5>; /* LPC_EV_WKUP */ + }; + wui_host_acc: wui1-4-6 { + miwus = <&miwu1 3 6>; /* HOST_ACC */ + }; + wui_espi_rst: wui1-4-7 { + miwus = <&miwu1 3 7>; /* PLT_RST/ESPI_RST */ + }; + + /* MIWU group E */ + wui_emac: wui1-5-0 { + miwus = <&miwu1 4 0>; /* EMAC */ + }; + wui_mswc: wui1-5-2 { + miwus = <&miwu1 4 2>; /* MSWC */ + }; + wui_t0out: wui1-5-3 { + miwus = <&miwu1 4 3>; /* T0OUT */ + }; + + /* MIWU group F */ + wui_iob0: wui1-6-0 { + miwus = <&miwu1 5 0>; /* GPIOB0 */ + }; + wui_iob1: wui1-6-1 { + miwus = <&miwu1 5 1>; /* GPIOB1 */ + }; + wui_iob2: wui1-6-2 { + miwus = <&miwu1 5 2>; /* GPIOB2 */ + }; + wui_iob3: wui1-6-3 { + miwus = <&miwu1 5 3>; /* GPIOB3 */ + }; + wui_iob4: wui1-6-4 { + miwus = <&miwu1 5 4>; /* GPIOB4 */ + }; + wui_iob5: wui1-6-5 { + miwus = <&miwu1 5 5>; /* GPIOB5 */ + }; + wui_iob6: wui1-6-6 { + miwus = <&miwu1 5 6>; /* GPIOB6 */ + }; + wui_iob7: wui1-6-7 { + miwus = <&miwu1 5 7>; /* GPIOB7 */ + }; + + /* MIWU group G */ + wui_i3c: wui1-7-7 { + miwus = <&miwu1 6 7>; /* I3C1/2 */ + }; + + /* MIWU group H */ + wui_smb1: wui1-8-1 { + miwus = <&miwu1 7 1>; /* SMB1 */ + }; + wui_smb3: wui1-8-3 { + miwus = <&miwu1 7 3>; /* SMB3 */ + }; + wui_smb4: wui1-8-4 { + miwus = <&miwu1 7 4>; /* SMB4 */ + }; + wui_smb5: wui1-8-5 { + miwus = <&miwu1 7 5>; /* SMB5 */ + }; + wui_smb6: wui1-8-6 { + miwus = <&miwu1 7 6>; /* SMB6 */ + }; + wui_rtc: wui1-8-7 { + miwus = <&miwu1 7 7>; /* RTC */ + }; + + /* MIWU table 2 */ + /* MIWU group A */ + /* eSPI VW Events */ + wui_vw_slp_s3: wui2-1-0 { + miwus = <&miwu2 0 0>; /* VW020 SLP_S3_L */ + }; + wui_vw_slp_s4: wui2-1-1 { + miwus = <&miwu2 0 1>; /* VW021 SLP_S4_L */ + }; + wui_vw_slp_s5: wui2-1-2 { + miwus = <&miwu2 0 2>; /* VW022 SLP_S5_L */ + }; + wui_vw_sus_stat: wui2-1-4 { + miwus = <&miwu2 0 4>; /* SUS_STAT_L */ + }; + wui_vw_plt_rst: wui2-1-5 { + miwus = <&miwu2 0 5>; /* PLTRST_L */ + }; + wui_vw_oob_rst_warn: wui2-1-6 { + miwus = <&miwu2 0 6>; /* OOB_RST_WARN */ + }; + + /* MIWU group B */ + wui_vw_host_rst_warn: wui2-2-0 { + miwus = <&miwu2 1 0>; /* HOST_RST_WARN */ + }; + wui_vw_sus_warn: wui2-2-4 { + miwus = <&miwu2 1 4>; /* SUS_WARN_L */ + }; + wui_vw_sus_pwrdn_ack: wui2-2-5 { + miwus = <&miwu2 1 5>; /* SUS_PWRDN_ACK */ + }; + wui_vw_slp_a: wui2-2-7 { + miwus = <&miwu2 1 7>; /* SLP_A_L */ + }; + + /* MIWU group C */ + /* eSPI VW Events */ + wui_vw_slp_lan: wui2-3-0 { + miwus = <&miwu2 2 0>; /* SLP_LAN_L */ + }; + wui_vw_slp_wlan: wui2-3-1 { + miwus = <&miwu2 2 1>; /* SLP_WLAN_L) */ + }; + wui_vw_pch_to_ec_gen_0: wui2-3-4 { + miwus = <&miwu2 2 4>; /* PCH_TO_EC_GENERIC_0 */ + }; + wui_vw_pch_to_ec_gen_1: wui2-3-5 { + miwus = <&miwu2 2 5>; /* PCH_TO_EC_GENERIC_1 */ + }; + wui_vw_pch_to_ec_gen_2: wui2-3-6 { + miwus = <&miwu2 2 6>; /* PCH_TO_EC_GENERIC_2 */ + }; + wui_vw_pch_to_ec_gen_3: wui2-3-7 { + miwus = <&miwu2 2 7>; /* PCH_TO_EC_GENERIC_3 */ + }; + + /* MIWU group D */ + wui_vw_pch_to_ec_gen_4: wui2-4-0 { + miwus = <&miwu2 3 0>; /* PCH_TO_EC_GENERIC_4 */ + }; + wui_vw_pch_to_ec_gen_5: wui2-4-1 { + miwus = <&miwu2 3 1>; /* PCH_TO_EC_GENERIC_5 */ + }; + wui_vw_pch_to_ec_gen_6: wui2-4-2 { + miwus = <&miwu2 3 2>; /* PCH_TO_EC_GENERIC_6 */ + }; + wui_vw_pch_to_ec_gen_7: wui2-4-3 { + miwus = <&miwu2 3 3>; /* PCH_TO_EC_GENERIC_7 */ + }; + wui_vw_host_c10: wui2-4-4 { + miwus = <&miwu2 3 4>; /* HOST_C10 */ + }; + + /* MIWU group E */ + wui_ioc0: wui2-5-0 { + miwus = <&miwu2 4 0>; /* GPIOC0 */ + }; + wui_ioc1: wui2-5-1 { + miwus = <&miwu2 4 1>; /* GPIOC1 */ + }; + wui_ioc2: wui2-5-2 { + miwus = <&miwu2 4 2>; /* GPIOC2 */ + }; + wui_ioc3: wui2-5-3 { + miwus = <&miwu2 4 3>; /* GPIOC3 */ + }; + wui_ioc4: wui2-5-4 { + miwus = <&miwu2 4 4>; /* GPIOC4 */ + }; + wui_ioc5: wui2-5-5 { + miwus = <&miwu2 4 5>; /* GPIOC5 */ + }; + wui_ioc6: wui2-5-6 { + miwus = <&miwu2 4 6>; /* GPIOC6 */ + }; + wui_ioc7: wui2-5-7 { + miwus = <&miwu2 4 7>; /* GPIOC7 */ + }; + + /* MIWU group F */ + wui_iod0: wui2-6-0 { + miwus = <&miwu2 5 0>; /* GPIOD0 */ + }; + wui_iod1: wui2-6-1 { + miwus = <&miwu2 5 1>; /* GPIOD1 */ + }; + wui_iod2: wui2-6-2 { + miwus = <&miwu2 5 2>; /* GPIOD2 */ + }; + wui_iod3: wui2-6-3 { + miwus = <&miwu2 5 3>; /* GPIOD3 */ + }; + wui_iod4: wui2-6-4 { + miwus = <&miwu2 5 4>; /* GPIOD4 */ + }; + wui_iod5: wui2-6-5 { + miwus = <&miwu2 5 5>; /* GPIOD5 */ + }; + wui_iod6: wui2-6-6 { + miwus = <&miwu2 5 6>; /* GPIOD6 */ + }; + wui_iod7: wui2-6-7 { + miwus = <&miwu2 5 7>; /* GPIOD7 */ + }; + + /* MIWU group G */ + wui_ioe0: wui2-7-0 { + miwus = <&miwu2 6 0>; /* GPIOE0 */ + }; + wui_ioe1: wui2-7-1 { + miwus = <&miwu2 6 1>; /* GPIOE1 */ + }; + wui_ioe2: wui2-7-2 { + miwus = <&miwu2 6 2>; /* GPIOE2 */ + }; + wui_ioe3: wui2-7-3 { + miwus = <&miwu2 6 3>; /* GPIOE3 */ + }; + wui_ioe4: wui2-7-4 { + miwus = <&miwu2 6 4>; /* GPIOE4 */ + }; + wui_ioe5: wui2-7-5 { + miwus = <&miwu2 6 5>; /* GPIOE5 */ + }; + wui_ioe6: wui2-7-6 { + miwus = <&miwu2 6 6>; /* GPIOE6 */ + }; + + /* MIWU group H */ + wui_iof0: wui2-8-0 { + miwus = <&miwu2 7 0>; /* GPIOF0 */ + }; + wui_iof1: wui2-8-1 { + miwus = <&miwu2 7 1>; /* GPIOF1 */ + }; + wui_iof2: wui2-8-2 { + miwus = <&miwu2 7 2>; /* GPIOF2 */ + }; + wui_iof3: wui2-8-3 { + miwus = <&miwu2 7 3>; /* GPIOF3 */ + }; + wui_vcc: wui2-8-7 { + miwus = <&miwu2 7 7>; /* VCC */ + }; + + /* Pseudo wui item means no mapping between source and wui */ + wui_none: wui-pseudo { + miwus = <&miwu_none 7 7>; + }; + }; + + /* Pseudo MIWU device to present no mapping relationship */ + miwu_none: miwu-pseudo { + compatible = "nuvoton,npcm-miwu"; + index = <3>; + #miwu-cells = <2>; + status = "disabled"; + }; +}; diff --git a/dts/arm/nuvoton/npcm/npcm.dtsi b/dts/arm/nuvoton/npcm/npcm.dtsi new file mode 100644 index 00000000000000..5d6b81f5ca2336 --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm.dtsi @@ -0,0 +1,235 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include + +/* Macros for device tree declarations of npcm soc family */ +#include +#include +#include +#include +#include + +/ { + cpus { + #address-cells = <1>; + #size-cells = <0>; + + cpu0: cpu@0 { + device_type = "cpu"; + compatible = "arm,cortex-m4"; + reg = <0>; + }; + }; + + def-io-conf-list { + compatible = "nuvoton,npcm-pinctrl-def"; + pinmux = <>; + }; + + pinctrl: pinctrl { + compatible = "nuvoton,npcm-pinctrl"; + status = "okay"; + }; + + soc { + pcc: clock-controller@4000d000 { + compatible = "nuvoton,npcm-pcc"; + /* Cells for bus type, clock control reg and bit */ + #clock-cells = <3>; + /* First reg region is Power Management Controller */ + /* Second reg region is Core Domain Clock Generator */ + reg = <0x4000d000 0x2000 + 0x400b5000 0x2000>; + reg-names = "pmc", "cdcg"; + }; + + scfg: scfg@400c3000 { + compatible = "nuvoton,npcm-scfg"; + /* First reg region is System Configuration Device */ + /* Second reg region is System Glue Device */ + reg = <0x400c3000 0x70 + 0x400a5000 0x2000>; + reg-names = "scfg", "glue"; + #alt-cells = <3>; + #lvol-cells = <2>; + }; + + mdc: mdc@4000c000 { + compatible = "syscon"; + reg = <0x4000c000 0xa>; + reg-io-width = <1>; + }; + + mdc_header: mdc@4000c00a { + compatible = "syscon"; + reg = <0x4000c00a 0x4>; + reg-io-width = <2>; + }; + + miwu0: miwu@400bb000 { + compatible = "nuvoton,npcm-miwu"; + reg = <0x400bb000 0x2000>; + index = <0>; + #miwu-cells = <2>; + }; + + miwu1: miwu@400bd000 { + compatible = "nuvoton,npcm-miwu"; + reg = <0x400bd000 0x2000>; + index = <1>; + #miwu-cells = <2>; + }; + + miwu2: miwu@400bf000 { + compatible = "nuvoton,npcm-miwu"; + reg = <0x400bf000 0x2000>; + index = <2>; + #miwu-cells = <2>; + }; + + gpio0: gpio@40081000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40081000 0x2000>; + gpio-controller; + index = <0x0>; + #gpio-cells=<2>; + }; + + gpio1: gpio@40083000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40083000 0x2000>; + gpio-controller; + index = <0x1>; + #gpio-cells=<2>; + }; + + gpio2: gpio@40085000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40085000 0x2000>; + gpio-controller; + index = <0x2>; + #gpio-cells=<2>; + }; + + gpio3: gpio@40087000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40087000 0x2000>; + gpio-controller; + index = <0x3>; + #gpio-cells=<2>; + }; + + gpio4: gpio@40089000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40089000 0x2000>; + gpio-controller; + index = <0x4>; + #gpio-cells=<2>; + }; + + gpio5: gpio@4008b000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4008b000 0x2000>; + gpio-controller; + index = <0x5>; + #gpio-cells=<2>; + }; + + gpio6: gpio@4008d000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4008d000 0x2000>; + gpio-controller; + index = <0x6>; + #gpio-cells=<2>; + }; + + gpio7: gpio@4008f000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4008f000 0x2000>; + gpio-controller; + index = <0x7>; + #gpio-cells=<2>; + }; + + gpio8: gpio@40091000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40091000 0x2000>; + gpio-controller; + index = <0x8>; + #gpio-cells=<2>; + }; + + gpio9: gpio@40093000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40093000 0x2000>; + gpio-controller; + index = <0x9>; + #gpio-cells=<2>; + }; + + gpioa: gpio@40095000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40095000 0x2000>; + gpio-controller; + index = <0xA>; + #gpio-cells=<2>; + }; + + gpiob: gpio@40097000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40097000 0x2000>; + gpio-controller; + index = <0xB>; + #gpio-cells=<2>; + }; + + gpioc: gpio@40099000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x40099000 0x2000>; + gpio-controller; + index = <0xC>; + #gpio-cells=<2>; + }; + + gpiod: gpio@4009b000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4009b000 0x2000>; + gpio-controller; + index = <0xD>; + #gpio-cells=<2>; + }; + + gpioe: gpio@4009d000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4009d000 0x2000>; + gpio-controller; + index = <0xE>; + #gpio-cells=<2>; + }; + + gpiof: gpio@4009f000 { + compatible = "nuvoton,npcm-gpio"; + reg = <0x4009f000 0x2000>; + gpio-controller; + index = <0xF>; + #gpio-cells=<2>; + }; + }; + + soc-id { + compatible = "nuvoton,npcm-soc-id"; + family-id = <0x20>; + }; + + booter-variant { + compatible = "nuvoton,npcm-booter-variant"; + }; +}; + +&nvic { + arm,num-irq-priority-bits = <3>; +}; diff --git a/dts/arm/nuvoton/npcm/npcm4.dtsi b/dts/arm/nuvoton/npcm/npcm4.dtsi index 35664956354215..a7cb004755e272 100644 --- a/dts/arm/nuvoton/npcm/npcm4.dtsi +++ b/dts/arm/nuvoton/npcm/npcm4.dtsi @@ -4,36 +4,119 @@ * SPDX-License-Identifier: Apache-2.0 */ -#include +/* npcm4 series pinmux mapping table */ +#include "npcm4/npcm4-alts-map.dtsi" +/* npcm4 series mapping table between MIWU groups and interrupts */ +#include "npcm4/npcm4-miwus-wui-map.dtsi" -#include -#include -#include +/* Device tree declarations of npcm soc family */ +#include "npcm.dtsi" / { - cpus { - #address-cells = <1>; - #size-cells = <0>; - - cpu0: cpu@0 { - device_type = "cpu"; - compatible = "arm,cortex-m4"; - reg = <0>; - }; + def-io-conf-list { + /* Change default functional pads to GPIOs */ + pinmux = <&alt5c_psin_sel + &alt5c_psout_sel + &alt5c_pson_sel + &alt5d_rstout0_sel + &alt5d_rstout1_sel + &alt5d_rstout2_sel + &alt5d_sktocc_sel + &alt5d_caseopen_sel + &alt5e_dpwrok_sel + &alt5e_rsmrst_sel + &alt5e_deep_s5_sel + &alt5e_pwrok0_sel + &alt5e_3vsbsw_sel>; }; soc { + pcc: clock-controller@4000d000 { + clock-frequency = ; /* OFMCLK runs at 96MHz */ + core-prescaler = <1>; /* CORE_CLK runs at 96MHz */ + apb1-prescaler = <8>; /* APB1_CLK runs at 12MHz */ + apb2-prescaler = <1>; /* APB2_CLK runs at 96MHz */ + apb3-prescaler = <1>; /* APB3_CLK runs at 96MHz */ + }; + + gpio0: gpio@40081000 { + wui-maps = <&wui_io00 &wui_io01 &wui_io02 &wui_io03 + &wui_io04 &wui_io05 &wui_io06 &wui_io07>; + }; + + gpio1: gpio@40083000 { + wui-maps = <&wui_io10 &wui_io11 &wui_io12 &wui_io13 + &wui_io14 &wui_io15 &wui_io16 &wui_io17>; + }; + + gpio2: gpio@40085000 { + wui-maps = <&wui_io20 &wui_io21 &wui_io22 &wui_io23 + &wui_io24 &wui_io25 &wui_io26 &wui_io27>; + }; + + gpio3: gpio@40087000 { + wui-maps = <&wui_io30 &wui_io31 &wui_io32 &wui_io33 + &wui_io34 &wui_io35 &wui_io36 &wui_io37>; + }; + + gpio4: gpio@40089000 { + wui-maps = <&wui_io40 &wui_io41 &wui_io42 &wui_io43 + &wui_io44 &wui_io45 &wui_io46 &wui_io47>; + }; + + gpio5: gpio@4008b000 { + wui-maps = <&wui_io50 &wui_io51 &wui_io52 &wui_io53 + &wui_io54 &wui_io55 &wui_io56 &wui_io57>; + }; + + gpio6: gpio@4008d000 { + wui-maps = <&wui_io60 &wui_io61 &wui_io62 &wui_io63 + &wui_io64 &wui_io65 &wui_io66 &wui_io67>; + }; - mdc: mdc@4000c000 { - compatible = "syscon"; - reg = <0x4000c000 0xa>; - reg-io-width = <1>; + gpio7: gpio@4008f000 { + wui-maps = <&wui_io70 &wui_io71 &wui_io72 &wui_io73 + &wui_io74 &wui_io75 &wui_io76 &wui_io77>; }; - mdc_header: mdc@4000c00a { - compatible = "syscon"; - reg = <0x4000c00a 0x4>; - reg-io-width = <2>; + gpio8: gpio@40091000 { + wui-maps = <&wui_io80 &wui_io81 &wui_io82 &wui_io83 + &wui_io84 &wui_io85 &wui_io86 &wui_io87>; + }; + + gpio9: gpio@40093000 { + wui-maps = <&wui_io90 &wui_io91 &wui_io92 &wui_io93 + &wui_io94 &wui_io95 &wui_io96 &wui_io97>; + }; + + gpioa: gpio@40095000 { + wui-maps = <&wui_ioa0 &wui_ioa1 &wui_ioa2 &wui_ioa3 + &wui_ioa4 &wui_ioa5 &wui_ioa6 &wui_ioa7>; + }; + + gpiob: gpio@40097000 { + wui-maps = <&wui_iob0 &wui_iob1 &wui_iob2 &wui_iob3 + &wui_iob4 &wui_iob5 &wui_iob6 &wui_iob7>; + }; + + gpioc: gpio@40099000 { + wui-maps = <&wui_ioc0 &wui_ioc1 &wui_ioc2 &wui_ioc3 + &wui_ioc4 &wui_ioc5 &wui_ioc6 &wui_ioc7>; + }; + + gpiod: gpio@4009b000 { + wui-maps = <&wui_iod0 &wui_iod1 &wui_iod2 &wui_iod3 + &wui_iod4 &wui_iod5 &wui_iod6 &wui_iod7>; + }; + + gpioe: gpio@4009d000 { + wui-maps = <&wui_ioe0 &wui_ioe1 &wui_ioe2 &wui_ioe3 + &wui_ioe4 &wui_ioe5 &wui_ioe6 &wui_none>; + }; + + gpiof: gpio@4009f000 { + wui-maps = <&wui_iof0 &wui_iof1 &wui_iof2 &wui_iof3 + &wui_none &wui_none &wui_none &wui_none>; }; }; @@ -44,7 +127,3 @@ */ }; }; - -&nvic { - arm,num-irq-priority-bits = <3>; -}; diff --git a/dts/arm/nuvoton/npcm/npcm4/npcm4-alts-map.dtsi b/dts/arm/nuvoton/npcm/npcm4/npcm4-alts-map.dtsi new file mode 100644 index 00000000000000..b43679b2b71308 --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm4/npcm4-alts-map.dtsi @@ -0,0 +1,8 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/* Common pin-mux configurations in npcm family */ +#include diff --git a/dts/arm/nuvoton/npcm/npcm4/npcm4-miwus-wui-map.dtsi b/dts/arm/nuvoton/npcm/npcm4/npcm4-miwus-wui-map.dtsi new file mode 100644 index 00000000000000..481ba366e4e789 --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm4/npcm4-miwus-wui-map.dtsi @@ -0,0 +1,16 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +/* Common Wake-Up Unit Input (WUI) mapping configurations in npcm family */ +#include + +/* Specific Wake-Up Unit Input (WUI) mapping configurations in npcm4 series */ +/ { + /* Mapping between MIWU wui bits and source device */ + npcm-miwus-wui-map { + compatible = "nuvoton,npcm-miwu-wui-map"; + }; +}; diff --git a/dts/arm/nuvoton/npcm/npcm4/npcm4-pinctrl.dtsi b/dts/arm/nuvoton/npcm/npcm4/npcm4-pinctrl.dtsi new file mode 100644 index 00000000000000..06a544ebe057e2 --- /dev/null +++ b/dts/arm/nuvoton/npcm/npcm4/npcm4-pinctrl.dtsi @@ -0,0 +1,187 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +&pinctrl { + + /* Prebuild nodes for peripheral device's pin-muxing and pad properties */ + /* Flash Interface Unit (FIU) */ + /omit-if-no-ref/ fiu0_shd_cs_io0_io1_clk_gp44_45_46_47: periph-fiu0-shd { + dev-ctl = <0x0 6 1 0x00>; + pinmux = <&altc_shd_spi>; + }; + + /omit-if-no-ref/ fiu0_shd_quad_io2_io3_clk_gp55_56: periph-fiu0-shd-quad { + pinmux = <&altc_shd_spi_quad>; + }; + + /* PSPI Intefaces */ + /omit-if-no-ref/ pspi1_clk_io0_io1_io2_io3_cs_gp66_67_70_73_76_77: periph-pspi1 { + pinmux = <&altc_spip1_sl>; + }; + + /* I2C peripheral interfaces */ + /omit-if-no-ref/ i2c1a_scl_sda_gp60_61: periph-i2c1a { + pinmux = <&alta_smb1a_sl>; + }; + + /omit-if-no-ref/ i2c1b_scl_sda_gp26_25: periph-i2c1b { + pinmux = <&alta_smb1b_sl>; + }; + + /omit-if-no-ref/ i2c2a_scl_sda_gp11_13: periph-i2c2a { + pinmux = <&alte_smb2a_sl>; + }; + + /omit-if-no-ref/ i2c3a_scl_sda_gpa7_a2: periph-i2c3a { + pinmux = <&alta_smb3a_sl>; + }; + + /omit-if-no-ref/ i2c4a_scl_sda_gp36_37: periph-i2c4a { + pinmux = <&alta_smb4a_sl>; + }; + + /omit-if-no-ref/ i2c4b_scl_sda_gpf0_f1: periph-i2c4b { + pinmux = <&alt6d_smb4b_sl>; + }; + + /omit-if-no-ref/ i2c5a_scl_sda_gp34_35: periph-i2c5a { + pinmux = <&alta_smb5a_sl>; + }; + + /omit-if-no-ref/ i2c6a_scl_gp96: periph-i2c6a-scl { + pinmux = <&alt7_no_gp96>; + }; + + /omit-if-no-ref/ i2c6a_sda_gp97: periph-i2c6a-sda { + pinmux = <&alt7_no_gp97>; + }; + + /omit-if-no-ref/ i2c6b_scl_sda_gp16_17: periph-i2c6b { + pinmux = <&alt6d_smb6b_sl>; + }; + + /omit-if-no-ref/ i2c7a_scl_sda_gpc2_c3: periph-i2c7a { + pinmux = <&alt6d_smb7a_sl>; + }; + + /omit-if-no-ref/ i2c8a_scl_sda_gpc6_c7: periph-i2c8a { + pinmux = <&alt6d_smb8a_sl>; + }; + + /omit-if-no-ref/ i2c9a_scl_sda_gp32_33: periph-i2c9a { + pinmux = <&alt6d_smb9a_sl>; + }; + + /omit-if-no-ref/ i2c10a_scl_sda_gpd2_d3: periph-i2c10a { + pinmux = <&alt6d_smb10a_sl>; + }; + + /omit-if-no-ref/ i2c11a_scl_sda_gpd4_d5: periph-i2c11a { + pinmux = <&alt6d_smb11a_sl>; + }; + + /omit-if-no-ref/ i2c12a_scl_sda_gpd6_d7: periph-i2c12a { + pinmux = <&alt6d_smb12a_sl>; + }; + + /* I3C peripheral interfaces */ + /omit-if-no-ref/ i3c1_scl_sda_gp21_22: periph-i3c1 { + pinmux = <&alt10_i3c1_sl>; + }; + + /omit-if-no-ref/ i3c2_scl_sda_gp23_24: periph-i3c2 { + pinmux = <&alt10_i3c2_sl>; + }; + + /omit-if-no-ref/ i3c3_scl_sda_gp26_25: periph-i3c3 { + pinmux = <&alt10_i3c3_sl>; + }; + + /omit-if-no-ref/ i3c4_scl_sda_gpd0_d1: periph-i3c4 { + pinmux = <&alt10_i3c4_sl>; + }; + + /omit-if-no-ref/ i3c5_scl_sda_gp82_83: periph-i3c5 { + pinmux = <&alta_i3c5_sl>; + }; + + /omit-if-no-ref/ i3c6_scl_sda_gp96_97: periph-i3c6 { + pinmux = <&alt7_i3c6_sl>; + }; + + /* UART peripheral interfaces */ + /omit-if-no-ref/ cr_uart1_sin_gp14: periph-cr-uart1-in { + pinmux = <&altc_urti1_sl>; + }; + + /omit-if-no-ref/ cr_uart1_sout_gp15: periph-cr-uart1-out { + pinmux = <&alta_urto2_sl>; + }; + + /omit-if-no-ref/ cr_uart2_sin_gp30: periph-cr-uart2-in { + pinmux = <&alt31_urti2_sl>; + }; + + /omit-if-no-ref/ cr_uart2_sout_gp31: periph-cr-uart2-out { + pinmux = <&alt31_urto3_sl>; + }; + + /* ADC peripheral interfaces */ + /omit-if-no-ref/ adc_vin1_gp93: periph-adc-vin1 { + pinmux = <&alt1_vin1_sl>; + }; + + /omit-if-no-ref/ adc_vin2_gp94: periph-adc-vin2 { + pinmux = <&alt1_vin2_sl>; + }; + + /omit-if-no-ref/ adc_vin3_gp95: periph-adc-vin3 { + pinmux = <&alt1_vin3_sl>; + }; + + /omit-if-no-ref/ adc_vin5_gp87: periph-adc-vin5 { + pinmux = <&alt1_vin5_sl>; + }; + + /omit-if-no-ref/ adc_vin7_gp86: periph-adc-vin7 { + pinmux = <&alt1_vin7_sl>; + }; + + /omit-if-no-ref/ adc_vin14_gp92: periph-adc-vin14 { + pinmux = <&alt2_vin14_sl>; + }; + + /omit-if-no-ref/ adc_vin15_gp91: periph-adc-vin15 { + pinmux = <&alt2_vin15_sl>; + }; + + /omit-if-no-ref/ adc_vin16_gp91: periph-adc-vin16 { + pinmux = <&alt2_vin16_sl>; + }; + + /* SGPIO peripheral interfaces */ + /omit-if-no-ref/ iox1_ldsh_dout_din_sclk_gp74_75_f2_f3: periph-siox1 { + pinmux = <&alt6a_siox1_sl>; + }; + + /omit-if-no-ref/ iox2_ldsh_dout_din_sclk_gpa0_a1_a3_a4: periph-siox2 { + pinmux = <&alt6a_siox2_sl>; + }; + + /* PECI peripheral interfaces */ + /omit-if-no-ref/ peci0_gp97: periph-peci0 { + pinmux = <&alt5_peci_en>; + }; + + /* USB peripheral interfaces */ + /omit-if-no-ref/ usbdphy_en: periph-usbd-phy-en { + pinmux = <&alt2e_usbd_phy_en>; + }; + + /omit-if-no-ref/ usbdphy_clk_external: periph-usbd-phy-clk-sel { + pinmux = <&alt2e_usbd_phy_clk_sel>; + }; +}; diff --git a/dts/bindings/clock/nuvoton,npcm-pcc.yaml b/dts/bindings/clock/nuvoton,npcm-pcc.yaml new file mode 100644 index 00000000000000..cf8583a5e50c43 --- /dev/null +++ b/dts/bindings/clock/nuvoton,npcm-pcc.yaml @@ -0,0 +1,167 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: | + Nuvoton, NPCM PCC (Power and Clock Controller) node. + Besides power management, this node is also in charge of configuring the + Oscillator Frequency Multiplier Clock (OFMCLK), which is derived from + High-Frequency Clock Generator (HFCG), is the source clock of Cortex-M4 core + and most of NPCM hardware modules. + + Here is an example of configuring OFMCLK and the other clock sources derived + from it in board dts file. + &pcc { + clock-frequency = ; /* OFMCLK runs at 96MHz */ + core-prescaler = <1>; /* CORE_CLK runs at 96MHz */ + apb1-prescaler = <8>; /* APB1_CLK runs at 12MHz */ + apb2-prescaler = <1>; /* APB2_CLK runs at 96MHz */ + apb3-prescaler = <1>; /* APB3_CLK runs at 96MHz */ + }; + +compatible: "nuvoton,npcm-pcc" + +include: [clock-controller.yaml, base.yaml] + +properties: + reg: + required: true + + clock-frequency: + required: true + type: int + description: | + Default frequency in Hz for HFCG output clock (OFMCLK). Currently, + only the following values are allowed: + 96000000, 96 MHz + 48000000, 48 MHz + enum: + - 96000000 + - 48000000 + + core-prescaler: + type: int + required: true + description: | + Core clock prescaler (FPRED). It sets the Core frequency, CORE_CLK, by + dividing OFMCLK(MCLK) and needs to meet the following requirements. + - CORE_CLK must be set to 4MHz <= CORE_CLK <= 100MHz. + = Only the following values are allowed: + 1, CORE_CLK = OFMCLK + 2, CORE_CLK = OFMCLK / 2 + 3, CORE_CLK = OFMCLK / 3 + 4, CORE_CLK = OFMCLK / 4 + 5, CORE_CLK = OFMCLK / 5 + 6, CORE_CLK = OFMCLK / 6 + 7, CORE_CLK = OFMCLK / 7 + 8, CORE_CLK = OFMCLK / 8 + 9, CORE_CLK = OFMCLK / 9 + 10, CORE_CLK = OFMCLK / 10 + enum: + - 1 + - 2 + - 3 + - 4 + - 5 + - 6 + - 7 + - 8 + - 9 + - 10 + + apb1-prescaler: + type: int + required: true + description: | + APB1 prescaler. It sets the APB1 bus frequency, APB1_CLK, by dividing + OFMCLK(MCLK) and needs to meet the following requirements. + - APB1_CLK must be set to 4MHz <= APB1_CLK <= 50MHz. + - APB1_CLK must be an integer division (including 1) of CORE_CLK. + = Only the following values are allowed: + 1, APB1_CLK = OFMCLK + 2, APB1_CLK = OFMCLK / 2 + 3, APB1_CLK = OFMCLK / 3 + 4, APB1_CLK = OFMCLK / 4 + 5, APB1_CLK = OFMCLK / 5 + 6, APB1_CLK = OFMCLK / 6 + 7, APB1_CLK = OFMCLK / 7 + 8, APB1_CLK = OFMCLK / 8 + 9, APB1_CLK = OFMCLK / 9 + 10, APB1_CLK = OFMCLK / 10 + enum: + - 1 + - 2 + - 3 + - 4 + - 5 + - 6 + - 7 + - 8 + - 9 + - 10 + + apb2-prescaler: + type: int + required: true + description: | + APB2 prescaler. It sets the APB2 bus frequency, APB2_CLK, by dividing + OFMCLK(MCLK) and needs to meet the following requirements. + - APB2_CLK must be set to 8MHz <= APB2_CLK <= 50MHz. + - APB2_CLK must be an integer division (including 1) of CORE_CLK. + = Only the following values are allowed: + 1, APB2_CLK = OFMCLK + 2, APB2_CLK = OFMCLK / 2 + 3, APB2_CLK = OFMCLK / 3 + 4, APB2_CLK = OFMCLK / 4 + 5, APB2_CLK = OFMCLK / 5 + 6, APB2_CLK = OFMCLK / 6 + 7, APB2_CLK = OFMCLK / 7 + 8, APB2_CLK = OFMCLK / 8 + 9, APB2_CLK = OFMCLK / 9 + 10, APB2_CLK = OFMCLK / 10 + enum: + - 1 + - 2 + - 3 + - 4 + - 5 + - 6 + - 7 + - 8 + - 9 + - 10 + + apb3-prescaler: + type: int + required: true + description: | + APB3 prescaler. It sets the APB3 bus frequency, APB3_CLK, by dividing + OFMCLK(MCLK) and needs to meet the following requirements. + - APB3_CLK must be set to 12.5MHz <= APB3_CLK <= 50MHz. + - APB3_CLK must be an integer division (including 1) of CORE_CLK. + = Only the following values are allowed: + 1, APB3_CLK = OFMCLK + 2, APB3_CLK = OFMCLK / 2 + 3, APB3_CLK = OFMCLK / 3 + 4, APB3_CLK = OFMCLK / 4 + 5, APB3_CLK = OFMCLK / 5 + 6, APB3_CLK = OFMCLK / 6 + 7, APB3_CLK = OFMCLK / 7 + 8, APB3_CLK = OFMCLK / 8 + 9, APB3_CLK = OFMCLK / 9 + 10, APB3_CLK = OFMCLK / 10 + enum: + - 1 + - 2 + - 3 + - 4 + - 5 + - 6 + - 7 + - 8 + - 9 + - 10 + +clock-cells: + - bus + - ctl + - bit diff --git a/dts/bindings/gpio/nuvoton,npcm-gpio.yaml b/dts/bindings/gpio/nuvoton,npcm-gpio.yaml new file mode 100644 index 00000000000000..ace4f853232eb6 --- /dev/null +++ b/dts/bindings/gpio/nuvoton,npcm-gpio.yaml @@ -0,0 +1,36 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCM-GPIO node + +compatible: "nuvoton,npcm-gpio" + +include: [gpio-controller.yaml, base.yaml] + +properties: + reg: + required: true + + index: + type: int + required: true + description: index of gpio device + + wui-maps: + type: phandles + required: true + description: | + Mapping table between Wake-Up Input (WUI) and 8 IOs belong to this device. + Please notice not all IOs connect to WUIs. + In this case, it will be presented by wui_none. + + For example the WUI mapping on NPCM4 GPIO8 would be + wui-maps = <&wui_io80 &wui_io81 &wui_io82 &wui_io83 + &wui_none &wui_none &wui_io86 &wui_io87>; + + "#gpio-cells": + const: 2 + +gpio-cells: + - pin + - flags diff --git a/dts/bindings/interrupt-controller/nuvoton,npcm-miwu-wui-map.yaml b/dts/bindings/interrupt-controller/nuvoton,npcm-miwu-wui-map.yaml new file mode 100644 index 00000000000000..f4d6d21c93056d --- /dev/null +++ b/dts/bindings/interrupt-controller/nuvoton,npcm-miwu-wui-map.yaml @@ -0,0 +1,13 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: NPCM-MIWU Wake-Up Unit Input (WUI) mapping child node + +compatible: "nuvoton,npcm-miwu-wui-map" + +child-binding: + description: Child node to present the mapping between input of MIWU and its source device + properties: + miwus: + type: phandle-array + required: true diff --git a/dts/bindings/interrupt-controller/nuvoton,npcm-miwu.yaml b/dts/bindings/interrupt-controller/nuvoton,npcm-miwu.yaml new file mode 100644 index 00000000000000..1bed91c845edaa --- /dev/null +++ b/dts/bindings/interrupt-controller/nuvoton,npcm-miwu.yaml @@ -0,0 +1,23 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCM Multi-Input Wake-Up Unit (MIWU) node + +compatible: "nuvoton,npcm-miwu" + +include: [base.yaml] + +properties: + index: + type: int + required: true + description: index of miwu device + + "#miwu-cells": + type: int + required: true + description: Number of items to present a MIWU input source specifier + +miwu-cells: + - group + - bit diff --git a/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-conf.yaml b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-conf.yaml new file mode 100644 index 00000000000000..8565b5adfcafa4 --- /dev/null +++ b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-conf.yaml @@ -0,0 +1,16 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: | + Nuvoton NPCM Pin-Mux Configuration + Configuration map from Nuvoton NPCM GPIO to pinmux controller + (SCFG) driver instances. + +compatible: "nuvoton,npcm-pinctrl-conf" +child-binding: + description: NPCM Pinmux configuration child node + properties: + alts: + type: phandle-array + required: true + description: A SCFG ALT (Alternative controllers) specifier for pinmuxing of npcm esio diff --git a/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-def.yaml b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-def.yaml new file mode 100644 index 00000000000000..f81c8475d339fa --- /dev/null +++ b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl-def.yaml @@ -0,0 +1,14 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCM Default Pins Configurations + +compatible: "nuvoton,npcm-pinctrl-def" + +include: [base.yaml] + +properties: + pinmux: + type: phandles + required: true + description: list of configurations of pinmux controllers need to set diff --git a/dts/bindings/pinctrl/nuvoton,npcm-pinctrl.yaml b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl.yaml new file mode 100644 index 00000000000000..d096a4718f04ed --- /dev/null +++ b/dts/bindings/pinctrl/nuvoton,npcm-pinctrl.yaml @@ -0,0 +1,97 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: | + The Nuvoton pin controller is a singleton node responsible for controlling + pin function selection and pin properties. For example, you can use these + nodes to select peripheral pin functions. + + Here is a list of supported standard pin properties: + - bias-pull-down: Enable pull-down resistor. + - bias-pull-up: Enable pull-up resistor. + + Custom pin properties for npcx series are available also: + - pinmux-gpio: Inverse pinmux back to gpio + + An example for NPCM4 family, include the chip level pinctrl DTSI file in the + board level DTS: + + #include + + We want to use the I2C0_0 port of the NPCM400F controller and enable the + internal 3.3V pull-up if its i2c frequency won't exceed 400kHz. + + To change a pin's pinctrl default properties, add a reference to the + pin in the board's DTS file and set the properties as below: + + &i2c0_0_sda_scl_gpb4_b5 { + bias-pull-up; /* Enable internal pull-up for i2c0_0 */ + pinmux-locked; /* Lock pinmuxing */ + }; + + &i2c0_0 { + pinctrl-0 = <&i2c0_0_sda_scl_gpb4_b5>; + pinctrl-names = "default"; + } + +compatible: "nuvoton,npcm-pinctrl" + +include: base.yaml + +child-binding: + description: | + NPCM pin controller pin configuration nodes + + include: + - name: pincfg-node.yaml + property-allowlist: + - bias-pull-down + - bias-pull-up + - drive-open-drain + + properties: + pinmux: + type: phandle + description: Configurations of pinmux selection + dev-ctl: + type: array + description: Configurations of device control such as tri-state, io type and so on. + periph-pupd: + type: array + description: | + A map to PUPD_ENn register/bit that enable pull-up/down of NPCX peripheral devices. + Please don't overwrite this property in the board-level DT driver. + psl-offset: + type: int + description: | + Offset to PSL_CTS register that is used for PSL input's status and detection mode. + Please don't overwrite this property in the board-level DT driver. + psl-polarity: + type: phandle + description: | + A map to DEVALTn that configures detection polarity of PSL input pads. + Please don't overwrite this property in the board-level DT driver. + pinmux-locked: + type: boolean + description: Lock pinmux selection + pinmux-gpio: + type: boolean + description: Inverse pinmux selection to GPIO + psl-in-mode: + type: string + description: | + The assertion detection mode of PSL input selection + - "level": Select the detection mode to level detection + - "edge": Select the detection mode to edge detection + enum: + - "level" + - "edge" + psl-in-pol: + type: string + description: | + The assertion detection polarity of PSL input selection + - "low-falling": Select the detection polarity to low/falling + - "high-rising": Select the detection polarity to high/rising + enum: + - "low-falling" + - "high-rising" diff --git a/dts/bindings/pinctrl/nuvoton,npcm-scfg.yaml b/dts/bindings/pinctrl/nuvoton,npcm-scfg.yaml new file mode 100644 index 00000000000000..30898ed862891c --- /dev/null +++ b/dts/bindings/pinctrl/nuvoton,npcm-scfg.yaml @@ -0,0 +1,32 @@ +# Copyright (c) 2024 Nuvoton Technology Corporation. +# SPDX-License-Identifier: Apache-2.0 + +description: Nuvoton, NPCM System Configuration (Pinmux, 1.8V support and so on) node + +compatible: "nuvoton,npcm-scfg" + +include: [base.yaml] + +properties: + reg: + required: true + + "#alt-cells": + type: int + required: true + description: Number of items to expect in a SCFG ALT (Alternative controllers) specifier + + "#lvol-cells": + type: int + required: true + description: | + Number of items to expect in a SCFG LV_GPIO_CTL (Low level IO controllers) specifier + +alt-cells: + - group + - bit + - inv + +lvol-cells: + - ctrl + - bit diff --git a/include/zephyr/dt-bindings/clock/npcm_clock.h b/include/zephyr/dt-bindings/clock/npcm_clock.h new file mode 100755 index 00000000000000..7308991ad4e265 --- /dev/null +++ b/include/zephyr/dt-bindings/clock/npcm_clock.h @@ -0,0 +1,34 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ +#ifndef ZEPHYR_INCLUDE_DT_BINDINGS_CLOCK_NPCM_CLOCK_H_ +#define ZEPHYR_INCLUDE_DT_BINDINGS_CLOCK_NPCM_CLOCK_H_ + +/* clock bus references */ +#define NPCM_CLOCK_BUS_FREERUN 0 +#define NPCM_CLOCK_BUS_LFCLK 1 +#define NPCM_CLOCK_BUS_OSC 2 +#define NPCM_CLOCK_BUS_FIU 3 +#define NPCM_CLOCK_BUS_CORE 4 +#define NPCM_CLOCK_BUS_APB1 5 +#define NPCM_CLOCK_BUS_APB2 6 +#define NPCM_CLOCK_BUS_APB3 7 +#define NPCM_CLOCK_BUS_APB4 8 +#define NPCM_CLOCK_BUS_AHB6 9 +#define NPCM_CLOCK_BUS_FMCLK 10 + +/* clock enable/disable references */ +#define NPCM_PWDWN_CTL0 0 +#define NPCM_PWDWN_CTL1 1 +#define NPCM_PWDWN_CTL2 2 +#define NPCM_PWDWN_CTL3 3 +#define NPCM_PWDWN_CTL4 4 +#define NPCM_PWDWN_CTL5 5 +#define NPCM_PWDWN_CTL6 6 +#define NPCM_PWDWN_CTL7 7 +#define NPCM_PWDWN_CTL8 8 +#define NPCM_PWDWN_CTL_COUNT 9 + +#endif /* ZEPHYR_INCLUDE_DT_BINDINGS_CLOCK_NPCX_CLOCK_H_ */ diff --git a/include/zephyr/dt-bindings/pinctrl/npcm-pinctrl.h b/include/zephyr/dt-bindings/pinctrl/npcm-pinctrl.h new file mode 100644 index 00000000000000..ce565bdc033f0d --- /dev/null +++ b/include/zephyr/dt-bindings/pinctrl/npcm-pinctrl.h @@ -0,0 +1,16 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ +#ifndef ZEPHYR_INCLUDE_DT_BINDINGS_PINCTRL_NPCM_PINCTRL_H_ +#define ZEPHYR_INCLUDE_DT_BINDINGS_PINCTRL_NPCM_PINCTRL_H_ + +/** + * @brief NPCM specific PIN configuration flag + * + * Pin configuration is coded with the following fields + * Reserved [ 0 : 31] + */ + +#endif /* ZEPHYR_INCLUDE_DT_BINDINGS_PINCTRL_NPCM_PINCTRL_H_ */ diff --git a/soc/nuvoton/npcm/common/CMakeLists.txt b/soc/nuvoton/npcm/common/CMakeLists.txt index 371a459d829483..10cb1e6f11c6e0 100644 --- a/soc/nuvoton/npcm/common/CMakeLists.txt +++ b/soc/nuvoton/npcm/common/CMakeLists.txt @@ -5,6 +5,10 @@ zephyr_include_directories(.) +zephyr_sources( + scfg.c +) + set(NPCM_BIN_NAME ${CONFIG_KERNEL_BIN_NAME}_signed.bin) string(TOUPPER "${SOC_NAME}" soc_name_upper) diff --git a/soc/nuvoton/npcm/common/pinctrl_soc.h b/soc/nuvoton/npcm/common/pinctrl_soc.h new file mode 100644 index 00000000000000..b2dadb807ca3a2 --- /dev/null +++ b/soc/nuvoton/npcm/common/pinctrl_soc.h @@ -0,0 +1,182 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_PINCTRL_SOC_H_ +#define _NUVOTON_PINCTRL_SOC_H_ + +#include +#include +#include + +/** + * @brief Pinctrl node types in NPCM series + */ +enum npcm_pinctrl_type { + NPCM_PINCTRL_TYPE_PERIPH, + NPCM_PINCTRL_TYPE_DEVICE_CTRL, + NPCM_PINCTRL_TYPE_RESERVED, +}; + +/** + * @brief Suppoerted peripheral device configuration type in NPCM series + */ +enum npcm_periph_type { + NPCM_PINCTRL_TYPE_PERIPH_PINMUX, + NPCM_PINCTRL_TYPE_PERIPH_PUPD, +}; + +/** + * @brief Suppoerted IO bias type in NPCM series + */ +enum npcm_io_bias_type { + NPCM_BIAS_TYPE_NONE, + NPCM_BIAS_TYPE_PULL_DOWN, + NPCM_BIAS_TYPE_PULL_UP, +}; + +/** + * @brief NPCM peripheral device configuration structure + * + * Used to indicate the peripheral device's corresponding register/bit for + * pin-muxing, pull-up/down and so on. + */ +struct npcm_periph { + /** Related register group for peripheral device. */ + uint16_t group: 8; + /** Related register bit for peripheral device. */ + uint16_t bit: 3; + /** The polarity for peripheral device functionality. */ + bool inverted: 1; + /** The type of peripheral device configuration. */ + enum npcm_periph_type type: 2; + /** Reserved field. */ + uint16_t reserved: 2; +} __packed; + +/** + * @brief NPCM device control structure + * + * Used to indicate the device's corresponding register/field for its io + * characteristics such as tri-state, power supply type selection, and so on. + */ +struct npcm_dev_ctl { + /** Related register offset for device configuration. */ + uint16_t offest: 5; + /** Related register field offset for device control. */ + uint16_t field_offset: 3; + /** Related register field size for device control. */ + uint16_t field_size: 3; + /** field value */ + uint16_t field_value: 5; +} __packed; + +/** + * @brief Type for NPCM pin configuration. Please make sure the size of this + * structure is 4 bytes in case the impact of ROM usage. + */ +struct npcm_pinctrl { + union { + struct npcm_periph periph; + struct npcm_dev_ctl dev_ctl; + uint16_t cfg_word; + } cfg; + struct { + /** Indicates the current pinctrl type. */ + enum npcm_pinctrl_type type :2; + /** Properties used for pinmuxing. */ + bool pinmux_gpio :1; + /** Properties used for io-pad. */ + enum npcm_io_bias_type io_bias_type :2; + uint16_t reserved :11; + } flags; +} __packed; + +typedef struct npcm_pinctrl pinctrl_soc_pin_t; + +/** Helper macros for NPCM pinctrl configurations. */ +#define Z_PINCTRL_NPCM_BIAS_TYPE(node_id) \ + COND_CODE_1(DT_PROP(node_id, bias_pull_up), (NPCM_BIAS_TYPE_PULL_UP), \ + (COND_CODE_1(DT_PROP(node_id, bias_pull_down), \ + (NPCM_BIAS_TYPE_PULL_DOWN), (NPCM_BIAS_TYPE_NONE)))) + +#define Z_PINCTRL_NPCM_HAS_PUPD_PROP(node_id) \ + UTIL_OR(DT_PROP(node_id, bias_pull_down), \ + DT_PROP(node_id, bias_pull_up)) + +/** + * @brief Utility macro to initialize a periphral pinmux configuration. + * + * @param node_id Node identifier. + * @param prop Property name for pinmux configuration. (i.e. 'pinmux') + */ +#define Z_PINCTRL_NPCM_PERIPH_PINMUX_INIT(node_id, prop) \ + { \ + .flags.type = NPCM_PINCTRL_TYPE_PERIPH, \ + .flags.pinmux_gpio = DT_PROP(node_id, pinmux_gpio), \ + .cfg.periph.type = NPCM_PINCTRL_TYPE_PERIPH_PINMUX, \ + .cfg.periph.group = DT_PHA(DT_PROP(node_id, prop), alts, group), \ + .cfg.periph.bit = DT_PHA(DT_PROP(node_id, prop), alts, bit), \ + .cfg.periph.inverted = DT_PHA(DT_PROP(node_id, prop), alts, inv), \ + }, + +/** + * @brief Utility macro to initialize a periphral pinmux configuration. + * + * @param node_id Node identifier. + * @param prop Property name for pinmux configuration. (i.e. 'pinmux') + */ +#define Z_PINCTRL_NPCM_DEVICE_CONTROL_INIT(node_id, prop) \ + { \ + .flags.type = NPCM_PINCTRL_TYPE_DEVICE_CTRL, \ + .cfg.dev_ctl.offest = DT_PROP_BY_IDX(node_id, prop, 0), \ + .cfg.dev_ctl.field_offset = DT_PROP_BY_IDX(node_id, prop, 1), \ + .cfg.dev_ctl.field_size = DT_PROP_BY_IDX(node_id, prop, 2), \ + .cfg.dev_ctl.field_value = DT_PROP_BY_IDX(node_id, prop, 3), \ + }, + +/** + * @brief Utility macro to initialize a periphral pull-up/down configuration. + * + * @param node_id Node identifier. + * @param prop Property name for pull-up/down configuration. (i.e. 'periph-pupd') + */ +#define Z_PINCTRL_NPCM_PERIPH_PUPD_INIT(node_id, prop) \ + { \ + .flags.type = NPCM_PINCTRL_TYPE_PERIPH, \ + .flags.io_bias_type = Z_PINCTRL_NPCM_BIAS_TYPE(node_id), \ + .cfg.periph.type = NPCM_PINCTRL_TYPE_PERIPH_PUPD, \ + .cfg.periph.group = DT_PROP_BY_IDX(node_id, prop, 0), \ + .cfg.periph.bit = DT_PROP_BY_IDX(node_id, prop, 1), \ + }, + +/** + * @brief Utility macro to initialize all peripheral confiurations for each pin. + * + * @param node_id Node identifier. + * @param prop Pinctrl state property name. (i.e. 'pinctrl-0/1/2') + * @param idx Property entry index. + */ +#define Z_PINCTRL_STATE_PIN_INIT(node_id, prop, idx) \ + COND_CODE_1(Z_PINCTRL_NPCM_HAS_PUPD_PROP(DT_PROP_BY_IDX(node_id, prop, idx)), \ + (Z_PINCTRL_NPCM_PERIPH_PUPD_INIT( \ + DT_PROP_BY_IDX(node_id, prop, idx), periph_pupd)), ()) \ + COND_CODE_1(DT_NODE_HAS_PROP(DT_PROP_BY_IDX(node_id, prop, idx), dev_ctl), \ + (Z_PINCTRL_NPCM_DEVICE_CONTROL_INIT( \ + DT_PROP_BY_IDX(node_id, prop, idx), dev_ctl)), ()) \ + COND_CODE_1(DT_NODE_HAS_PROP(DT_PROP_BY_IDX(node_id, prop, idx), pinmux), \ + (Z_PINCTRL_NPCM_PERIPH_PINMUX_INIT( \ + DT_PROP_BY_IDX(node_id, prop, idx), pinmux)), ()) + +/** + * @brief Utility macro to initialize state pins contained in a given property. + * + * @param node_id Node identifier. + * @param prop Property name describing state pins. + */ +#define Z_PINCTRL_STATE_PINS_INIT(node_id, prop) \ + {DT_FOREACH_PROP_ELEM(node_id, prop, Z_PINCTRL_STATE_PIN_INIT)} + +#endif /* _NUVOTON_PINCTRL_SOC_H_ */ diff --git a/soc/nuvoton/npcm/common/scfg.c b/soc/nuvoton/npcm/common/scfg.c new file mode 100644 index 00000000000000..cfac6f2d392e90 --- /dev/null +++ b/soc/nuvoton/npcm/common/scfg.c @@ -0,0 +1,84 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#include +#include +#include +#include + +#include +LOG_MODULE_REGISTER(pimux_npcm, LOG_LEVEL_ERR); + +/* Driver config */ +struct npcm_scfg_config { + /* scfg device base address */ + uintptr_t base_scfg; + uintptr_t base_glue; +}; + +/* + * Get io list which default functionality are not IOs. Then switch them to + * GPIO in pin-mux init function. + * + * def-io-conf-list { + * pinmux = <&alt0_gpio_no_spip + * &alt0_gpio_no_fpip + * ...>; + * }; + */ +#define NPCM_NO_GPIO_ALT_ITEM(node_id, prop, idx) { \ + .group = DT_PHA(DT_PROP_BY_IDX(node_id, prop, idx), alts, group), \ + .bit = DT_PHA(DT_PROP_BY_IDX(node_id, prop, idx), alts, bit), \ + .inverted = DT_PHA(DT_PROP_BY_IDX(node_id, prop, idx), alts, inv), \ + }, + +static const struct npcm_alt def_alts[] = { + DT_FOREACH_PROP_ELEM(DT_INST(0, nuvoton_npcm_pinctrl_def), pinmux, + NPCM_NO_GPIO_ALT_ITEM) +}; + +static const struct npcm_scfg_config npcm_scfg_cfg = { + .base_scfg = DT_REG_ADDR_BY_NAME(DT_NODELABEL(scfg), scfg), + .base_glue = DT_REG_ADDR_BY_NAME(DT_NODELABEL(scfg), glue), +}; + +/* Driver convenience defines */ +#define HAL_SFCG_INST() (struct scfg_reg *)(npcm_scfg_cfg.base_scfg) + +#define HAL_GLUE_INST() (struct glue_reg *)(npcm_scfg_cfg.base_glue) + +/* Pin-control local functions */ +static void npcm_pinctrl_alt_sel(const struct npcm_alt *alt, int alt_func) +{ + const uint32_t scfg_base = npcm_scfg_cfg.base_scfg; + uint8_t alt_mask = BIT(alt->bit); + + /* + * alt_fun == 0 means select GPIO, otherwise Alternate Func. + * inverted == 0: + * Set devalt bit to select Alternate Func. + * inverted == 1: + * Clear devalt bit to select Alternate Func. + */ + if (!!alt_func != !!alt->inverted) { + NPCM_DEVALT(scfg_base, alt->group) |= alt_mask; + } else { + NPCM_DEVALT(scfg_base, alt->group) &= ~alt_mask; + } +} + +/* Pin-control driver registration */ +static int npcm_scfg_init(void) +{ + /* Change all pads whose default functionality isn't IO to GPIO */ + for (int i = 0; i < ARRAY_SIZE(def_alts); i++) { + npcm_pinctrl_alt_sel(&def_alts[i], 0); + } + + return 0; +} + +SYS_INIT(npcm_scfg_init, PRE_KERNEL_1, CONFIG_KERNEL_INIT_PRIORITY_DEFAULT); diff --git a/soc/nuvoton/npcm/common/soc_clock.h b/soc/nuvoton/npcm/common/soc_clock.h new file mode 100644 index 00000000000000..85b7f85120faac --- /dev/null +++ b/soc/nuvoton/npcm/common/soc_clock.h @@ -0,0 +1,139 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_NPCM_SOC_CLOCK_H_ +#define _NUVOTON_NPCM_SOC_CLOCK_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +/* Common clock control device name for all NPCM series */ +#define NPCM_CLK_CTRL_NODE DT_NODELABEL(pcc) + +/** + * @brief NPCM clock configuration structure + * + * Used to indicate the device's clock bus type and corresponding PWDWN_CTL + * register/bit to turn on/off its source clock. + */ +struct npcm_clk_cfg { + uint16_t bus:8; + uint16_t ctrl:5; + uint16_t bit:3; +}; + +/* Clock settings from pcc node */ +/* Target OFMCLK freq */ +#define OFMCLK DT_PROP(DT_NODELABEL(pcc), clock_frequency) +/* Core clock prescaler */ +#define FPRED_VAL (DT_PROP(DT_NODELABEL(pcc), core_prescaler) - 1) +/* APB1 clock divider */ +#define APB1DIV_VAL (DT_PROP(DT_NODELABEL(pcc), apb1_prescaler) - 1) +/* APB2 clock divider */ +#define APB2DIV_VAL (DT_PROP(DT_NODELABEL(pcc), apb2_prescaler) - 1) +/* APB3 clock divider */ +#define APB3DIV_VAL (DT_PROP(DT_NODELABEL(pcc), apb3_prescaler) - 1) + +/* Core domain clock */ +#define CORE_CLK (OFMCLK / DT_PROP(DT_NODELABEL(pcc), core_prescaler)) +/* Low Frequency clock */ +#define LFCLK 32768 + +/* FMUL clock */ +#define FMCLK OFMCLK /* FMUL clock = OFMCLK */ + +/* APBs source clock */ +#define APBSRC_CLK OFMCLK + +/* AHB6 clock */ +#define AHB6DIV_VAL 0 /* AHB6_CLK = CORE_CLK */ +/* FIU clock divider */ +#define FIUDIV_VAL 0 /* FIU_CLK = CORE_CLK */ +/* Get APB clock freq */ +#define NPCM_APB_CLOCK(no) (APBSRC_CLK / (APB##no##DIV_VAL + 1)) + +/* + * Frequency multiplier M/N value definitions according to the requested + * OFMCLK (Unit:Hz). + */ +#if (OFMCLK > 50000000) +#define HFCGN_VAL 0x82 /* Set XF_RANGE as 1 if OFMCLK > 50MHz */ +#else +#define HFCGN_VAL 0x02 +#endif +#if (OFMCLK == 100000000) +#define HFCGMH_VAL 0x0B +#define HFCGML_VAL 0xEC +#elif (OFMCLK == 96000000) +#define HFCGMH_VAL 0x0B +#define HFCGML_VAL 0x72 +#elif (OFMCLK == 90000000) +#define HFCGMH_VAL 0x0A +#define HFCGML_VAL 0xBA +#elif (OFMCLK == 80000000) +#define HFCGMH_VAL 0x09 +#define HFCGML_VAL 0x89 +#elif (OFMCLK == 66000000) +#define HFCGMH_VAL 0x07 +#define HFCGML_VAL 0xDE +#elif (OFMCLK == 50000000) +#define HFCGMH_VAL 0x0B +#define HFCGML_VAL 0xEC +#elif (OFMCLK == 48000000) +#define HFCGMH_VAL 0x0B +#define HFCGML_VAL 0x72 +#elif (OFMCLK == 40000000) +#define HFCGMH_VAL 0x09 +#define HFCGML_VAL 0x89 +#elif (OFMCLK == 33000000) +#define HFCGMH_VAL 0x07 +#define HFCGML_VAL 0xDE +#else +#error "Unsupported OFMCLK Frequency" +#endif + +/** + * @brief Function to notify clock driver that backup the counter value of + * low-frequency timer before ec entered deep idle state. + */ +void npcm_clock_capture_low_freq_timer(void); + +/** + * @brief Function to notify clock driver that compensate the counter value of + * system timer by low-frequency timer after ec left deep idle state. + * + */ +void npcm_clock_compensate_system_timer(void); + +/** + * @brief Function to get time ticks in system sleep/deep sleep state. The unit + * is ticks. + * + */ +uint64_t npcm_clock_get_sleep_ticks(void); + +/** + * @brief Function to configure system sleep settings. After ec received "wfi" + * instruction, ec will enter sleep/deep sleep state for better power + * consumption. + * + * @param is_deep A boolean indicating ec enters deep sleep or sleep state + * @param is_instant A boolean indicating 'Instant Wake-up' from deep idle is + * enabled + */ +void npcm_clock_control_turn_on_system_sleep(bool is_deep, bool is_instant); + +/** + * @brief Function to turn off system sleep mode. + */ +void npcm_clock_control_turn_off_system_sleep(void); + +#ifdef __cplusplus +} +#endif + +#endif /* _NUVOTON_NPCM_SOC_CLOCK_H_ */ diff --git a/soc/nuvoton/npcm/common/soc_dt.h b/soc/nuvoton/npcm/common/soc_dt.h new file mode 100644 index 00000000000000..c426e4beefa64b --- /dev/null +++ b/soc/nuvoton/npcm/common/soc_dt.h @@ -0,0 +1,418 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_NPCM_SOC_DT_H_ +#define _NUVOTON_NPCM_SOC_DT_H_ + +#include +#include +#include + +/** + * @brief Like DT_PROP(), but expand parameters with + * DT_ENUM_UPPER_TOKEN not DT_PROP + * + * If the prop exists, this expands to DT_ENUM_UPPER_TOKEN(node_id, prop). + * The default_value parameter is not expanded in this case. + * + * Otherwise, this expands to default_value. + * + * @param node_id node identifier + * @param prop lowercase-and-underscores property name + * @param default_value a fallback value to expand to + * @return the property's enum upper token value or default_value + */ +#define NPCM_DT_PROP_ENUM_OR(node_id, prop, default_value) \ + COND_CODE_1(DT_NODE_HAS_PROP(node_id, prop), \ + (DT_STRING_UPPER_TOKEN(node_id, prop)), (default_value)) + +/** + * @brief Like DT_INST_PROP_OR(), but expand parameters with + * NPCM_DT_PROP_ENUM_OR not DT_PROP_OR + * @param inst instance number + * @param prop lowercase-and-underscores property name + * @param default_value a fallback value to expand to + * @return the property's enum upper token value or default_value + */ +#define NPCM_DT_INST_PROP_ENUM_OR(inst, prop, default_value) \ + NPCM_DT_PROP_ENUM_OR(DT_DRV_INST(inst), prop, default_value) + +/** + * @brief Construct a npcm_clk_cfg item from first item in 'clocks' prop which + * type is 'phandle-array' to handle "clock-cells" in current driver. + * + * Example devicetree fragment: + * / { + * uart1: serial@400c4000 { + * clocks = <&pcc NPCM_CLOCK_BUS_APB2 NPCM_PWDWN_CTL1 4>; + * ... + * }; + * }; + * + * Example usage: + * const struct npcm_clk_cfg clk_cfg = NPCM_DT_CLK_CFG_ITEM(inst); + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return npcm_clk_cfg item. + */ +#define NPCM_DT_CLK_CFG_ITEM(inst) \ + { \ + .bus = NPCM_DT_INST_PROP_ENUM_OR(inst, clock_bus, \ + DT_PHA(DT_DRV_INST(inst), clocks, bus)), \ + .ctrl = DT_PHA(DT_DRV_INST(inst), clocks, ctl), \ + .bit = DT_PHA(DT_DRV_INST(inst), clocks, bit), \ + } + +/** + * @brief Construct a npcm_clk_cfg structure from 'clocks' property at index 'i' + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param i index of clocks prop which type is 'phandle-array' + * @return npcm_clk_cfg item from 'clocks' property at index 'i' + */ +#define NPCM_DT_CLK_CFG_ITEM_BY_IDX(inst, i) \ + { \ + .bus = DT_CLOCKS_CELL_BY_IDX(DT_DRV_INST(inst), i, bus), \ + .ctrl = DT_CLOCKS_CELL_BY_IDX(DT_DRV_INST(inst), i, ctl), \ + .bit = DT_CLOCKS_CELL_BY_IDX(DT_DRV_INST(inst), i, bit), \ + } + +/** + * @brief Construct a npcm_clk_cfg structure from 'clocks' with the same clock 'name'. + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param name name of the clock + * @return npcm_clk_cfg item from 'clocks' property with the same clock 'name' + */ +#define NPCM_DT_CLK_CFG_ITEM_BY_NAME(inst, name) \ + { \ + .bus = DT_CLOCKS_CELL_BY_NAME(DT_DRV_INST(inst), name, bus), \ + .ctrl = DT_CLOCKS_CELL_BY_NAME(DT_DRV_INST(inst), name, ctl), \ + .bit = DT_CLOCKS_CELL_BY_NAME(DT_DRV_INST(inst), name, bit), \ + } + +/** + * @brief Length of 'clocks' property which type is 'phandle-array' + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return length of 'clocks' property which type is 'phandle-array' + */ +#define NPCM_DT_CLK_CFG_ITEMS_LEN(inst) DT_INST_PROP_LEN(inst, clocks) + +/** + * @brief Macro function to construct npcm_clk_cfg item in UTIL_LISTIFY + * extension. + * + * @param child child index in UTIL_LISTIFY extension. + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return macro function to construct a npcm_clk_cfg structure. + */ +#define NPCM_DT_CLK_CFG_ITEMS_FUNC(child, inst) \ + NPCM_DT_CLK_CFG_ITEM_BY_IDX(inst, child) + +/** + * @brief Macro function to construct a list of npcm_clk_cfg items by + * UTIL_LISTIFY func + * + * Example devicetree fragment: + * / { + * host_sub: lpc@400c1000 { + * clocks = <&pcc NPCM_CLOCK_BUS_APB3 NPCM_PWDWN_CTL5 3>, + * <&pcc NPCM_CLOCK_BUS_APB3 NPCM_PWDWN_CTL5 4>, + * <&pcc NPCM_CLOCK_BUS_APB3 NPCM_PWDWN_CTL5 5>, + * <&pcc NPCM_CLOCK_BUS_APB3 NPCM_PWDWN_CTL5 6>, + * <&pcc NPCM_CLOCK_BUS_APB3 NPCM_PWDWN_CTL5 7>; + * ... + * }; + * Example usage: + * const struct npcm_clk_cfg clk_cfg[] = NPCM_DT_CLK_CFG_ITEMS_LIST(0); + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return an array of npcm_clk_cfg items. + */ +#define NPCM_DT_CLK_CFG_ITEMS_LIST(inst) { \ + LISTIFY(NPCM_DT_CLK_CFG_ITEMS_LEN(inst), \ + NPCM_DT_CLK_CFG_ITEMS_FUNC, (,), \ + inst) \ + } + +/** + * @brief Get phandle from "name" property which contains wui information. + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param name property 'name' which type is 'phandle' and contains wui info. + * @return phandle from 'name' property. + */ +#define NPCM_DT_PHANDLE_FROM_WUI_NAME(inst, name) \ + DT_INST_PHANDLE(inst, name) + +/** + * @brief Construct a npcm_wui structure from 'name' property + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param name property 'name'which type is 'phandle' and contains wui info. + * @return npcm_wui item from 'name' property. + */ +#define NPCM_DT_WUI_ITEM_BY_NAME(inst, name) \ + { \ + .table = DT_PROP(DT_PHANDLE(NPCM_DT_PHANDLE_FROM_WUI_NAME(inst, \ + name), miwus), index), \ + .group = DT_PHA(NPCM_DT_PHANDLE_FROM_WUI_NAME(inst, name), miwus, \ + group), \ + .bit = DT_PHA(NPCM_DT_PHANDLE_FROM_WUI_NAME(inst, name), miwus, \ + bit), \ + } + +/** + * @brief Get phandle from 'wui-maps' prop which type is 'phandles' at index 'i' + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param i index of 'wui-maps' prop which type is 'phandles' + * @return phandle from 'wui-maps' prop at index 'i' + */ +#define NPCM_DT_PHANDLE_FROM_WUI_MAPS(inst, i) \ + DT_INST_PHANDLE_BY_IDX(inst, wui_maps, i) + +/** + * @brief Construct a npcm_wui structure from wui-maps property at index 'i' + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @param i index of 'wui-maps' prop which type is 'phandles' + * @return npcm_wui item at index 'i' + */ +#define NPCM_DT_WUI_ITEM_BY_IDX(inst, i) \ + { \ + .table = DT_PROP(DT_PHANDLE(NPCM_DT_PHANDLE_FROM_WUI_MAPS(inst, i), \ + miwus), index), \ + .group = DT_PHA(NPCM_DT_PHANDLE_FROM_WUI_MAPS(inst, i), miwus, \ + group), \ + .bit = DT_PHA(NPCM_DT_PHANDLE_FROM_WUI_MAPS(inst, i), miwus, bit), \ + } + +/** + * @brief Length of npcm_wui structures in 'wui-maps' property + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return length of 'wui-maps' prop which type is 'phandles' + */ +#define NPCM_DT_WUI_ITEMS_LEN(inst) DT_INST_PROP_LEN(inst, wui_maps) + +/** + * @brief Macro function to construct a list of npcm_wui items by UTIL_LISTIFY + * + * @param child child index in UTIL_LISTIFY extension. + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return macro function to construct a npcm_wui structure. + */ +#define NPCM_DT_WUI_ITEMS_FUNC(child, inst) NPCM_DT_WUI_ITEM_BY_IDX(inst, child) + +/** + * @brief Macro function to construct a list of npcm_wui items by UTIL_LISTIFY + * func. + * + * Example devicetree fragment: + * / { + * uart1: serial@400c4000 { + * uart-rx = <&wui_cr_sin1>; + * ... + * }; + * + * gpio0: gpio@40081000 { + * wui-maps = <&wui_io00 &wui_io01 &wui_io02 &wui_io03 + * &wui_io04 &wui_io05 &wui_io06 &wui_io07>; + * ... + * }; + * }; + * + * Example usage: + * const struct npcm_wui wui_map = NPCM_DT_PHANDLE_FROM_WUI_NAME(inst, uart_rx); + * const struct npcm_wui wui_maps[] = NPCM_DT_WUI_ITEMS_LIST(inst); + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return an array of npcm_wui items. + */ +#define NPCM_DT_WUI_ITEMS_LIST(inst) { \ + LISTIFY(NPCM_DT_WUI_ITEMS_LEN(inst), \ + NPCM_DT_WUI_ITEMS_FUNC, (,), \ + inst) \ + } + +/** + * @brief Get a node from path '/npcm_miwus_map/map_miwu(0/1/2)_groups' + * + * @param i index of npcm miwu devices + * @return node identifier with that path. + */ +#define NPCM_DT_NODE_FROM_MIWU_MAP(i) DT_PATH(npcm_miwus_int_map, \ + map_miwu##i##_groups) +/** + * @brief Get the index prop from parent MIWU device node. + * + * @param child index in UTIL_LISTIFY extension. + * @return 'index' prop value of the node which compatible type is + * "nuvoton,npcm-miwu". + */ +#define NPCM_DT_MIWU_IRQ_TABLE_IDX(child) \ + DT_PROP(DT_PHANDLE(DT_PARENT(child), parent), index) + +/** + * @brief Macro function for DT_FOREACH_CHILD to generate a IRQ_CONNECT + * implementation. + * + * @param child index in UTIL_LISTIFY extension. + * @return implementation to initialize interrupts of MIWU groups and enable + * them. + */ +#define NPCM_DT_MIWU_IRQ_CONNECT_IMPL_CHILD_FUNC(child) \ + NPCM_DT_MIWU_IRQ_CONNECT_IMPL_CHILD_FUNC_OBJ(child); + +#define NPCM_DT_MIWU_IRQ_CONNECT_IMPL_CHILD_FUNC_OBJ(child) \ + do { \ + IRQ_CONNECT(DT_PROP(child, irq), \ + DT_PROP(child, irq_prio), \ + NPCM_MIWU_ISR_FUNC(NPCM_DT_MIWU_IRQ_TABLE_IDX(child)), \ + DT_PROP(child, group_mask), \ + 0); \ + irq_enable(DT_PROP(child, irq)); \ + } while (false) + +/** + * @brief Get a child node from path '/npcm-espi-vws-map/name'. + * + * @param name a path which name is /npcm-espi-vws-map/'name'. + * @return child node identifier with that path. + */ +#define NPCM_DT_NODE_FROM_VWTABLE(name) DT_CHILD(DT_PATH(npcm_espi_vws_map), \ + name) + +/** + * @brief Get phandle from vw-wui property of child node with that path. + * + * @param name path which name is /npcm-espi-vws-map/'name'. + * @return phandle from "vw-wui" prop of child node with that path. + */ +#define NPCM_DT_PHANDLE_VW_WUI(name) DT_PHANDLE(NPCM_DT_NODE_FROM_VWTABLE( \ + name), vw_wui) + +/** + * @brief Construct a npcm_wui structure from vw-wui property of a child node + * with that path. + * + * @param name a path which name is /npcm-espi-vws-map/'name'. + * @return npcm_wui item with that path. + */ +#define NPCM_DT_VW_WUI_ITEM(name) \ + { \ + .table = DT_PROP(DT_PHANDLE(NPCM_DT_PHANDLE_VW_WUI(name), miwus), \ + index),\ + .group = DT_PHA(NPCM_DT_PHANDLE_VW_WUI(name), miwus, group), \ + .bit = DT_PHA(NPCM_DT_PHANDLE_VW_WUI(name), miwus, bit), \ + } + +/** + * @brief Construct a npcm espi device configuration of vw input signal from + * a child node with that path. + * + * @signal vw input signal name. + * @param name a path which name is /npcm-espi-vws-map/'name'. + * @return npcm_vw_in_config item with that path. + */ +#define NPCM_DT_VW_IN_CONF(signal, name) \ + { \ + .sig = signal, \ + .reg_idx = DT_PROP_BY_IDX(NPCM_DT_NODE_FROM_VWTABLE(name), vw_reg, \ + 0), \ + .bitmask = DT_PROP_BY_IDX(NPCM_DT_NODE_FROM_VWTABLE(name), vw_reg, \ + 1), \ + .vw_wui = NPCM_DT_VW_WUI_ITEM(name), \ + } + +/** + * @brief Construct a npcm espi device configuration of vw output signal from + * a child node with that path. + * + * @signal vw output signal name. + * @param name a path which name is /npcm-espi-vws-map/'name'. + * @return npcm_vw_in_config item with that path. + */ +#define NPCM_DT_VW_OUT_CONF(signal, name) \ + { \ + .sig = signal, \ + .reg_idx = DT_PROP_BY_IDX(NPCM_DT_NODE_FROM_VWTABLE(name), vw_reg, \ + 0), \ + .bitmask = DT_PROP_BY_IDX(NPCM_DT_NODE_FROM_VWTABLE(name), vw_reg, \ + 1), \ + } + +/** + * @brief Construct a npcm_lvol structure from 'lvol-maps' property at index 'i'. + * + * @param node_id Node identifier. + * @param prop Low voltage configurations property name. (i.e. 'lvol-maps') + * @param idx Property entry index. + */ +#define NPCM_DT_LVOL_CTRL_NONE \ + DT_PHA(DT_NODELABEL(lvol_none), lvols, ctrl) + +/** + * @brief Length of npcm_lvol structures in 'lvol-maps' property + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return length of 'lvol-maps' prop which type is 'phandles' + */ +#define NPCM_DT_LVOL_ITEMS_LEN(inst) DT_INST_PROP_LEN(inst, lvol_maps) + +/** + * @brief Construct a npcm_lvol structure from 'lvol-maps' property at index 'i'. + * + * @param node_id Node identifier. + * @param prop Low voltage configurations property name. (i.e. 'lvol-maps') + * @param idx Property entry index. + */ +#define NPCM_DT_LVOL_ITEMS_INIT(node_id, prop, idx) \ + { \ + .ctrl = DT_PHA(DT_PROP_BY_IDX(node_id, prop, idx), lvols, ctrl), \ + .bit = DT_PHA(DT_PROP_BY_IDX(node_id, prop, idx), lvols, bit), \ + }, + +/** + * @brief Macro function to construct a list of npcm_lvol items from 'lvol-maps' + * property. + * + * @param inst instance number for compatible defined in DT_DRV_COMPAT. + * @return an array of npcm_lvol items. + */ +#define NPCM_DT_LVOL_ITEMS_LIST(inst) { \ + DT_FOREACH_PROP_ELEM(DT_DRV_INST(inst), lvol_maps, \ + NPCM_DT_LVOL_ITEMS_INIT)} + +/** + * @brief Check if the host interface type is automatically configured by + * booter. + * + * @return TRUE - if the host interface is configured by booter, + * FALSE - otherwise. + */ +#define NPCM_BOOTER_IS_HIF_TYPE_SET() \ + DT_PROP(DT_PATH(booter_variant), hif_type_auto) + +/** + * @brief Helper macro to get address of system configuration module which is + * used by serval peripheral device drivers in npcm series. + * + * @return base address of system configuration module. + */ +#define NPCM_SCFG_REG_ADDR DT_REG_ADDR_BY_NAME(DT_NODELABEL(scfg), scfg) + +/** + * @brief Helper macro to get address of system glue module which is + * used by serval peripheral device drivers in npcm series. + * + * @return base address of system glue module. + */ +#define NPCM_GLUE_REG_ADDR DT_REG_ADDR_BY_NAME(DT_NODELABEL(scfg), glue) + +#endif /* _NUVOTON_NPCM_SOC_DT_H_ */ diff --git a/soc/nuvoton/npcm/common/soc_gpio.h b/soc/nuvoton/npcm/common/soc_gpio.h new file mode 100644 index 00000000000000..7d83ce0a2e6377 --- /dev/null +++ b/soc/nuvoton/npcm/common/soc_gpio.h @@ -0,0 +1,49 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_NPCM_SOC_GPIO_H_ +#define _NUVOTON_NPCM_SOC_GPIO_H_ + +#include + +#ifdef __cplusplus +extern "C" { +#endif + +/* Pin number for each GPIO device */ +#define NPCM_GPIO_PORT_PIN_NUM 8U + +/** + * @brief Get GPIO device instance by port index + * + * @param port GPIO device index + * + * @retval Pointer to structure device + * @retval NULL Invalid parameter of GPIO port index + */ +const struct device *npcm_get_gpio_dev(int port); + +/** + * @brief Enable the connection between io pads and GPIO instance + * + * @param dev Pointer to device structure for the gpio driver instance. + * @param pin Pin number. + */ +void npcm_gpio_enable_io_pads(const struct device *dev, int pin); + +/** + * @brief Disable the connection between io pads and GPIO instance + * + * @param dev Pointer to device structure for the gpio driver instance. + * @param pin Pin number. + */ +void npcm_gpio_disable_io_pads(const struct device *dev, int pin); + +#ifdef __cplusplus +} +#endif + +#endif /* _NUVOTON_NPCM_SOC_GPIO_H_ */ diff --git a/soc/nuvoton/npcm/common/soc_miwu.h b/soc/nuvoton/npcm/common/soc_miwu.h new file mode 100644 index 00000000000000..620f957de14b88 --- /dev/null +++ b/soc/nuvoton/npcm/common/soc_miwu.h @@ -0,0 +1,232 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_NPCM_SOC_MIWU_H_ +#define _NUVOTON_NPCM_SOC_MIWU_H_ + +#include + +#include +#include + +#ifdef __cplusplus +extern "C" { +#endif + +enum miwu_table { + NPCM_MIWU_TABLE_0, + NPCM_MIWU_TABLE_1, + NPCM_MIWU_TABLE_2, + NPCM_MIWU_TABLE_COUNT +}; + +enum miwu_group { + NPCM_MIWU_GROUP_1, + NPCM_MIWU_GROUP_2, + NPCM_MIWU_GROUP_3, + NPCM_MIWU_GROUP_4, + NPCM_MIWU_GROUP_5, + NPCM_MIWU_GROUP_6, + NPCM_MIWU_GROUP_7, + NPCM_MIWU_GROUP_8, + NPCM_MIWU_GROUP_COUNT +}; + +#define NPCM_MIWU_TABLE_NONE NPCM_MIWU_TABLE_COUNT + +/* Interrupt modes supported by npcm miwu modules */ +enum miwu_int_mode { + NPCM_MIWU_MODE_LEVEL, + NPCM_MIWU_MODE_EDGE, +}; + +/* Interrupt trigger modes supported by npcm miwu modules */ +enum miwu_int_trig { + NPCM_MIWU_TRIG_LOW, /** Edge failing or active low detection */ + NPCM_MIWU_TRIG_HIGH, /** Edge rising or active high detection */ + NPCM_MIWU_TRIG_BOTH, /** Both edge rising and failing detection */ +}; + +/** + * @brief NPCM wake-up input source structure + * + * Used to indicate a Wake-Up Input source (WUI) belongs to which group and bit + * of Multi-Input Wake-Up Unit (MIWU) modules. + */ +struct npcm_wui { + uint8_t table : 2; /** A source belongs to which MIWU table. */ + uint8_t group : 3; /** A source belongs to which group of MIWU table. */ + uint8_t bit : 3; /** A source belongs to which bit of MIWU group. */ +}; + +/** + * Define npcm miwu driver callback handler signature for wake-up input source + * of generic hardware. Its parameters contain the device issued interrupt + * and corresponding WUI source. + */ +typedef void (*miwu_dev_callback_handler_t)(const struct device *source, + struct npcm_wui *wui); + +/** + * @brief MIWU/GPIO information structure + * + * It contains both GPIO and MIWU information which is stored in unused field + * of struct gpio_port_pins_t since a interested mask of pins is only 8 bits. + * Beware the size of such structure must equal struct gpio_port_pins_t. + */ +struct miwu_io_params { + uint8_t pin_mask; /** A mask of pins the callback is interested in. */ + uint8_t reserved; + uint8_t gpio_port; /** GPIO device index */ + struct npcm_wui wui; /** Wake-up input source of GPIO */ +}; + +/** + * @brief MIWU callback structure for a GPIO input + * + * Used to register a GPIO callback in the driver instance callback list. + * Beware such structure should not be allocated on stack and its size must + * equal struct gpio_callback. + * + * Note: To help setting it, see npcx_miwu_init_gpio_callback() below + */ +struct miwu_io_callback { + /** Node of single-linked list */ + sys_snode_t node; + /** Callback function being called when GPIO event occurred */ + gpio_callback_handler_t handler; + /** GPIO callback parameters used in MIWU ISR */ + struct miwu_io_params params; +}; + +/** + * @brief MIWU callback structure for a device input + * + * Used to register a generic hardware device callback in the driver instance + * callback list. Beware such structure should not be allocated on stack. + * + * Note: To help setting it, see npcm_miwu_init_dev_callback() below + */ +struct miwu_dev_callback { + /** Node of single-linked list */ + sys_snode_t node; + /** Callback function being called when device event occurred */ + miwu_dev_callback_handler_t handler; + /** Device instance register callback function */ + const struct device *source; + /* Wake-up input source */ + struct npcm_wui wui; +}; + +/** + * @brief Enable interrupt of the wake-up input source + * + * @param A pointer on wake-up input source + */ +void npcm_miwu_irq_enable(const struct npcm_wui *wui); + +/** + * @brief Disable interrupt of the wake-up input source + * + * @param wui A pointer on wake-up input source + */ +void npcm_miwu_irq_disable(const struct npcm_wui *wui); + +/** + * @brief Connect io to the wake-up input source + * + * @param wui A pointer on wake-up input source + */ +void npcm_miwu_io_enable(const struct npcm_wui *wui); + +/** + * @brief Disconnect io to the wake-up input source + * + * @param wui A pointer on wake-up input source + */ +void npcm_miwu_io_disable(const struct npcm_wui *wui); + +/** + * @brief Get interrupt state of the wake-up input source + * + * @param wui A pointer on wake-up input source + * + * @retval 0 if interrupt is disabled, otherwise interrupt is enabled + */ +bool npcm_miwu_irq_get_state(const struct npcm_wui *wui); + +/** + * @brief Get & clear interrupt pending bit of the wake-up input source + * + * @param wui A pointer on wake-up input source + * + * @retval 1 if interrupt is pending + */ +bool npcm_miwu_irq_get_and_clear_pending(const struct npcm_wui *wui); + +/** + * @brief Configure interrupt type of the wake-up input source + * + * @param wui Pointer to wake-up input source for configuring + * @param mode Interrupt mode supported by NPCM MIWU + * @param trig Interrupt trigger mode supported by NPCM MIWU + * + * @retval 0 If successful + * @retval -EINVAL Invalid parameters + */ +int npcm_miwu_interrupt_configure(const struct npcm_wui *wui, + enum miwu_int_mode mode, enum miwu_int_trig trig); + +/** + * @brief Function to initialize a struct miwu_io_callback properly + * + * @param callback Pointer to io callback structure for initialization + * @param io_wui Pointer to wake-up input IO source + * @param port GPIO port issued a callback function + */ +void npcm_miwu_init_gpio_callback(struct miwu_io_callback *callback, + const struct npcm_wui *io_wui, int port); + +/** + * @brief Function to initialize a struct miwu_dev_callback properly + * + * @param callback Pointer to device callback structure for initialization + * @param dev_wui Pointer to wake-up input device source + * @param handler A function called when its device input event issued + * @param source Pointer to device instance issued a callback function + */ +void npcm_miwu_init_dev_callback(struct miwu_dev_callback *callback, + const struct npcm_wui *dev_wui, + miwu_dev_callback_handler_t handler, + const struct device *source); + +/** + * @brief Function to insert or remove a IO callback from a callback list + * + * @param callback Pointer to io callback structure + * @param set A boolean indicating insertion or removal of the callback + * + * @retval 0 If successful. + * @retval -EINVAL Invalid parameters + */ +int npcm_miwu_manage_gpio_callback(struct miwu_io_callback *callback, bool set); + + +/** + * @brief Function to insert or remove a device callback from a callback list + * + * @param callback Pointer to device callback structure + * @param set A boolean indicating insertion or removal of the callback + * + * @retval 0 If successful. + * @retval -EINVAL Invalid parameters + */ +int npcm_miwu_manage_dev_callback(struct miwu_dev_callback *cb, bool set); + +#ifdef __cplusplus +} +#endif +#endif /* _NUVOTON_NPCM_SOC_MIWU_H_ */ diff --git a/soc/nuvoton/npcm/common/soc_pins.h b/soc/nuvoton/npcm/common/soc_pins.h new file mode 100644 index 00000000000000..13bd062ffe10fb --- /dev/null +++ b/soc/nuvoton/npcm/common/soc_pins.h @@ -0,0 +1,35 @@ +/* + * Copyright (c) 2024 Nuvoton Technology Corporation. + * + * SPDX-License-Identifier: Apache-2.0 + */ + +#ifndef _NUVOTON_NPCM_SOC_PINS_H_ +#define _NUVOTON_NPCM_SOC_PINS_H_ + +#include + +#include "reg/reg_def.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/** + * @brief NPCM pin-mux configuration structure + * + * Used to indicate the device's corresponding DEVALT register/bit for + * pin-muxing and its polarity to enable alternative functionality. + */ +struct npcm_alt { + uint8_t group; + uint8_t bit:3; + uint8_t inverted:1; + uint8_t reserved:4; +}; + +#ifdef __cplusplus +} +#endif + +#endif /* _NUVOTON_NPCM_SOC_PINS_H_ */ diff --git a/soc/nuvoton/npcm/npcm4/Kconfig b/soc/nuvoton/npcm/npcm4/Kconfig index 6042048cebfaf5..5cdb452dbd830e 100644 --- a/soc/nuvoton/npcm/npcm4/Kconfig +++ b/soc/nuvoton/npcm/npcm4/Kconfig @@ -10,6 +10,5 @@ config SOC_SERIES_NPCM4 select SOC_FAMILY_NPCM select CORTEX_M_SYSTICK select CPU_HAS_ARM_MPU - select CPU_HAS_CUSTOM_FIXED_SOC_MPU_REGIONS help Enable support for Nuvoton NPCM4 series diff --git a/soc/nuvoton/npcm/npcm4/soc.h b/soc/nuvoton/npcm/npcm4/soc.h index 6449769087e13e..ce557126e35357 100644 --- a/soc/nuvoton/npcm/npcm4/soc.h +++ b/soc/nuvoton/npcm/npcm4/soc.h @@ -15,4 +15,12 @@ #include #include +#include +#include +#include +#include +#include + +#define NPCM_PUPD_EN_OFFSET(n) (0x028 + n) + #endif /* _NUVOTON_NPCM_SOC_H_ */