drivers: eSPI: add eSPI driver support for NPCX7 series.

In npcx7 series, all of them support the Intel Enhanced Serial
Peripheral Interface (eSPI) Revision 1.0. This specification provides a
path for migrating host sub-devices via LPC to a lower pin count, higher
bandwidth bus. In addition to Host communication via the peripheral
channel, it provides virtual wires support, out-of-band communication,
and device mastering option over the Chipset SPI flash.

Becisdes introducing eSPI device in npcx7, this CL also includes:

1. Add eSPI device tree declarations.
2. Add npcx7-espi-vws-map.dtsi to present the relationship between eSPI
   Virtual-Wire signals, eSPI registers, and wake-up input sources.
3. Zephyr eSPI api implementation.
4, Add OOB (Out of Band tunneled SMBus) support.
5. Add configuration files for eSPI test suites.

Signed-off-by: Mulin Chao <MLChao@nuvoton.com>
This commit is contained in:
Mulin Chao 2020-09-10 17:39:44 +08:00 committed by Carles Cufí
parent e12d1ae851
commit be217e4a3a
18 changed files with 1373 additions and 0 deletions

View file

@ -181,6 +181,7 @@
/drivers/entropy/*gecko* @chrta
/drivers/entropy/*litex* @mateusz-holenko @kgugala @pgielda
/drivers/espi/ @albertofloyd @franciscomunoz @scottwcpg
/drivers/espi/*npcx* @MulinChao
/drivers/ethernet/ @jukkar @tbursztyka @pfalcon
/drivers/ethernet/*stm32* @Nukersson @lochej
/drivers/flash/ @nashif @nvlsianpu

View file

@ -24,3 +24,7 @@
current-speed = <115200>;
pinctrl = <&altc_uart1_sl2>; /* Use UART1_SL2 ie. PIN64.65 */
};
&espi0 {
status = "okay";
};

View file

@ -34,6 +34,9 @@ CONFIG_UART_INTERRUPT_DRIVEN=y
# GPIO Driver
CONFIG_GPIO=y
# ESPI Driver
CONFIG_ESPI=y
# Console Driver
CONFIG_CONSOLE=y
CONFIG_UART_CONSOLE=y

View file

@ -3,4 +3,5 @@
zephyr_library()
zephyr_library_sources_ifdef(CONFIG_ESPI_XEC espi_mchp_xec.c)
zephyr_library_sources_ifdef(CONFIG_ESPI_NPCX espi_npcx.c)
zephyr_library_sources_ifdef(CONFIG_USERSPACE espi_handlers.c)

View file

@ -12,6 +12,8 @@ if ESPI
source "drivers/espi/Kconfig.xec"
source "drivers/espi/Kconfig.npcx"
module = ESPI
module-str = espi
source "subsys/logging/Kconfig.template.log_config"

31
drivers/espi/Kconfig.npcx Normal file
View file

@ -0,0 +1,31 @@
# NPCX eSPI driver configuration options
# Copyright (c) 2020 Nuvoton Technology Corporation.
# SPDX-License-Identifier: Apache-2.0
config ESPI_NPCX
bool "Nuvoton NPCX embedd controller (EC) ESPI driver"
depends on SOC_FAMILY_NPCX
help
This option enables the Intel Enhanced Serial Peripheral Interface
(eSPI) for NPCX family of processors.
# The default value 'y' for the existing options if ESPI_NPCX is selected.
if ESPI_NPCX
config ESPI_OOB_CHANNEL
default y
config ESPI_PERIPHERAL_8042_KBC
default y
config ESPI_PERIPHERAL_HOST_IO
default y
config ESPI_PERIPHERAL_DEBUG_PORT_80
default y
config ESPI_PERIPHERAL_UART
default y
endif #ESPI_NPCX

866
drivers/espi/espi_npcx.c Normal file
View file

@ -0,0 +1,866 @@
/*
* Copyright (c) 2020 Nuvoton Technology Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT nuvoton_npcx_espi
#include <assert.h>
#include <drivers/espi.h>
#include <drivers/gpio.h>
#include <drivers/clock_control.h>
#include <dt-bindings/espi/npcx_espi.h>
#include <kernel.h>
#include <soc.h>
#include "espi_utils.h"
#include "soc_miwu.h"
#include <logging/log.h>
LOG_MODULE_REGISTER(espi, CONFIG_ESPI_LOG_LEVEL);
struct espi_npcx_config {
uintptr_t base;
/* clock configuration */
struct npcx_clk_cfg clk_cfg;
/* mapping table between eSPI reset signal and wake-up input */
struct npcx_wui espi_rst_wui;
/* pinmux configuration */
const uint8_t alts_size;
const struct npcx_alt *alts_list;
};
struct espi_npcx_data {
sys_slist_t callbacks;
uint8_t plt_rst_asserted;
uint8_t espi_rst_asserted;
uint8_t sx_state;
#if defined(CONFIG_ESPI_OOB_CHANNEL)
struct k_sem oob_rx_lock;
#endif
};
/* Driver convenience defines */
#define DRV_CONFIG(dev) ((const struct espi_npcx_config *)(dev)->config)
#define DRV_DATA(dev) ((struct espi_npcx_data *)(dev)->data)
#define HAL_INSTANCE(dev) (struct espi_reg *)(DRV_CONFIG(dev)->base)
/* eSPI channels */
#define NPCX_ESPI_CH_PC 0
#define NPCX_ESPI_CH_VW 1
#define NPCX_ESPI_CH_OOB 2
#define NPCX_ESPI_CH_FLASH 3
#define NPCX_ESPI_CH_COUNT 4
#define NPCX_ESPI_HOST_CH_EN(ch) (ch + 4)
/* eSPI max supported frequency */
#define NPCX_ESPI_MAXFREQ_20 0
#define NPCX_ESPI_MAXFREQ_25 1
#define NPCX_ESPI_MAXFREQ_33 2
#define NPCX_ESPI_MAXFREQ_50 3
/* Minimum delay before acknowledging a virtual wire */
#define NPCX_ESPI_VWIRE_ACK_DELAY 10ul /* 10 us */
/* OOB channel maximum payload size */
#define NPCX_ESPI_OOB_MAX_PAYLOAD 64
#define NPCX_OOB_RX_PACKAGE_LEN(hdr) (((hdr & 0xff000000) >> 24) | \
((hdr & 0xf0000) >> 8))
/* eSPI cycle type field for OOB and FLASH channels */
#define ESPI_FLASH_READ_CYCLE_TYPE 0x00
#define ESPI_FLASH_WRITE_CYCLE_TYPE 0x01
#define ESPI_FLASH_ERASE_CYCLE_TYPE 0x02
#define ESPI_OOB_GET_CYCLE_TYPE 0x21
#define ESPI_OOB_TAG 0x00
#define ESPI_OOB_MAX_TIMEOUT 500ul /* 500 ms */
/* eSPI bus interrupt configuration structure and macro function */
struct espi_bus_isr {
uint8_t status_bit; /* bit order in ESPISTS register */
uint8_t int_en_bit; /* bit order in ESPIIE register */
uint8_t wake_en_bit; /* bit order in ESPIWE register */
void (*bus_isr)(const struct device *dev); /* eSPI bus ISR */
};
#define NPCX_ESPI_BUS_INT_ITEM(event, isr) { \
.status_bit = NPCX_ESPISTS_##event, \
.int_en_bit = NPCX_ESPIIE_##event##IE, \
.wake_en_bit = NPCX_ESPIWE_##event##WE, \
.bus_isr = isr }
/* eSPI Virtual Wire Input (Master-to-Slave) signals configuration structure */
struct npcx_vw_in_config {
enum espi_vwire_signal sig; /* Virtual Wire signal */
uint8_t reg_idx; /* register index for VW signal */
uint8_t bitmask; /* VW signal bits-mask */
struct npcx_wui vw_wui; /* WUI mapping in MIWU modules for VW signal */
};
/* eSPI Virtual Wire Output (Slave-to-Master) signals configuration structure */
struct npcx_vw_out_config {
enum espi_vwire_signal sig; /* Virtual Wire signal */
uint8_t reg_idx; /* register index for VW signal */
uint8_t bitmask; /* VW signal bits-mask */
};
/*
* eSPI VW input/Output signal configuration tables. Please refer
* npcx7-espi-vws-map.dtsi device tree file for more detail.
*/
static const struct npcx_vw_in_config vw_in_tbl[] = {
/* index 02h (In) */
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_S3, vw_slp_s3),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_S4, vw_slp_s4),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_S5, vw_slp_s5),
/* index 03h (In) */
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SUS_STAT, vw_sus_stat),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_PLTRST, vw_plt_rst),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_OOB_RST_WARN, vw_oob_rst_warn),
/* index 07h (In) */
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_HOST_RST_WARN, vw_host_rst_warn),
/* index 41h (In) */
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SUS_WARN, vw_sus_warn),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SUS_PWRDN_ACK, vw_sus_pwrdn_ack),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_A, vw_slp_a),
/* index 42h (In) */
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_LAN, vw_slp_lan),
DT_NPCX_VW_IN_CONF(ESPI_VWIRE_SIGNAL_SLP_WLAN, vw_slp_wlan),
};
static const struct npcx_vw_out_config vw_out_tbl[] = {
/* index 04h (Out) */
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_OOB_RST_ACK, vw_oob_rst_ack),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_WAKE, vw_wake),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_PME, vw_pme),
/* index 05h (Out) */
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_SLV_BOOT_DONE, vw_slv_boot_done),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_ERR_FATAL, vw_err_fatal),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_ERR_NON_FATAL, vw_err_non_fatal),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_SLV_BOOT_STS,
vw_slv_boot_sts_with_done),
/* index 06h (Out) */
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_SCI, vw_sci),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_SMI, vw_smi),
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_HOST_RST_ACK, vw_host_rst_ack),
/* index 40h (Out) */
DT_NPCX_VW_OUT_CONF(ESPI_VWIRE_SIGNAL_SUS_ACK, vw_sus_ack),
};
/* Callbacks for eSPI bus reset and Virtual Wire signals. */
static struct miwu_dev_callback espi_rst_callback;
static struct miwu_dev_callback vw_in_callback[ARRAY_SIZE(vw_in_tbl)];
/* eSPI VW service function forward declarations */
static int espi_npcx_receive_vwire(const struct device *dev,
enum espi_vwire_signal signal, uint8_t *level);
static int espi_npcx_send_vwire(const struct device *dev,
enum espi_vwire_signal signal, uint8_t level);
static void espi_vw_send_bootload_done(const struct device *dev);
/* eSPI local initialization functions */
static void espi_init_wui_callback(const struct device *dev,
struct miwu_dev_callback *callback, const struct npcx_wui *wui,
miwu_dev_callback_handler_t handler)
{
/* VW signal which has no wake-up input source */
if (wui->table == NPCX_MIWU_TABLE_NONE)
return;
/* Install callback function */
soc_miwu_init_dev_callback(callback, wui, handler, dev);
soc_miwu_manage_dev_callback(callback, 1);
/* Congiure MIWU setting and enable its interrupt */
soc_miwu_interrupt_configure(wui, NPCX_MIWU_MODE_EDGE,
NPCX_MIWU_TRIG_BOTH);
soc_miwu_irq_enable(wui);
}
/* eSPI local bus interrupt service functions */
static void espi_bus_err_isr(const struct device *dev)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
uint32_t err = inst->ESPIERR;
LOG_ERR("eSPI Bus Error %08X", err);
/* Clear error status bits */
inst->ESPIERR = err;
}
static void espi_bus_inband_rst_isr(const struct device *dev)
{
ARG_UNUSED(dev);
LOG_DBG("%s issued", __func__);
}
static void espi_bus_reset_isr(const struct device *dev)
{
ARG_UNUSED(dev);
LOG_DBG("%s issued", __func__);
/* Do nothing! This signal is handled in ESPI_RST VW signal ISR */
}
static void espi_bus_cfg_update_isr(const struct device *dev)
{
int chan;
struct espi_reg *const inst = HAL_INSTANCE(dev);
struct espi_npcx_data *const data = DRV_DATA(dev);
struct espi_event evt = { .evt_type = ESPI_BUS_EVENT_CHANNEL_READY,
.evt_details = 0,
.evt_data = 0 };
/* If host enable bits are not sync with ready bits on slave side. */
uint8_t chg_mask = GET_FIELD(inst->ESPICFG, NPCX_ESPICFG_HCHANS_FIELD)
^ GET_FIELD(inst->ESPICFG, NPCX_ESPICFG_CHANS_FIELD);
chg_mask &= (ESPI_CHANNEL_VWIRE | ESPI_CHANNEL_OOB |
ESPI_CHANNEL_FLASH);
LOG_DBG("ESPI CFG Change Updated! 0x%02X", chg_mask);
/*
* If host enable/disable channel for VW/OOB/FLASH, EC should follow
* except Peripheral channel. It is handled after receiving PLTRST
* event separately.
*/
for (chan = NPCX_ESPI_CH_VW; chan < NPCX_ESPI_CH_COUNT; chan++) {
/* Channel ready bit isn't sync with enabled bit on host side */
if (chg_mask & BIT(chan)) {
evt.evt_data = IS_BIT_SET(inst->ESPICFG,
NPCX_ESPI_HOST_CH_EN(chan));
evt.evt_details = BIT(chan);
if (evt.evt_data)
inst->ESPICFG |= BIT(chan);
else
inst->ESPICFG &= ~BIT(chan);
espi_send_callbacks(&data->callbacks, dev, evt);
}
}
LOG_DBG("ESPI CFG EC Updated! 0x%02X", GET_FIELD(inst->ESPICFG,
NPCX_ESPICFG_CHANS_FIELD));
/* If VW channel is enabled and ready, send bootload done VW signal */
if ((chg_mask & BIT(NPCX_ESPI_CH_VW)) && IS_BIT_SET(inst->ESPICFG,
NPCX_ESPI_HOST_CH_EN(NPCX_ESPI_CH_VW))) {
espi_vw_send_bootload_done(dev);
}
}
#if defined(CONFIG_ESPI_OOB_CHANNEL)
static void espi_bus_oob_rx_isr(const struct device *dev)
{
struct espi_npcx_data *const data = DRV_DATA(dev);
LOG_DBG("%s", __func__);
k_sem_give(&data->oob_rx_lock);
}
#endif
const struct espi_bus_isr espi_bus_isr_tbl[] = {
NPCX_ESPI_BUS_INT_ITEM(BERR, espi_bus_err_isr),
NPCX_ESPI_BUS_INT_ITEM(IBRST, espi_bus_inband_rst_isr),
NPCX_ESPI_BUS_INT_ITEM(ESPIRST, espi_bus_reset_isr),
NPCX_ESPI_BUS_INT_ITEM(CFGUPD, espi_bus_cfg_update_isr),
#if defined(CONFIG_ESPI_OOB_CHANNEL)
NPCX_ESPI_BUS_INT_ITEM(OOBRX, espi_bus_oob_rx_isr),
#endif
};
static void espi_bus_generic_isr(void *arg)
{
const struct device *dev = (const struct device *)arg;
struct espi_reg *const inst = HAL_INSTANCE(dev);
int i;
uint32_t mask, status;
/*
* Bit 17 of ESPIIE is reserved. We need to set the same bit in mask
* in case bit 17 in ESPISTS of npcx7 is not cleared in ISR.
*/
mask = inst->ESPIIE | (1 << NPCX_ESPISTS_VWUPDW);
status = inst->ESPISTS & mask;
/* Clear pending bits of status register first */
inst->ESPISTS = status;
LOG_DBG("%s: 0x%08X", __func__, status);
for (i = 0; i < ARRAY_SIZE(espi_bus_isr_tbl); i++) {
struct espi_bus_isr entry = espi_bus_isr_tbl[i];
if (status & BIT(entry.status_bit)) {
if (entry.bus_isr != NULL) {
entry.bus_isr(dev);
}
}
}
}
/* eSPI local virtual-wire service functions */
static void espi_vw_config_input(const struct device *dev,
const struct npcx_vw_in_config *config_in)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
int idx = config_in->reg_idx;
/* IE & WE bits are already set? */
if (IS_BIT_SET(inst->VWEVMS[idx], NPCX_VWEVMS_IE) &&
IS_BIT_SET(inst->VWEVMS[idx], NPCX_VWEVMS_WE))
return;
/* Set IE & WE bits in VWEVMS */
inst->VWEVMS[idx] |= BIT(NPCX_VWEVMS_IE) | BIT(NPCX_VWEVMS_WE);
LOG_DBG("VWEVMS%d 0x%08X", idx, inst->VWEVMS[idx]);
}
static void espi_vw_config_output(const struct device *dev,
const struct npcx_vw_out_config *config_out)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
int idx = config_out->reg_idx;
uint8_t valid = GET_FIELD(inst->VWEVSM[idx], NPCX_VWEVSM_VALID);
/* Set valid bits for vw signal which we have declared in table. */
valid |= config_out->bitmask;
SET_FIELD(inst->VWEVSM[idx], NPCX_VWEVSM_VALID, valid);
LOG_DBG("VWEVSM%d 0x%08X", idx, inst->VWEVSM[idx]);
}
static void espi_vw_notify_system_state(const struct device *dev,
enum espi_vwire_signal signal)
{
struct espi_npcx_data *const data = DRV_DATA(dev);
struct espi_event evt = { ESPI_BUS_EVENT_VWIRE_RECEIVED, 0, 0 };
uint8_t wire = 0;
espi_npcx_receive_vwire(dev, signal, &wire);
if (!wire) {
data->sx_state = signal;
}
evt.evt_details = signal;
evt.evt_data = wire;
espi_send_callbacks(&data->callbacks, dev, evt);
}
static void espi_vw_notify_host_warning(const struct device *dev,
enum espi_vwire_signal signal)
{
uint8_t wire;
espi_npcx_receive_vwire(dev, signal, &wire);
k_busy_wait(NPCX_ESPI_VWIRE_ACK_DELAY);
switch (signal) {
case ESPI_VWIRE_SIGNAL_HOST_RST_WARN:
espi_npcx_send_vwire(dev,
ESPI_VWIRE_SIGNAL_HOST_RST_ACK,
wire);
break;
case ESPI_VWIRE_SIGNAL_SUS_WARN:
espi_npcx_send_vwire(dev, ESPI_VWIRE_SIGNAL_SUS_ACK,
wire);
break;
case ESPI_VWIRE_SIGNAL_OOB_RST_WARN:
espi_npcx_send_vwire(dev, ESPI_VWIRE_SIGNAL_OOB_RST_ACK,
wire);
break;
default:
break;
}
}
static void espi_vw_notify_plt_rst(const struct device *dev)
{
struct espi_npcx_data *const data = DRV_DATA(dev);
struct espi_reg *const inst = HAL_INSTANCE(dev);
struct espi_event evt = { ESPI_BUS_EVENT_VWIRE_RECEIVED,
ESPI_VWIRE_SIGNAL_PLTRST, 0
};
uint8_t wire = 0;
espi_npcx_receive_vwire(dev, ESPI_VWIRE_SIGNAL_PLTRST, &wire);
LOG_DBG("VW_PLT_RST is %d!", wire);
if (wire) {
/* Set Peripheral Channel ready when PLTRST is de-asserted */
inst->ESPICFG |= BIT(NPCX_ESPICFG_PCHANEN);
}
/* PLT_RST will be received several times */
if (wire != data->plt_rst_asserted) {
data->plt_rst_asserted = wire;
evt.evt_data = wire;
espi_send_callbacks(&data->callbacks, dev, evt);
}
}
static void espi_vw_send_bootload_done(const struct device *dev)
{
int ret;
uint8_t boot_done;
ret = espi_npcx_receive_vwire(dev,
ESPI_VWIRE_SIGNAL_SLV_BOOT_DONE, &boot_done);
LOG_DBG("%s: %d", __func__, boot_done);
if (!ret && !boot_done) {
/* Send slave boot status bit with done bit at the same time. */
espi_npcx_send_vwire(dev, ESPI_VWIRE_SIGNAL_SLV_BOOT_STS, 1);
}
}
static void espi_vw_generic_isr(const struct device *dev, struct npcx_wui *wui)
{
int signal;
LOG_DBG("%s: WUI %d %d %d", __func__, wui->table, wui->group, wui->bit);
for (signal = 0; signal < ARRAY_SIZE(vw_in_tbl); signal++) {
if (wui->table == vw_in_tbl[signal].vw_wui.table &&
wui->group == vw_in_tbl[signal].vw_wui.group &&
wui->bit == vw_in_tbl[signal].vw_wui.bit) {
break;
}
}
if (signal == ARRAY_SIZE(vw_in_tbl))
LOG_ERR("Unknown VW event! %d %d %d", wui->table,
wui->group, wui->bit);
if (signal == ESPI_VWIRE_SIGNAL_SLP_S3
|| signal == ESPI_VWIRE_SIGNAL_SLP_S4
|| signal == ESPI_VWIRE_SIGNAL_SLP_S5
|| signal == ESPI_VWIRE_SIGNAL_SLP_A) {
espi_vw_notify_system_state(dev, signal);
} else if (signal == ESPI_VWIRE_SIGNAL_HOST_RST_WARN
|| signal == ESPI_VWIRE_SIGNAL_SUS_WARN
|| signal == ESPI_VWIRE_SIGNAL_OOB_RST_WARN) {
espi_vw_notify_host_warning(dev, signal);
} else if (signal == ESPI_VWIRE_SIGNAL_PLTRST) {
espi_vw_notify_plt_rst(dev);
}
}
static void espi_vw_espi_rst_isr(const struct device *dev, struct npcx_wui *wui)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
struct espi_npcx_data *const data = DRV_DATA(dev);
struct espi_event evt = { ESPI_BUS_RESET, 0, 0 };
data->espi_rst_asserted = !IS_BIT_SET(inst->ESPISTS,
NPCX_ESPISTS_ESPIRST_LVL);
LOG_DBG("eSPI RST asserted is %d!", data->espi_rst_asserted);
evt.evt_data = data->espi_rst_asserted;
espi_send_callbacks(&data->callbacks, dev, evt);
}
/* eSPI api functions */
static int espi_npcx_configure(const struct device *dev, struct espi_cfg *cfg)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
uint8_t max_freq = 0;
uint8_t cur_io_mode, io_mode = 0;
/* Configure eSPI frequency */
switch (cfg->max_freq) {
case 20:
max_freq = NPCX_ESPI_MAXFREQ_20;
break;
case 25:
max_freq = NPCX_ESPI_MAXFREQ_25;
break;
case 33:
max_freq = NPCX_ESPI_MAXFREQ_33;
break;
case 50:
max_freq = NPCX_ESPI_MAXFREQ_50;
break;
default:
return -EINVAL;
}
SET_FIELD(inst->ESPICFG, NPCX_ESPICFG_MAXFREQ_FIELD, max_freq);
/* Configure eSPI IO mode */
io_mode = (cfg->io_caps >> 1);
if (io_mode > 3) {
return -EINVAL;
}
cur_io_mode = GET_FIELD(inst->ESPICFG, NPCX_ESPICFG_IOMODE_FIELD);
if (io_mode != cur_io_mode) {
SET_FIELD(inst->ESPICFG, NPCX_ESPICFG_IOMODE_FIELD, io_mode);
}
/* Configure eSPI supported channels */
if (cfg->channel_caps & ESPI_CHANNEL_PERIPHERAL)
inst->ESPICFG |= BIT(NPCX_ESPICFG_PCCHN_SUPP);
if (cfg->channel_caps & ESPI_CHANNEL_VWIRE)
inst->ESPICFG |= BIT(NPCX_ESPICFG_VWCHN_SUPP);
if (cfg->channel_caps & ESPI_CHANNEL_OOB)
inst->ESPICFG |= BIT(NPCX_ESPICFG_OOBCHN_SUPP);
if (cfg->channel_caps & ESPI_CHANNEL_FLASH)
inst->ESPICFG |= BIT(NPCX_ESPICFG_FLASHCHN_SUPP);
LOG_DBG("%s: %d %d ESPICFG: 0x%08X", __func__,
max_freq, io_mode, inst->ESPICFG);
return 0;
}
static bool espi_npcx_channel_ready(const struct device *dev,
enum espi_channel ch)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
bool sts;
switch (ch) {
case ESPI_CHANNEL_PERIPHERAL:
sts = IS_BIT_SET(inst->ESPICFG, NPCX_ESPICFG_PCHANEN);
break;
case ESPI_CHANNEL_VWIRE:
sts = IS_BIT_SET(inst->ESPICFG, NPCX_ESPICFG_VWCHANEN);
break;
case ESPI_CHANNEL_OOB:
sts = IS_BIT_SET(inst->ESPICFG, NPCX_ESPICFG_OOBCHANEN);
break;
case ESPI_CHANNEL_FLASH:
sts = IS_BIT_SET(inst->ESPICFG, NPCX_ESPICFG_FLASHCHANEN);
break;
default:
sts = false;
break;
}
return sts;
}
static int espi_npcx_send_vwire(const struct device *dev,
enum espi_vwire_signal signal, uint8_t level)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
uint8_t reg_idx, bitmask, sig_idx, val = 0;
/* Find signal in VW output table */
for (sig_idx = 0; sig_idx < ARRAY_SIZE(vw_out_tbl); sig_idx++)
if (vw_out_tbl[sig_idx].sig == signal)
break;
if (sig_idx == ARRAY_SIZE(vw_out_tbl)) {
LOG_ERR("%s signal %d is invalid", __func__, signal);
return -EIO;
}
reg_idx = vw_out_tbl[sig_idx].reg_idx;
bitmask = vw_out_tbl[sig_idx].bitmask;
/* Get wire field and set/clear wire bit */
val = GET_FIELD(inst->VWEVSM[reg_idx], NPCX_VWEVSM_WIRE);
if (level)
val |= bitmask;
else
val &= ~bitmask;
SET_FIELD(inst->VWEVSM[reg_idx], NPCX_VWEVSM_WIRE, val);
LOG_DBG("Send VW: VWEVSM%d 0x%08X", reg_idx, inst->VWEVSM[reg_idx]);
return 0;
}
static int espi_npcx_receive_vwire(const struct device *dev,
enum espi_vwire_signal signal, uint8_t *level)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
uint8_t reg_idx, bitmask, sig_idx, val;
/* Find signal in VW input table */
for (sig_idx = 0; sig_idx < ARRAY_SIZE(vw_in_tbl); sig_idx++)
if (vw_in_tbl[sig_idx].sig == signal) {
reg_idx = vw_in_tbl[sig_idx].reg_idx;
bitmask = vw_in_tbl[sig_idx].bitmask;
val = GET_FIELD(inst->VWEVMS[reg_idx],
NPCX_VWEVMS_WIRE);
val &= GET_FIELD(inst->VWEVMS[reg_idx],
NPCX_VWEVMS_VALID);
*level = !!(val & bitmask);
return 0;
}
/* Find signal in VW output table */
for (sig_idx = 0; sig_idx < ARRAY_SIZE(vw_out_tbl); sig_idx++)
if (vw_out_tbl[sig_idx].sig == signal) {
reg_idx = vw_out_tbl[sig_idx].reg_idx;
bitmask = vw_out_tbl[sig_idx].bitmask;
val = GET_FIELD(inst->VWEVSM[reg_idx],
NPCX_VWEVSM_WIRE);
val &= GET_FIELD(inst->VWEVSM[reg_idx],
NPCX_VWEVSM_VALID);
*level = !!(val & bitmask);
return 0;
}
LOG_ERR("%s Out of index %d", __func__, signal);
return -EIO;
}
static int espi_npcx_manage_callback(const struct device *dev,
struct espi_callback *callback, bool set)
{
struct espi_npcx_data *const data = DRV_DATA(dev);
return espi_manage_callback(&data->callbacks, callback, set);
}
static int espi_npcx_read_lpc_request(const struct device *dev,
enum lpc_peripheral_opcode op,
uint32_t *data)
{
ARG_UNUSED(dev);
/* TODO: Implement it in next commit */
return 0;
}
static int espi_npcx_write_lpc_request(const struct device *dev,
enum lpc_peripheral_opcode op,
uint32_t *data)
{
ARG_UNUSED(dev);
/* TODO: Implement it in next commit */
return 0;
}
#if defined(CONFIG_ESPI_OOB_CHANNEL)
static int espi_npcx_send_oob(const struct device *dev,
struct espi_oob_packet *pckt)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
uint8_t *oob_buf = pckt->buf;
int sz_oob_tx = pckt->len;
int idx_tx_buf;
uint32_t oob_data;
/* Check out of OOB transmitted buffer size */
if (sz_oob_tx > NPCX_ESPI_OOB_MAX_PAYLOAD) {
LOG_ERR("Out of OOB transmitted buffer: %d", sz_oob_tx);
return -EINVAL;
}
/* Check OOB Transmit Queue is empty? */
if (IS_BIT_SET(inst->OOBCTL, NPCX_OOBCTL_OOB_AVAIL)) {
LOG_ERR("OOB channel is busy");
return -EBUSY;
}
/*
* GET_OOB header (first 4 bytes) in npcx 32-bits tx buffer
*
* [24:31] - LEN[0:7] Data length of GET_OOB request package
* [20:23] - TAG Tag of GET_OOB
* [16:19] - LEN[8:11] Ignore it since max payload is 64 bytes
* [8:15] - CYCLE_TYPE Cycle type of GET_OOB
* [0:7] - SZ_PACK Package size plus 3 bytes header. (Npcx only)
*/
inst->OOBTXBUF[0] = (sz_oob_tx + 3)
| (ESPI_OOB_GET_CYCLE_TYPE << 8)
| (ESPI_OOB_TAG << 16)
| (sz_oob_tx << 24);
/* Write GET_OOB data into 32-bits tx buffer in little endian */
for (idx_tx_buf = 0; idx_tx_buf < sz_oob_tx/4; idx_tx_buf++,
oob_buf += 4)
inst->OOBTXBUF[idx_tx_buf + 1] = oob_buf[0]
| (oob_buf[1] << 8)
| (oob_buf[2] << 16)
| (oob_buf[3] << 24);
/* Write remaining bytes of package */
if (sz_oob_tx % 4) {
int i;
oob_data = 0;
for (i = 0; i < sz_oob_tx % 4; i++)
oob_data |= (oob_buf[i] << (8 * i));
inst->OOBTXBUF[idx_tx_buf + 1] = oob_data;
}
/*
* Notify host a new OOB packet is ready. Please don't write OOB_FREE
* to 1 at the same tiem in case clear it unexpectedly.
*/
oob_data = inst->OOBCTL & ~(BIT(NPCX_OOBCTL_OOB_FREE));
oob_data |= BIT(NPCX_OOBCTL_OOB_AVAIL);
inst->OOBCTL = oob_data;
while (IS_BIT_SET(inst->OOBCTL, NPCX_OOBCTL_OOB_AVAIL))
;
LOG_DBG("%s issued!!", __func__);
return 0;
}
static int espi_npcx_receive_oob(const struct device *dev,
struct espi_oob_packet *pckt)
{
struct espi_reg *const inst = HAL_INSTANCE(dev);
struct espi_npcx_data *const data = DRV_DATA(dev);
uint8_t *oob_buf = pckt->buf;
uint32_t oob_data;
int idx_rx_buf, sz_oob_rx, ret;
/* Check eSPI bus status first */
if (IS_BIT_SET(inst->ESPISTS, NPCX_ESPISTS_BERR)) {
LOG_ERR("%s: eSPI Bus Error: 0x%08X", __func__, inst->ESPIERR);
return -EIO;
}
/* Notify host that OOB received buffer is free now. */
inst->OOBCTL |= BIT(NPCX_OOBCTL_OOB_FREE);
/* Wait until get oob package or timeout */
ret = k_sem_take(&data->oob_rx_lock, K_MSEC(ESPI_OOB_MAX_TIMEOUT));
if (ret == -EAGAIN) {
LOG_ERR("%s: Timeout", __func__);
return -ETIMEDOUT;
}
/*
* PUT_OOB header (first 4 bytes) in npcx 32-bits rx buffer
*
* [24:31] - LEN[0:7] Data length of PUT_OOB request package
* [20:23] - TAG Tag of PUT_OOB
* [16:19] - LEN[8:11] Data length of PUT_OOB request package
* [8:15] - CYCLE_TYPE Cycle type of PUT_OOB
* [0:7] - SZ_PACK Reserved. (Npcx only)
*/
oob_data = inst->OOBRXBUF[0];
/* Get received package length first */
sz_oob_rx = NPCX_OOB_RX_PACKAGE_LEN(oob_data);
/* Check OOB received buffer size */
if (sz_oob_rx > NPCX_ESPI_OOB_MAX_PAYLOAD) {
LOG_ERR("Out of OOB received buffer: %d", sz_oob_rx);
return -EINVAL;
}
/* Set received size to package structure */
pckt->len = sz_oob_rx;
/* Read PUT_OOB data into 32-bits rx buffer in little endian */
for (idx_rx_buf = 0; idx_rx_buf < sz_oob_rx/4; idx_rx_buf++) {
oob_data = inst->OOBRXBUF[idx_rx_buf + 1];
*(oob_buf++) = oob_data & 0xFF;
*(oob_buf++) = (oob_data >> 8) & 0xFF;
*(oob_buf++) = (oob_data >> 16) & 0xFF;
*(oob_buf++) = (oob_data >> 24) & 0xFF;
}
/* Read remaining bytes of package */
if (sz_oob_rx % 4) {
int i;
oob_data = inst->OOBRXBUF[idx_rx_buf + 1];
for (i = 0; i < sz_oob_rx % 4; i++)
*(oob_buf++) = (oob_data >> (8 * i)) & 0xFF;
}
return 0;
}
#endif
/* eSPI driver registration */
static int espi_npcx_init(const struct device *dev);
static const struct espi_driver_api espi_npcx_driver_api = {
.config = espi_npcx_configure,
.get_channel_status = espi_npcx_channel_ready,
.send_vwire = espi_npcx_send_vwire,
.receive_vwire = espi_npcx_receive_vwire,
.manage_callback = espi_npcx_manage_callback,
.read_lpc_request = espi_npcx_read_lpc_request,
.write_lpc_request = espi_npcx_write_lpc_request,
#if defined(CONFIG_ESPI_OOB_CHANNEL)
.send_oob = espi_npcx_send_oob,
.receive_oob = espi_npcx_receive_oob,
#endif
};
static struct espi_npcx_data espi_npcx_data;
static const struct npcx_alt espi_alts[] = DT_NPCX_ALT_ITEMS_LIST(0);
static const struct espi_npcx_config espi_npcx_config = {
.base = DT_INST_REG_ADDR(0),
.espi_rst_wui = DT_NPCX_ESPI_WUI_ITEM(espi_rst_wui),
.clk_cfg = DT_NPCX_CLK_CFG_ITEM(0),
.alts_size = ARRAY_SIZE(espi_alts),
.alts_list = espi_alts,
};
DEVICE_AND_API_INIT(espi_npcx_0, DT_INST_LABEL(0),
&espi_npcx_init, &espi_npcx_data, &espi_npcx_config,
PRE_KERNEL_2, CONFIG_ESPI_INIT_PRIORITY,
&espi_npcx_driver_api);
static int espi_npcx_init(const struct device *dev)
{
const struct espi_npcx_config *const config = DRV_CONFIG(dev);
struct espi_npcx_data *const data = DRV_DATA(dev);
struct espi_reg *const inst = HAL_INSTANCE(dev);
const struct device *clk_dev = device_get_binding(NPCX_CLK_CTRL_NAME);
int i;
/* Turn on eSPI device clock first */
if (clock_control_on(clk_dev,
(clock_control_subsys_t *) &config->clk_cfg) != 0) {
return -EIO;
}
/* Enable events which share the same espi bus interrupt */
for (i = 0; i < ARRAY_SIZE(espi_bus_isr_tbl); i++) {
inst->ESPIIE |= BIT(espi_bus_isr_tbl[i].int_en_bit);
inst->ESPIWE |= BIT(espi_bus_isr_tbl[i].wake_en_bit);
}
#if defined(CONFIG_ESPI_OOB_CHANNEL)
k_sem_init(&data->oob_rx_lock, 0, 1);
#endif
/* Configure Virtual Wire input signals */
for (i = 0; i < ARRAY_SIZE(vw_in_tbl); i++)
espi_vw_config_input(dev, &vw_in_tbl[i]);
/* Configure Virtual Wire output signals */
for (i = 0; i < ARRAY_SIZE(vw_out_tbl); i++)
espi_vw_config_output(dev, &vw_out_tbl[i]);
/* Configure wake-up input and callback for eSPI VW input signal */
for (i = 0; i < ARRAY_SIZE(vw_in_tbl); i++)
espi_init_wui_callback(dev, &vw_in_callback[i],
&vw_in_tbl[i].vw_wui, espi_vw_generic_isr);
/* Configure wake-up input and callback for ESPI_RST signal */
espi_init_wui_callback(dev, &espi_rst_callback,
&config->espi_rst_wui, espi_vw_espi_rst_isr);
/* Configure pin-mux for eSPI bus device */
soc_pinctrl_mux_configure(config->alts_list, config->alts_size, 1);
/* eSPI Bus interrupt installation */
IRQ_CONNECT(DT_INST_IRQN(0),
DT_INST_IRQ(0, priority),
espi_bus_generic_isr,
DEVICE_GET(espi_npcx_0), 0);
/* Enable eSPI bus interrupt */
irq_enable(DT_INST_IRQN(0));
return 0;
}

View file

@ -0,0 +1,93 @@
/*
* Copyright (c) 2020 Nuvoton Technology Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
/*
* Nuvoton NPCX7 eSPI Virtual Wires Mapping Table
* |--------------------------------------------------------------------------|
* | VW idx | SLV reg | Wire Bit 3 | Wire Bit 2 | Wire Bit 1| Wire Bit 0 |
* |--------------------------------------------------------------------------|
* | Input (Master-to-Slave) Virtual Wires |
* |--------------------------------------------------------------------------|
* | 02h[S] | VWEVMS0 | Reserved | SLP_S5# | SLP_S4# | SLP_S3# |
* | 03h[S] | VWEVMS1 | Reserved | OOB_RST_WARN | PLTRST# | SUS_STAT# |
* | 07h[S] | VWEVMS2 | Reserved | Reserved | Reserved | HOS_RST_WARN|
* | 41h[P] | VWEVMS3 | SLP_A# | Reserved | SUS_PDNACK| SUS_WARN# |
* | 42h[P] | VWEVMS4 | Reserved | Reserved | SLP_WLAN# | SLP_LAN# |
* |--------------------------------------------------------------------------|
* | Output (Slave-to-Master) Virtual Wires |
* |--------------------------------------------------------------------------|
* | 04h[S] | VWEVSM0 | PME# | WAKE# | Reserved | OOB_RST_ACK |
* | 05h[S] | VWEVSM1 | SLV_BOOT_STS | ERR_NONFATAL | ERR_FATAL | SLV_BT_DONE |
* | 06h[S] | VWEVSM2 | HOST_RST_ACK | Reserved | SMI# | SCI# |
* | 40h[P] | VWEVSM3 | Reserved | Reserved | Reserved | SUS_ACK# |
* |--------------------------------------------------------------------------|
* [S] System-/[P] Platform-Specific Virtual Wires
*/
/ {
npcx7_espi_vws_map {
compatible = "nuvoton,npcx-espi-vw-conf";
/* eSPI Virtual Vire (VW) input configuration */
/* index 02h (In) */
vw_slp_s3 { vw_reg =
<NPCX_VWEVMS0 0x01>; wui_map = <&wui_vw_slp_s3>; };
vw_slp_s4 { vw_reg =
<NPCX_VWEVMS0 0x02>; wui_map = <&wui_vw_slp_s4>; };
vw_slp_s5 { vw_reg =
<NPCX_VWEVMS0 0x04>; wui_map = <&wui_vw_slp_s5>; };
/* index 03h (In) */
vw_sus_stat { vw_reg =
<NPCX_VWEVMS1 0x01>; wui_map = <&wui_vw_sus_stat>; };
vw_plt_rst { vw_reg =
<NPCX_VWEVMS1 0x02>; wui_map = <&wui_vw_plt_rst>; };
vw_oob_rst_warn { vw_reg =
<NPCX_VWEVMS1 0x04>; wui_map = <&wui_vw_oob_rst_warn>;};
/* index 07h (In) */
vw_host_rst_warn { vw_reg =
<NPCX_VWEVMS2 0x01>; wui_map =<&wui_vw_host_rst_warn>;};
/* index 41h (In) */
vw_sus_warn { vw_reg =
<NPCX_VWEVMS3 0x01>; wui_map = <&wui_vw_sus_warn>; };
vw_sus_pwrdn_ack { vw_reg =
<NPCX_VWEVMS3 0x02>; wui_map =<&wui_vw_sus_pwrdn_ack>;};
vw_slp_a { vw_reg =
<NPCX_VWEVMS3 0x08>; wui_map = <&wui_vw_slp_a>; };
/* index 42h (In) */
vw_slp_lan { vw_reg =
<NPCX_VWEVMS4 0x01>; wui_map = <&wui_vw_slp_lan>; };
vw_slp_wlan { vw_reg =
<NPCX_VWEVMS4 0x02>; wui_map = <&wui_vw_slp_wlan>; };
/* eSPI Virtual Vire (VW) output configuration */
/* index 04h (Out) */
vw_oob_rst_ack { vw_reg = <NPCX_VWEVSM0 0x01>; };
vw_wake { vw_reg = <NPCX_VWEVSM0 0x04>; };
vw_pme { vw_reg = <NPCX_VWEVSM0 0x08>; };
/* index 05h (Out) */
vw_slv_boot_done { vw_reg = <NPCX_VWEVSM1 0x01>; };
vw_err_fatal { vw_reg = <NPCX_VWEVSM1 0x02>; };
vw_err_non_fatal { vw_reg = <NPCX_VWEVSM1 0x04>; };
/*
* SLAVE_BOOT_DONE & SLAVE_LOAD_STS bits (bit 0 & bit 3) have
* to be sent together. Hence its bitmask is 0x09.
*/
vw_slv_boot_sts_with_done { vw_reg = <NPCX_VWEVSM1 0x09>; };
/* index 06h (Out) */
vw_sci { vw_reg = <NPCX_VWEVSM2 0x01>; };
vw_smi { vw_reg = <NPCX_VWEVSM2 0x02>; };
vw_host_rst_ack { vw_reg = <NPCX_VWEVSM2 0x08>; };
/* index 40h (Out) */
vw_sus_ack { vw_reg = <NPCX_VWEVSM3 0x01>; };
};
};

View file

@ -7,6 +7,7 @@
#include <arm/armv7-m.dtsi>
/* Macros for device tree declarations */
#include <dt-bindings/clock/npcx_clock.h>
#include <dt-bindings/espi/npcx_espi.h>
#include <dt-bindings/gpio/gpio.h>
/* NPCX7 series pinmux mapping table */
@ -15,6 +16,8 @@
#include "npcx/npcx7-miwus-wui-map.dtsi"
/* NPCX7 series mapping table between MIWU groups and interrupts */
#include "npcx/npcx7-miwus-int-map.dtsi"
/* NPCX7 series eSPI VW mapping table */
#include "npcx/npcx7-espi-vws-map.dtsi"
/ {
cpus {
@ -287,6 +290,25 @@
#gpio-cells=<2>;
label="GPIO_F";
};
espi0: espi@4000a000 {
compatible = "nuvoton,npcx-espi";
reg = <0x4000a000 0x2000>;
interrupts = <18 3>; /* Interrupt for eSPI Bus */
/* clocks for eSPI modules */
clocks = <&pcc NPCX_CLOCK_BUS_APB3 NPCX_PWDWN_CTL6 7>;
/* PIN46.47.51.52.53.54.55.57 */
pinctrl = <&alt1_no_lpc_espi>;
/* WUI maps for eSPI signals */
espi_rst_wui = <&wui_espi_rst>;
label = "ESPI_0";
#address-cells = <1>;
#size-cells = <0>;
#vw-cells = <3>;
status = "disabled";
};
};
};

View file

@ -0,0 +1,22 @@
# Copyright (c) 2020 Nuvoton Technology Corporation.
# SPDX-License-Identifier: Apache-2.0
description: Nuvoton NPCX eSPI Virtual Wire (VW) mapping child node
compatible: "nuvoton,npcx-espi-vw-conf"
child-binding:
description: Child node to to present the mapping between VW signal, its core register and input source of MIWU
properties:
vw_reg:
type: array
required: true
description: vw signal's register index and vw bitmask.
wui_map:
type: phandle
description: |
Mapping table between Wake-Up Input (WUI) and vw input signal.
For example the WUI mapping on NPCX7 for VW_SLP5 would be
wui_map = <&wui_vw_slp_s5>;

View file

@ -0,0 +1,31 @@
# Copyright (c) 2020 Nuvoton Technology Corporation.
# SPDX-License-Identifier: Apache-2.0
description: Nuvoton, NPCX-eSPI node
compatible: "nuvoton,npcx-espi"
include: espi-controller.yaml
properties:
reg:
description: mmio register space
required: true
clocks:
required: true
description: configurations of device source clock controller
pinctrl:
type: phandles
required: true
description: configurations of pinmux controllers
espi_rst_wui:
type: phandle
required: true
description: |
Mapping table between Wake-Up Input (WUI) and ESPI_RST signal.
For example the WUI mapping on NPCX7 would be
espi_rst_wui = <&wui_cr_sin1>;

View file

@ -0,0 +1,35 @@
/*
* Copyright (c) 2020 Nuvoton Technology Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
#ifndef ZEPHYR_INCLUDE_DT_BINDINGS_ESPI_NPCX_ESPI_H_
#define ZEPHYR_INCLUDE_DT_BINDINGS_ESPI_NPCX_ESPI_H_
/* eSPI VW Master to Slave Register Index */
#define NPCX_VWEVMS0 0
#define NPCX_VWEVMS1 1
#define NPCX_VWEVMS2 2
#define NPCX_VWEVMS3 3
#define NPCX_VWEVMS4 4
#define NPCX_VWEVMS5 5
#define NPCX_VWEVMS6 6
#define NPCX_VWEVMS7 7
#define NPCX_VWEVMS8 8
#define NPCX_VWEVMS9 9
/* eSPI VW Slave to Master Register Index */
#define NPCX_VWEVSM0 0
#define NPCX_VWEVSM1 1
#define NPCX_VWEVSM2 2
#define NPCX_VWEVSM3 3
#define NPCX_VWEVSM4 4
#define NPCX_VWEVSM5 5
#define NPCX_VWEVSM6 6
#define NPCX_VWEVSM7 7
#define NPCX_VWEVSM8 8
#define NPCX_VWEVSM9 9
#define NPCX_VWEVSM10 10
#define NPCX_VWEVSM11 11
#endif /* ZEPHYR_INCLUDE_DT_BINDINGS_ESPI_NPCX_ESPI_H_ */

View file

@ -0,0 +1,9 @@
/*
* Copyright (c) 2020 Nuvoton Technology Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
/ {
/* TODO: Add GPIOs for power sequence later */
};

View file

@ -0,0 +1,7 @@
# eSPI + npcx7m6fb_evb
CONFIG_LOG=y
CONFIG_LOG_BUFFER_SIZE=4096
CONFIG_LOG_PROCESS_THREAD_SLEEP_MS=100
# Not supported yet
CONFIG_ESPI_AUTOMATIC_WARNING_ACKNOWLEDGE=n

View file

@ -308,4 +308,163 @@ struct gpio_reg {
volatile uint8_t PLOCK_CTL;
};
/*
* Enhanced Serial Peripheral Interface (eSPI) device registers
*/
struct espi_reg {
/* 0x000: eSPI Identification */
volatile uint32_t ESPIID;
/* 0x004: eSPI Configuration */
volatile uint32_t ESPICFG;
/* 0x008: eSPI Status */
volatile uint32_t ESPISTS;
/* 0x00C: eSPI Interrupt Enable */
volatile uint32_t ESPIIE;
/* 0x010: eSPI Wake-Up Enable */
volatile uint32_t ESPIWE;
/* 0x014: Virtual Wire Register Index */
volatile uint32_t VWREGIDX;
/* 0x018: Virtual Wire Register Data */
volatile uint32_t VWREGDATA;
/* 0x01C: OOB Receive Buffer Read Head */
volatile uint32_t OOBRXRDHEAD;
/* 0x020: OOB Transmit Buffer Write Head */
volatile uint32_t OOBTXWRHEAD;
/* 0x024: OOB Channel Control */
volatile uint32_t OOBCTL;
/* 0x028: Flash Receive Buffer Read Head */
volatile uint32_t FLASHRXRDHEAD;
/* 0x02C: Flash Transmit Buffer Write Head */
volatile uint32_t FLASHTXWRHEAD;
volatile uint32_t reserved1;
/* 0x034: Flash Channel Configuration */
volatile uint32_t FLASHCFG;
/* 0x038: Flash Channel Control */
volatile uint32_t FLASHCTL;
/* 0x03C: eSPI Error Status */
volatile uint32_t ESPIERR;
/* 0x040: Peripheral Bus Master Receive Buffer Read Head */
volatile uint32_t PBMRXRDHEAD;
/* 0x044: Peripheral Bus Master Transmit Buffer Write Head */
volatile uint32_t PBMTXWRHEAD;
/* 0x048: Peripheral Channel Configuration */
volatile uint32_t PERCFG;
/* 0x04C: Peripheral Channel Control */
volatile uint32_t PERCTL;
volatile uint32_t reserved2[44];
/* 0x100 - 127: Virtual Wire Event Slave-to-Master 0 - 9 */
volatile uint32_t VWEVSM[10];
volatile uint32_t reserved3[6];
/* 0x140 - 16F: Virtual Wire Event Master-to-Slave 0 - 11 */
volatile uint32_t VWEVMS[12];
volatile uint32_t reserved4[99];
/* 0x2FC: Virtual Wire Channel Control */
volatile uint32_t VWCTL;
/* 0x300 - 34F: OOB Receive Buffer 0 - 19 */
volatile uint32_t OOBRXBUF[20];
volatile uint32_t reserved5[12];
/* 0x380 - 3CF: OOB Transmit Buffer 0-19 */
volatile uint32_t OOBTXBUF[20];
volatile uint32_t reserved6[11];
/* 0x3FC: OOB Channel Control used in 'direct' mode */
volatile uint32_t OOBCTL_DIRECT;
/* 0x400 - 443: Flash Receive Buffer 0-16 */
volatile uint32_t FLASHRXBUF[17];
volatile uint32_t reserved7[15];
/* 0x480 - 497: Flash Transmit Buffer 0-5 */
volatile uint32_t FLASHTXBUF[6];
volatile uint32_t reserved8[25];
/* 0x4FC: Flash Channel Control used in 'direct' mode */
volatile uint32_t FLASHCTL_DIRECT;
};
/* eSPI register fields */
#define NPCX_ESPICFG_PCHANEN 0
#define NPCX_ESPICFG_VWCHANEN 1
#define NPCX_ESPICFG_OOBCHANEN 2
#define NPCX_ESPICFG_FLASHCHANEN 3
#define NPCX_ESPICFG_HPCHANEN 4
#define NPCX_ESPICFG_HVWCHANEN 5
#define NPCX_ESPICFG_HOOBCHANEN 6
#define NPCX_ESPICFG_HFLASHCHANEN 7
#define NPCX_ESPICFG_CHANS_FIELD FIELD(0, 4)
#define NPCX_ESPICFG_HCHANS_FIELD FIELD(4, 4)
#define NPCX_ESPICFG_IOMODE_FIELD FIELD(8, 9)
#define NPCX_ESPICFG_MAXFREQ_FIELD FIELD(10, 12)
#define NPCX_ESPICFG_PCCHN_SUPP 24
#define NPCX_ESPICFG_VWCHN_SUPP 25
#define NPCX_ESPICFG_OOBCHN_SUPP 26
#define NPCX_ESPICFG_FLASHCHN_SUPP 27
#define NPCX_ESPIIE_IBRSTIE 0
#define NPCX_ESPIIE_CFGUPDIE 1
#define NPCX_ESPIIE_BERRIE 2
#define NPCX_ESPIIE_OOBRXIE 3
#define NPCX_ESPIIE_FLASHRXIE 4
#define NPCX_ESPIIE_SFLASHRDIE 5
#define NPCX_ESPIIE_PERACCIE 6
#define NPCX_ESPIIE_DFRDIE 7
#define NPCX_ESPIIE_VWUPDIE 8
#define NPCX_ESPIIE_ESPIRSTIE 9
#define NPCX_ESPIIE_PLTRSTIE 10
#define NPCX_ESPIIE_AMERRIE 15
#define NPCX_ESPIIE_AMDONEIE 16
#define NPCX_ESPIIE_BMTXDONEIE 19
#define NPCX_ESPIIE_PBMRXIE 20
#define NPCX_ESPIIE_PMSGRXIE 21
#define NPCX_ESPIIE_BMBURSTERRIE 22
#define NPCX_ESPIIE_BMBURSTDONEIE 23
#define NPCX_ESPIWE_IBRSTWE 0
#define NPCX_ESPIWE_CFGUPDWE 1
#define NPCX_ESPIWE_BERRWE 2
#define NPCX_ESPIWE_OOBRXWE 3
#define NPCX_ESPIWE_FLASHRXWE 4
#define NPCX_ESPIWE_PERACCWE 6
#define NPCX_ESPIWE_DFRDWE 7
#define NPCX_ESPIWE_VWUPDWE 8
#define NPCX_ESPIWE_ESPIRSTWE 9
#define NPCX_ESPIWE_PBMRXWE 20
#define NPCX_ESPIWE_PMSGRXWE 21
#define NPCX_ESPISTS_IBRST 0
#define NPCX_ESPISTS_CFGUPD 1
#define NPCX_ESPISTS_BERR 2
#define NPCX_ESPISTS_OOBRX 3
#define NPCX_ESPISTS_FLASHRX 4
#define NPCX_ESPISTS_PERACC 6
#define NPCX_ESPISTS_DFRD 7
#define NPCX_ESPISTS_VWUPD 8
#define NPCX_ESPISTS_ESPIRST 9
#define NPCX_ESPISTS_PLTRST 10
#define NPCX_ESPISTS_AMERR 15
#define NPCX_ESPISTS_AMDONE 16
#define NPCX_ESPISTS_VWUPDW 17
#define NPCX_ESPISTS_BMTXDONE 19
#define NPCX_ESPISTS_PBMRX 20
#define NPCX_ESPISTS_PMSGRX 21
#define NPCX_ESPISTS_BMBURSTERR 22
#define NPCX_ESPISTS_BMBURSTDONE 23
#define NPCX_ESPISTS_ESPIRST_LVL 24
#define NPCX_VWEVMS_WIRE FIELD(0, 4)
#define NPCX_VWEVMS_VALID FIELD(4, 4)
#define NPCX_VWEVMS_IE 18
#define NPCX_VWEVMS_WE 20
#define NPCX_VWEVSM_WIRE FIELD(0, 4)
#define NPCX_VWEVSM_VALID FIELD(4, 4)
#define NPCX_VWEVSM_BIT_VALID(n) (4+n)
#define NPCX_OOBCTL_OOB_FREE 0
#define NPCX_OOBCTL_OOB_AVAIL 1
#define NPCX_OOBCTL_RSTBUFHEADS 2
#define NPCX_OOBCTL_OOBPLSIZE FIELD(10, 3)
#define NPCX_FLASHCFG_FLASHBLERSSIZE FIELD(7, 3)
#define NPCX_FLASHCFG_FLASHPLSIZE FIELD(10, 3)
#define NPCX_FLASHCFG_FLASHREQSIZE FIELD(13, 3)
#define NPCX_FLASHCTL_FLASH_NP_FREE 0
#define NPCX_FLASHCTL_FLASH_TX_AVAIL 1
#define NPCX_FLASHCTL_STRPHDR 2
#define NPCX_FLASHCTL_DMATHRESH FIELD(3, 2)
#define NPCX_FLASHCTL_AMTSIZE FIELD(5, 8)
#define NPCX_FLASHCTL_RSTBUFHEADS 13
#define NPCX_FLASHCTL_CRCEN 14
#define NPCX_FLASHCTL_CHKSUMSEL 15
#define NPCX_FLASHCTL_AMTEN 16
#endif /* _NUVOTON_NPCX_REG_DEF_H */

View file

@ -18,6 +18,27 @@
.bit = DT_PHA(DT_DRV_INST(inst), clocks, bit), \
}
/* Construct a npcx_clk_cfg structure from clocks property at index 'i' */
#define DT_NPCX_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), \
},
/* Length of npcx_clk_cfg structures in clocks property */
#define DT_NPCX_CLK_CFG_ITEMS_LEN(inst) DT_INST_PROP_LEN(inst, clocks)
/* Macro function to construct a list of npcx_clk_cfg items by UTIL_LISTIFY */
#define DT_NPCX_CLK_CFG_ITEMS_FUC(idx, inst) \
DT_NPCX_CLK_CFG_ITEM_BY_IDX(inst, idx)
#define DT_NPCX_CLK_CFG_ITEMS_LIST(inst) { \
UTIL_LISTIFY(DT_NPCX_CLK_CFG_ITEMS_LEN(inst), \
DT_NPCX_CLK_CFG_ITEMS_FUC, \
inst) \
}
/* Get phandle from "pinctrl" prop which type is 'phandles' at index 'i' */
#define DT_PHANDLE_FROM_PINCTRL(inst, i) \
DT_INST_PHANDLE_BY_IDX(inst, pinctrl, i)
@ -99,4 +120,48 @@
irq_enable(DT_PROP(child, irq)); \
}
/* Get a child node from path '/npcx7_espi_vws_map/name' */
#define DT_NODE_FROM_VWTABLE(name) DT_CHILD(DT_PATH(npcx7_espi_vws_map), name)
/* Get a handle from wui_map property of child node */
#define DT_PHANDLE_VW_WUI(name) DT_PHANDLE(DT_NODE_FROM_VWTABLE(name), wui_map)
/* Construct a npcx_wui structure from wui_map property of vw table by name */
#define DT_NPCX_VW_WUI_ITEM(name) \
{ \
.table = DT_PROP(DT_PHANDLE(DT_PHANDLE_VW_WUI(name), miwus), index),\
.group = DT_PHA(DT_PHANDLE_VW_WUI(name), miwus, group), \
.bit = DT_PHA(DT_PHANDLE_VW_WUI(name), miwus, bit), \
}
/* Construct a npcx espi device configuration for vw input signal by name */
#define DT_NPCX_VW_IN_CONF(signal, name) \
{ \
.sig = signal, \
.reg_idx = DT_PROP_BY_IDX(DT_NODE_FROM_VWTABLE(name), vw_reg, 0), \
.bitmask = DT_PROP_BY_IDX(DT_NODE_FROM_VWTABLE(name), vw_reg, 1), \
.vw_wui = DT_NPCX_VW_WUI_ITEM(name), \
}
/* Construct a npcx espi device configuration for vw output signal by name */
#define DT_NPCX_VW_OUT_CONF(signal, name) \
{ \
.sig = signal, \
.reg_idx = DT_PROP_BY_IDX(DT_NODE_FROM_VWTABLE(name), vw_reg, 0), \
.bitmask = DT_PROP_BY_IDX(DT_NODE_FROM_VWTABLE(name), vw_reg, 1), \
}
/* Get phandle from "name" prop */
#define DT_PHANDLE_FROM_WUI_NAME(name) \
DT_INST_PHANDLE(0, name)
/* Construct a npcx_wui structure from wui_map property */
#define DT_NPCX_ESPI_WUI_ITEM(name) \
{ \
.table = DT_PROP(DT_PHANDLE(DT_PHANDLE_FROM_WUI_NAME(name), \
miwus), index), \
.group = DT_PHA(DT_PHANDLE_FROM_WUI_NAME(name), miwus, group), \
.bit = DT_PHA(DT_PHANDLE_FROM_WUI_NAME(name), miwus, bit), \
}
#endif /* _NUVOTON_NPCX_SOC_DT_H_ */

View file

@ -35,6 +35,18 @@ config GPIO_NPCX
help
Enable support for NPCX GPIO driver.
config ESPI_NPCX
default y
depends on ESPI
help
Enable support for NPCX ESPI driver. The Intel Enhanced Serial
Peripheral Interface (eSPI) provides a path for migrating host
sub-devices via LPC to a lower pin count, higher bandwidth bus.
So far, this driver supports all of functionalities beside flash
channel support. It will be supported in the future. Please refer
https://www.intel.com/content/www/us/en/support/articles/000020952/
software/chipset-software.html for more detail.
source "soc/arm/nuvoton_npcx/npcx7/Kconfig.defconfig.npcx7*"
endif # SOC_SERIES_NPCX7

View file

@ -46,3 +46,13 @@ NPCX_REG_OFFSET_CHECK(uart_reg, UFRCTL, 0x026);
/* GPIO register structure check */
NPCX_REG_SIZE_CHECK(gpio_reg, 0x008);
NPCX_REG_OFFSET_CHECK(gpio_reg, PLOCK_CTL, 0x007);
/* ESPI register structure check */
NPCX_REG_SIZE_CHECK(espi_reg, 0x500);
NPCX_REG_OFFSET_CHECK(espi_reg, FLASHCFG, 0x034);
NPCX_REG_OFFSET_CHECK(espi_reg, VWEVMS, 0x140);
NPCX_REG_OFFSET_CHECK(espi_reg, VWCTL, 0x2FC);
NPCX_REG_OFFSET_CHECK(espi_reg, OOBTXBUF, 0x380);
NPCX_REG_OFFSET_CHECK(espi_reg, OOBCTL_DIRECT, 0x3FC);
NPCX_REG_OFFSET_CHECK(espi_reg, FLASHTXBUF, 0x480);
NPCX_REG_OFFSET_CHECK(espi_reg, FLASHCTL_DIRECT, 0x4FC);