drivers: adc: add adc support in npcx7 series

NPCX7 includes a 10-bit resolution Analog-to-Digital Converter (ADC). Up
to 10 voltage inputs can be measured and a internal voltage reference
(VREF), 2.816V (typical) is used for measurement. It can be triggered
automatically in Autoscan mode. Each input channel is assigned a
separate result register, which is updated at the end of the conversion.

The CL also includes:
— Add npcx adc device tree declarations.
— Zephyr adc api implementation.
— Add adc definitions of npcx7 in
  tests/drivers/adc/adc_api/src/test_adc.c for supporting test suites.

Signed-off-by: Mulin Chao <MLChao@nuvoton.com>
This commit is contained in:
Mulin Chao 2020-08-17 11:02:38 +08:00 committed by Anas Nashif
commit a279b4cfb7
15 changed files with 550 additions and 0 deletions

View file

@ -162,6 +162,7 @@
/drivers/*/*lpc11u6x* @mbittan @simonguinot /drivers/*/*lpc11u6x* @mbittan @simonguinot
/drivers/adc/ @anangl /drivers/adc/ @anangl
/drivers/adc/adc_stm32.c @cybertale /drivers/adc/adc_stm32.c @cybertale
/drivers/adc/*npcx* @MulinChao
/drivers/bluetooth/ @joerchan @jhedberg @Vudentz /drivers/bluetooth/ @joerchan @jhedberg @Vudentz
/drivers/can/ @alexanderwachter /drivers/can/ @alexanderwachter
/drivers/can/*mcp2515* @karstenkoenig /drivers/can/*mcp2515* @karstenkoenig

View file

@ -44,6 +44,11 @@
status = "okay"; status = "okay";
}; };
&adc0 {
/* ADC pinmux is changed only if related channel is configured. */
status = "okay";
};
&espi0 { &espi0 {
status = "okay"; status = "okay";
}; };

View file

@ -13,3 +13,5 @@ toolchain:
- gnuarmemb - gnuarmemb
ram: 64 ram: 64
flash: 192 flash: 192
supported:
- adc

View file

@ -37,6 +37,9 @@ CONFIG_GPIO=y
# PWM Driver # PWM Driver
CONFIG_PWM=y CONFIG_PWM=y
# ADC Driver
CONFIG_ADC=y
# ESPI Driver # ESPI Driver
CONFIG_ESPI=y CONFIG_ESPI=y

View file

@ -15,4 +15,5 @@ zephyr_library_sources_ifdef(CONFIG_ADC_STM32 adc_stm32.c)
zephyr_library_sources_ifdef(CONFIG_ADC_XEC adc_mchp_xec.c) zephyr_library_sources_ifdef(CONFIG_ADC_XEC adc_mchp_xec.c)
zephyr_library_sources_ifdef(CONFIG_ADC_LMP90XXX adc_lmp90xxx.c) zephyr_library_sources_ifdef(CONFIG_ADC_LMP90XXX adc_lmp90xxx.c)
zephyr_library_sources_ifdef(CONFIG_ADC_MCP320X adc_mcp320x.c) zephyr_library_sources_ifdef(CONFIG_ADC_MCP320X adc_mcp320x.c)
zephyr_library_sources_ifdef(CONFIG_ADC_NPCX adc_npcx.c)
zephyr_library_sources_ifdef(CONFIG_USERSPACE adc_handlers.c) zephyr_library_sources_ifdef(CONFIG_USERSPACE adc_handlers.c)

View file

@ -54,4 +54,6 @@ source "drivers/adc/Kconfig.lmp90xxx"
source "drivers/adc/Kconfig.mcp320x" source "drivers/adc/Kconfig.mcp320x"
source "drivers/adc/Kconfig.npcx"
endif # ADC endif # ADC

12
drivers/adc/Kconfig.npcx Normal file
View file

@ -0,0 +1,12 @@
# NPCX ADC driver configuration options
# Copyright (c) 2020 Nuvoton Technology Corporation.
# SPDX-License-Identifier: Apache-2.0
config ADC_NPCX
bool "Nuvoton NPCX embedd controller (EC) ADC driver"
depends on SOC_FAMILY_NPCX
help
This option enables the ADC driver for NPCX family of
processors.
Say y if you wish to use ADC channels on NPCX MCU.

383
drivers/adc/adc_npcx.c Normal file
View file

@ -0,0 +1,383 @@
/*
* Copyright (c) 2020 Nuvoton Technology Corporation.
*
* SPDX-License-Identifier: Apache-2.0
*/
#define DT_DRV_COMPAT nuvoton_npcx_adc
#include <assert.h>
#include <drivers/adc.h>
#include <drivers/clock_control.h>
#include <kernel.h>
#include <soc.h>
#define ADC_CONTEXT_USES_KERNEL_TIMER
#include "adc_context.h"
#include <logging/log.h>
LOG_MODULE_REGISTER(adc_npcx, CONFIG_ADC_LOG_LEVEL);
/* ADC speed/delay values during initialization */
#define ADC_REGULAR_DLY_VAL 0x03
#define ADC_REGULAR_ADCCNF2_VAL 0x8B07
#define ADC_REGULAR_GENDLY_VAL 0x0100
#define ADC_REGULAR_MEAST_VAL 0x0001
/* ADC channel number */
#define NPCX_ADC_CH_COUNT 10
/* ADC targeted operating frequency (2MHz) */
#define NPCX_ADC_CLK 2000000
/* ADC internal reference voltage (Unit:mV) */
#define NPCX_ADC_VREF_VOL 2816
/* ADC conversion mode */
#define NPCX_ADC_CHN_CONVERSION_MODE 0
#define NPCX_ADC_SCAN_CONVERSION_MODE 1
/* Device config */
struct adc_npcx_config {
/* adc controller base address */
uintptr_t base;
/* clock configuration */
struct npcx_clk_cfg clk_cfg;
/* pinmux configuration */
const struct npcx_alt *alts_list;
};
/* Driver data */
struct adc_npcx_data {
/* Input clock for ADC converter */
uint32_t input_clk;
/* mutex of ADC channels */
struct adc_context ctx;
/*
* Bit-mask indicating the channels to be included in each sampling
* of this sequence.
*/
uint16_t channels;
/* ADC Device pointer used in api functions */
const struct device *adc_dev;
uint16_t *buffer;
uint16_t *repeat_buffer;
/* end pointer of buffer to ensure enough space for storing ADC data. */
uint16_t *buf_end;
};
/* Driver convenience defines */
#define DRV_CONFIG(dev) ((const struct adc_npcx_config *)(dev)->config)
#define DRV_DATA(dev) ((struct adc_npcx_data *)(dev)->data)
#define HAL_INSTANCE(dev) (struct adc_reg *)(DRV_CONFIG(dev)->base)
/* ADC local functions */
static void adc_npcx_isr(void *arg)
{
struct adc_npcx_data *const data = DRV_DATA((const struct device *)arg);
struct adc_reg *const inst = HAL_INSTANCE((const struct device *)arg);
uint16_t status = inst->ADCSTS;
uint16_t result, channel;
/* Clear status pending bits first */
inst->ADCSTS = status;
LOG_DBG("%s: status is %04X\n", __func__, status);
/* Is end of conversion cycle event? ie. Scan conversion is done. */
if (IS_BIT_SET(status, NPCX_ADCSTS_EOCCEV)) {
/* Stop conversion for scan conversion mode */
inst->ADCCNF |= BIT(NPCX_ADCCNF_STOP);
/* Get result for each ADC selected channel */
while (data->channels) {
channel = find_lsb_set(data->channels) - 1;
result = GET_FIELD(inst->CHNDAT[channel],
NPCX_CHNDAT_CHDAT_FIELD);
/*
* Save ADC result and adc_npcx_validate_buffer_size()
* already ensures that the buffer has enough space for
* storing result.
*/
if (data->buffer < data->buf_end) {
*data->buffer++ = result;
}
data->channels &= ~BIT(channel);
}
/* Turn off ADC and inform sampling is done */
inst->ADCCNF &= ~(BIT(NPCX_ADCCNF_ADCEN));
adc_context_on_sampling_done(&data->ctx, data->adc_dev);
}
}
/*
* Validate the buffer size with adc channels mask. If it is lower than what
* we need return -ENOSPC.
*/
static int adc_npcx_validate_buffer_size(const struct device *dev,
const struct adc_sequence *sequence)
{
uint8_t channels = 0;
uint32_t mask;
size_t needed;
for (mask = BIT(NPCX_ADC_CH_COUNT - 1); mask != 0; mask >>= 1) {
if (mask & sequence->channels) {
channels++;
}
}
needed = channels * sizeof(uint16_t);
if (sequence->options) {
needed *= (1 + sequence->options->extra_samplings);
}
if (sequence->buffer_size < needed) {
return -ENOSPC;
}
return 0;
}
static void adc_npcx_start_scan(const struct device *dev)
{
struct adc_npcx_data *const data = DRV_DATA(dev);
struct adc_reg *const inst = HAL_INSTANCE(dev);
/* Turn on ADC first */
inst->ADCCNF |= BIT(NPCX_ADCCNF_ADCEN);
/* Update selected channels in scan mode by channels mask */
inst->ADCCS = data->channels;
/* Select 'Scan' Conversion mode. */
SET_FIELD(inst->ADCCNF, NPCX_ADCCNF_ADCMD_FIELD,
NPCX_ADC_SCAN_CONVERSION_MODE);
/* Select 'One-Shot' Repetitive mode */
inst->ADCCNF |= BIT(NPCX_ADCCNF_INTECEN);
/* Start conversion */
inst->ADCCNF |= BIT(NPCX_ADCCNF_START);
LOG_DBG("Start ADC scan conversion and ADCCNF,ADCCS are (%04X,%04X)\n",
inst->ADCCNF, inst->ADCCS);
}
static int adc_npcx_start_read(const struct device *dev,
const struct adc_sequence *sequence)
{
struct adc_npcx_data *const data = DRV_DATA(dev);
int error = 0;
if (!sequence->channels ||
(sequence->channels & ~BIT_MASK(NPCX_ADC_CH_COUNT))) {
LOG_ERR("Invalid ADC channels");
return -EINVAL;
}
/* Fixed 10 bit resolution of npcx ADC */
if (sequence->resolution != 10) {
LOG_ERR("Unfixed 10 bit ADC resolution");
return -ENOTSUP;
}
error = adc_npcx_validate_buffer_size(dev, sequence);
if (error) {
LOG_ERR("ADC buffer size too small");
return error;
}
/* Save ADC sequence sampling buffer and its end pointer address */
data->buffer = sequence->buffer;
data->buf_end = data->buffer + sequence->buffer_size / sizeof(uint16_t);
/* Start ADC conversion */
adc_context_start_read(&data->ctx, sequence);
error = adc_context_wait_for_completion(&data->ctx);
return error;
}
/* ADC api functions */
static void adc_context_start_sampling(struct adc_context *ctx)
{
struct adc_npcx_data *const data =
CONTAINER_OF(ctx, struct adc_npcx_data, ctx);
data->repeat_buffer = data->buffer;
data->channels = ctx->sequence.channels;
/* Start ADC scan conversion */
adc_npcx_start_scan(data->adc_dev);
}
static void adc_context_update_buffer_pointer(struct adc_context *ctx,
bool repeat_sampling)
{
struct adc_npcx_data *const data =
CONTAINER_OF(ctx, struct adc_npcx_data, ctx);
if (repeat_sampling) {
data->buffer = data->repeat_buffer;
}
}
static int adc_npcx_channel_setup(const struct device *dev,
const struct adc_channel_cfg *channel_cfg)
{
const struct adc_npcx_config *const config = DRV_CONFIG(dev);
uint8_t channel_id = channel_cfg->channel_id;
if (channel_id >= NPCX_ADC_CH_COUNT) {
LOG_ERR("Invalid channel %d", channel_id);
return -EINVAL;
}
if (channel_cfg->acquisition_time != ADC_ACQ_TIME_DEFAULT) {
LOG_ERR("Unsupported channel acquisition time");
return -ENOTSUP;
}
if (channel_cfg->differential) {
LOG_ERR("Differential channels are not supported");
return -ENOTSUP;
}
if (channel_cfg->gain != ADC_GAIN_1) {
LOG_ERR("Unsupported channel gain %d", channel_cfg->gain);
return -ENOTSUP;
}
if (channel_cfg->reference != ADC_REF_INTERNAL) {
LOG_ERR("Unsupported channel reference");
return -ENOTSUP;
}
/* Configure pin-mux for ADC channel */
npcx_pinctrl_mux_configure(config->alts_list + channel_cfg->channel_id,
1, 1);
LOG_DBG("ADC channel %d, alts(%d,%d)", channel_cfg->channel_id,
config->alts_list[channel_cfg->channel_id].group,
config->alts_list[channel_cfg->channel_id].bit);
return 0;
}
static int adc_npcx_read(const struct device *dev,
const struct adc_sequence *sequence)
{
struct adc_npcx_data *const data = DRV_DATA(dev);
int error;
adc_context_lock(&data->ctx, false, NULL);
error = adc_npcx_start_read(dev, sequence);
adc_context_release(&data->ctx, error);
return error;
}
#if defined(CONFIG_ADC_ASYNC)
static int adc_npcx_read_async(const struct device *dev,
const struct adc_sequence *sequence,
struct k_poll_signal *async)
{
struct adc_npcx_data *const data = DRV_DATA(dev);
int error;
adc_context_lock(&data->ctx, true, async);
error = adc_npcx_start_read(dev, sequence);
adc_context_release(&data->ctx, error);
return error;
}
#endif /* CONFIG_ADC_ASYNC */
/* ADC driver registration */
static const struct adc_driver_api adc_npcx_driver_api = {
.channel_setup = adc_npcx_channel_setup,
.read = adc_npcx_read,
#if defined(CONFIG_ADC_ASYNC)
.read_async = adc_npcx_read_async,
#endif
.ref_internal = NPCX_ADC_VREF_VOL,
};
static int adc_npcx_init(const struct device *dev);
static const struct npcx_alt adc_alts[] = DT_NPCX_ALT_ITEMS_LIST(0);
static const struct adc_npcx_config adc_npcx_cfg_0 = {
.base = DT_INST_REG_ADDR(0),
.clk_cfg = DT_NPCX_CLK_CFG_ITEM(0),
.alts_list = adc_alts,
};
static struct adc_npcx_data adc_npcx_data_0 = {
ADC_CONTEXT_INIT_TIMER(adc_npcx_data_0, ctx),
ADC_CONTEXT_INIT_LOCK(adc_npcx_data_0, ctx),
ADC_CONTEXT_INIT_SYNC(adc_npcx_data_0, ctx),
};
DEVICE_AND_API_INIT(adc_npcx, DT_INST_LABEL(0),
adc_npcx_init,
&adc_npcx_data_0, &adc_npcx_cfg_0,
PRE_KERNEL_1,
CONFIG_KERNEL_INIT_PRIORITY_DEFAULT,
&adc_npcx_driver_api);
static int adc_npcx_init(const struct device *dev)
{
const struct adc_npcx_config *const config = DRV_CONFIG(dev);
struct adc_npcx_data *const data = DRV_DATA(dev);
struct adc_reg *const inst = HAL_INSTANCE(dev);
const struct device *const clk_dev =
device_get_binding(NPCX_CLK_CTRL_NAME);
int prescaler = 0;
/* Save ADC device in data */
data->adc_dev = dev;
/* Turn on device clock first and get source clock freq. */
if (clock_control_on(clk_dev,
(clock_control_subsys_t *)&config->clk_cfg) != 0) {
LOG_ERR("Turn on ADC clock fail.");
return -EIO;
}
if (clock_control_get_rate(clk_dev, (clock_control_subsys_t *)
&config->clk_cfg, &data->input_clk) != 0) {
LOG_ERR("Get ADC clock rate error.");
return -EIO;
}
/* Configure the ADC clock */
prescaler = ceiling_fraction(data->input_clk, NPCX_ADC_CLK);
if (prescaler > 0x40)
prescaler = 0x40;
/* Set Core Clock Division Factor in order to obtain the ADC clock */
SET_FIELD(inst->ATCTL, NPCX_ATCTL_SCLKDIV_FIELD, prescaler - 1);
/* Set regular ADC delay */
SET_FIELD(inst->ATCTL, NPCX_ATCTL_DLY_FIELD, ADC_REGULAR_DLY_VAL);
/* Set ADC speed sequentially */
inst->ADCCNF2 = ADC_REGULAR_ADCCNF2_VAL;
inst->GENDLY = ADC_REGULAR_GENDLY_VAL;
inst->MEAST = ADC_REGULAR_MEAST_VAL;
/* Configure ADC interrupt and enable it */
IRQ_CONNECT(DT_INST_IRQN(0), DT_INST_IRQ(0, priority), adc_npcx_isr,
DEVICE_GET(adc_npcx), 0);
irq_enable(DT_INST_IRQN(0));
/* Initialize mutex of ADC channels */
adc_context_unlock_unconditionally(&data->ctx);
return 0;
}
BUILD_ASSERT(ARRAY_SIZE(adc_alts) == NPCX_ADC_CH_COUNT,
"The number of ADC channels and pin-mux configurations don't match!");

View file

@ -27,6 +27,8 @@
#define DT_DRV_COMPAT nxp_kinetis_adc16 #define DT_DRV_COMPAT nxp_kinetis_adc16
#elif DT_HAS_COMPAT_STATUS_OKAY(st_stm32_adc) #elif DT_HAS_COMPAT_STATUS_OKAY(st_stm32_adc)
#define DT_DRV_COMPAT st_stm32_adc #define DT_DRV_COMPAT st_stm32_adc
#elif DT_HAS_COMPAT_STATUS_OKAY(nuvoton_npcx_adc)
#define DT_DRV_COMPAT nuvoton_npcx_adc
#else #else
#error No known devicetree compatible match for ADC shell #error No known devicetree compatible match for ADC shell
#endif #endif

View file

@ -413,6 +413,27 @@
label = "PWM_7"; label = "PWM_7";
}; };
adc0: adc@400d1000 {
compatible = "nuvoton,npcx-adc";
#io-channel-cells = <1>;
reg = <0x400d1000 0x2000>;
interrupts = <10 0>;
clocks = <&pcc NPCX_CLOCK_BUS_APB1 NPCX_PWDWN_CTL4 4>;
pinctrl-0 = <&alt6_adc0_sl /* ADC0 - PIN45 */
&alt6_adc1_sl /* ADC1 - PIN44 */
&alt6_adc2_sl /* ADC2 - PIN43 */
&alt6_adc3_sl /* ADC3 - PIN42 */
&alt6_adc4_sl /* ADC4 - PIN41 */
&altf_adc5_sl /* ADC5 - PIN37 */
&altf_adc6_sl /* ADC6 - PIN34 */
&altf_adc7_sl /* ADC7 - PINE1 */
&altf_adc8_sl /* ADC8 - PINF1 */
&altf_adc9_sl>; /* ADC9 - PINF0 */
status = "disabled";
label = "ADC_0";
};
espi0: espi@4000a000 { espi0: espi@4000a000 {
compatible = "nuvoton,npcx-espi"; compatible = "nuvoton,npcx-espi";
reg = <0x4000a000 0x2000>; reg = <0x4000a000 0x2000>;

View file

@ -0,0 +1,23 @@
# Copyright (c) 2020 Nuvoton Technology Corporation.
# SPDX-License-Identifier: Apache-2.0
description: Nuvoton, NPCX-ADC node
compatible: "nuvoton,npcx-adc"
include: [adc-controller.yaml]
properties:
reg:
required: true
clocks:
required: true
label:
required: true
pinctrl-0:
type: phandles
required: true
description: configurations of pinmux controllers
io-channel-cells:
- input

View file

@ -357,6 +357,77 @@ struct pwm_reg {
#define NPCX_PWMCTLEX_FCK_SEL_FIELD FIELD(4, 2) #define NPCX_PWMCTLEX_FCK_SEL_FIELD FIELD(4, 2)
#define NPCX_PWMCTLEX_OD_OUT 7 #define NPCX_PWMCTLEX_OD_OUT 7
/*
* Analog-To-Digital Converter (ADC) device registers
*/
struct adc_reg {
/* 0x000: ADC Status */
volatile uint16_t ADCSTS;
/* 0x002: ADC Configuration */
volatile uint16_t ADCCNF;
/* 0x004: ADC Timing Control */
volatile uint16_t ATCTL;
/* 0x006: ADC Single Channel Address */
volatile uint16_t ASCADD;
/* 0x008: ADC Scan Channels Select */
volatile uint16_t ADCCS;
volatile uint8_t reserved1[10];
/* 0x014: Threshold Control 1 */
volatile uint16_t THRCTL1;
/* 0x016: Threshold Control 2 */
volatile uint16_t THRCTL2;
/* 0x018: Threshold Control 3 */
volatile uint16_t THRCTL3;
/* 0x01A: Threshold Status */
volatile uint16_t THRCTS;
volatile uint8_t reserved2[4];
/* 0x020: Internal register 1 for ADC Speed */
volatile uint16_t ADCCNF2;
/* 0x022: Internal register 2 for ADC Speed */
volatile uint16_t GENDLY;
volatile uint8_t reserved3[2];
/* 0x026: Internal register 3 for ADC Speed */
volatile uint16_t MEAST;
volatile uint8_t reserved4[18];
/* 0x03A: Deassertion Threshold Control 1 Word */
volatile uint16_t THR_DCTL1;
/* 0x03C: Deassertion Threshold Control 2 Word */
volatile uint16_t THR_DCTL2;
/* 0x03E: Deassertion Threshold Control 3 Word */
volatile uint16_t THR_DCTL3;
/* 0x040 - 52: Data Buffer of Channel 0 - 9 */
volatile uint16_t CHNDAT[10];
};
/* ADC register fields */
#define NPCX_ATCTL_SCLKDIV_FIELD FIELD(0, 6)
#define NPCX_ATCTL_DLY_FIELD FIELD(8, 3)
#define NPCX_ASCADD_SADDR_FIELD FIELD(0, 5)
#define NPCX_ADCSTS_EOCEV 0
#define NPCX_ADCSTS_EOCCEV 1
#define NPCX_ADCCNF_ADCMD_FIELD FIELD(1, 2)
#define NPCX_ADCCNF_ADCRPTC 3
#define NPCX_ADCCNF_INTECEN 6
#define NPCX_ADCCNF_START 4
#define NPCX_ADCCNF_ADCEN 0
#define NPCX_ADCCNF_STOP 11
#define NPCX_CHNDAT_CHDAT_FIELD FIELD(0, 10)
#define NPCX_CHNDAT_NEW 15
#define NPCX_THRCTL_THEN 15
#define NPCX_THRCTL_L_H 14
#define NPCX_THRCTL_CHNSEL FIELD(10, 4)
#define NPCX_THRCTL_THRVAL FIELD(0, 10)
#define NPCX_THRCTS_ADC_WKEN 15
#define NPCX_THRCTS_THR3_IEN 10
#define NPCX_THRCTS_THR2_IEN 9
#define NPCX_THRCTS_THR1_IEN 8
#define NPCX_THRCTS_ADC_EVENT 7
#define NPCX_THRCTS_THR3_STS 2
#define NPCX_THRCTS_THR2_STS 1
#define NPCX_THRCTS_THR1_STS 0
#define NPCX_THR_DCTL_THRD_EN 15
#define NPCX_THR_DCTL_THR_DVAL FIELD(0, 10)
/* /*
* Enhanced Serial Peripheral Interface (eSPI) device registers * Enhanced Serial Peripheral Interface (eSPI) device registers
*/ */

View file

@ -41,6 +41,15 @@ config PWM_NPCX
help help
Enable support for NPCX PWM driver. Enable support for NPCX PWM driver.
config ADC_NPCX
default y
depends on ADC
help
Enable support for NPCX ADC driver. In NPCX7 series, it includes a
10-bit resolution Analog-to-Digital Converter (ADC). Up to 10 voltage
inputs can be measured and a internal voltage reference (VREF), 2.816V
(typical) is used for measurement.
config ESPI_NPCX config ESPI_NPCX
default y default y
depends on ESPI depends on ESPI

View file

@ -53,6 +53,12 @@ NPCX_REG_OFFSET_CHECK(pwm_reg, PWMCTL, 0x004);
NPCX_REG_OFFSET_CHECK(pwm_reg, DCR, 0x006); NPCX_REG_OFFSET_CHECK(pwm_reg, DCR, 0x006);
NPCX_REG_OFFSET_CHECK(pwm_reg, PWMCTLEX, 0x00c); NPCX_REG_OFFSET_CHECK(pwm_reg, PWMCTLEX, 0x00c);
/* ADC register structure check */
NPCX_REG_SIZE_CHECK(adc_reg, 0x54);
NPCX_REG_OFFSET_CHECK(adc_reg, THRCTL1, 0x014);
NPCX_REG_OFFSET_CHECK(adc_reg, ADCCNF2, 0x020);
NPCX_REG_OFFSET_CHECK(adc_reg, CHNDAT, 0x040);
/* ESPI register structure check */ /* ESPI register structure check */
NPCX_REG_SIZE_CHECK(espi_reg, 0x500); NPCX_REG_SIZE_CHECK(espi_reg, 0x500);
NPCX_REG_OFFSET_CHECK(espi_reg, FLASHCFG, 0x034); NPCX_REG_OFFSET_CHECK(espi_reg, FLASHCFG, 0x034);

View file

@ -231,6 +231,15 @@
#define ADC_1ST_CHANNEL_ID 0 #define ADC_1ST_CHANNEL_ID 0
#define ADC_2ND_CHANNEL_ID 1 #define ADC_2ND_CHANNEL_ID 1
#elif defined(CONFIG_BOARD_NPCX7M6FB_EVB)
#define ADC_DEVICE_NAME DT_LABEL(DT_INST(0, nuvoton_npcx_adc))
#define ADC_RESOLUTION 10
#define ADC_GAIN ADC_GAIN_1
#define ADC_REFERENCE ADC_REF_INTERNAL
#define ADC_ACQUISITION_TIME ADC_ACQ_TIME_DEFAULT
#define ADC_1ST_CHANNEL_ID 0
#define ADC_2ND_CHANNEL_ID 2
#else #else
#error "Unsupported board." #error "Unsupported board."
#endif #endif