drivers: npcx: Drop DRV_CONFIG/DRV_DATA usage

Stop using DRV_CONFIG/DRV_DATA macros and use dev->data and dev->config
instead.

Signed-off-by: Wealian Liao <WHLIAO@nuvoton.com>
diff --git a/drivers/adc/adc_npcx.c b/drivers/adc/adc_npcx.c
index 5dac0c7..f303a31 100644
--- a/drivers/adc/adc_npcx.c
+++ b/drivers/adc/adc_npcx.c
@@ -67,17 +67,15 @@
 };
 
 /* 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)
+#define HAL_INSTANCE(dev) ((struct adc_reg *)((const struct adc_npcx_config *)(dev)->config)->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);
+	const struct device *dev = arg;
+	const struct adc_npcx_config *config = dev->config;
+	struct adc_npcx_data *const data = dev->data;
+	struct adc_reg *const inst = HAL_INSTANCE(dev);
 	uint16_t status = inst->ADCSTS;
 	uint16_t result, channel;
 
@@ -93,9 +91,7 @@
 		/* Get result for each ADC selected channel */
 		while (data->channels) {
 			channel = find_lsb_set(data->channels) - 1;
-			result = GET_FIELD(CHNDAT(DRV_CONFIG((const struct device *)arg)->base,
-						  channel),
-					   NPCX_CHNDAT_CHDAT_FIELD);
+			result = GET_FIELD(CHNDAT(config->base, channel), NPCX_CHNDAT_CHDAT_FIELD);
 			/*
 			 * Save ADC result and adc_npcx_validate_buffer_size()
 			 * already ensures that the buffer has enough space for
@@ -144,7 +140,7 @@
 
 static void adc_npcx_start_scan(const struct device *dev)
 {
-	struct adc_npcx_data *const data = DRV_DATA(dev);
+	struct adc_npcx_data *const data = dev->data;
 	struct adc_reg *const inst = HAL_INSTANCE(dev);
 
 	/* Turn on ADC first */
@@ -170,7 +166,7 @@
 static int adc_npcx_start_read(const struct device *dev,
 					const struct adc_sequence *sequence)
 {
-	struct adc_npcx_data *const data = DRV_DATA(dev);
+	struct adc_npcx_data *const data = dev->data;
 	int error = 0;
 
 	if (!sequence->channels ||
@@ -229,7 +225,7 @@
 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);
+	const struct adc_npcx_config *const config = dev->config;
 	uint8_t channel_id = channel_cfg->channel_id;
 
 	if (channel_id >= NPCX_ADC_CH_COUNT) {
@@ -270,7 +266,7 @@
 static int adc_npcx_read(const struct device *dev,
 			const struct adc_sequence *sequence)
 {
-	struct adc_npcx_data *const data = DRV_DATA(dev);
+	struct adc_npcx_data *const data = dev->data;
 	int error;
 
 	adc_context_lock(&data->ctx, false, NULL);
@@ -285,7 +281,7 @@
 			      const struct adc_sequence *sequence,
 			      struct k_poll_signal *async)
 {
-	struct adc_npcx_data *const data = DRV_DATA(dev);
+	struct adc_npcx_data *const data = dev->data;
 	int error;
 
 	adc_context_lock(&data->ctx, true, async);
@@ -331,8 +327,8 @@
 
 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);
+	const struct adc_npcx_config *const config = dev->config;
+	struct adc_npcx_data *const data = dev->data;
 	struct adc_reg *const inst = HAL_INSTANCE(dev);
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int prescaler = 0, ret;
diff --git a/drivers/bbram/bbram_npcx.c b/drivers/bbram/bbram_npcx.c
index 4aa00dd..ea40157 100644
--- a/drivers/bbram/bbram_npcx.c
+++ b/drivers/bbram/bbram_npcx.c
@@ -27,9 +27,8 @@
 #define NPCX_STATUS_VSBY BIT(1)
 #define NPCX_STATUS_VCC1 BIT(0)
 
-#define DRV_CONFIG(dev) ((const struct bbram_npcx_config *)(dev)->config)
 #define DRV_STATUS(dev)                                                        \
-	(*((volatile uint8_t *)DRV_CONFIG(dev)->status_reg_addr))
+	(*((volatile uint8_t *)((const struct bbram_npcx_config *)(dev)->config)->status_reg_addr))
 
 static int get_bit_and_reset(const struct device *dev, int mask)
 {
@@ -58,7 +57,7 @@
 
 static int bbram_npcx_get_size(const struct device *dev, size_t *size)
 {
-	const struct bbram_npcx_config *config = DRV_CONFIG(dev);
+	const struct bbram_npcx_config *config = dev->config;
 
 	*size = config->size;
 	return 0;
@@ -67,7 +66,7 @@
 static int bbram_npcx_read(const struct device *dev, size_t offset, size_t size,
 			   uint8_t *data)
 {
-	const struct bbram_npcx_config *config = DRV_CONFIG(dev);
+	const struct bbram_npcx_config *config = dev->config;
 
 	if (size < 1 || offset + size > config->size || bbram_npcx_check_invalid(dev)) {
 		return -EFAULT;
@@ -81,7 +80,7 @@
 static int bbram_npcx_write(const struct device *dev, size_t offset, size_t size,
 			    const uint8_t *data)
 {
-	const struct bbram_npcx_config *config = DRV_CONFIG(dev);
+	const struct bbram_npcx_config *config = dev->config;
 
 	if (size < 1 || offset + size > config->size || bbram_npcx_check_invalid(dev)) {
 		return -EFAULT;
diff --git a/drivers/clock_control/clock_control_npcx.c b/drivers/clock_control/clock_control_npcx.c
index 3e27549..b4f8aa7 100644
--- a/drivers/clock_control/clock_control_npcx.c
+++ b/drivers/clock_control/clock_control_npcx.c
@@ -22,14 +22,11 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) \
-	((const struct npcx_pcc_config *)(dev)->config)
-
 #define HAL_CDCG_INST(dev) \
-	((struct cdcg_reg *)DRV_CONFIG(dev)->base_cdcg)
+	((struct cdcg_reg *)((const struct npcx_pcc_config *)(dev)->config)->base_cdcg)
 
 #define HAL_PMC_INST(dev) \
-	((struct pmc_reg *)DRV_CONFIG(dev)->base_pmc)
+	((struct pmc_reg *)((const struct npcx_pcc_config *)(dev)->config)->base_pmc)
 
 /* Clock controller local functions */
 static inline int npcx_clock_control_on(const struct device *dev,
@@ -37,7 +34,7 @@
 {
 	ARG_UNUSED(dev);
 	struct npcx_clk_cfg *clk_cfg = (struct npcx_clk_cfg *)(sub_system);
-	const uint32_t pmc_base = DRV_CONFIG(dev)->base_pmc;
+	const uint32_t pmc_base = ((const struct npcx_pcc_config *)dev->config)->base_pmc;
 
 	if (clk_cfg->ctrl >= NPCX_PWDWN_CTL_COUNT)
 		return -EINVAL;
@@ -52,7 +49,7 @@
 {
 	ARG_UNUSED(dev);
 	struct npcx_clk_cfg *clk_cfg = (struct npcx_clk_cfg *)(sub_system);
-	const uint32_t pmc_base = DRV_CONFIG(dev)->base_pmc;
+	const uint32_t pmc_base = ((const struct npcx_pcc_config *)dev->config)->base_pmc;
 
 	if (clk_cfg->ctrl >= NPCX_PWDWN_CTL_COUNT)
 		return -EINVAL;
@@ -174,7 +171,7 @@
 static int npcx_clock_control_init(const struct device *dev)
 {
 	struct cdcg_reg *const inst_cdcg = HAL_CDCG_INST(dev);
-	const uint32_t pmc_base = DRV_CONFIG(dev)->base_pmc;
+	const uint32_t pmc_base = ((const struct npcx_pcc_config *)dev->config)->base_pmc;
 
 	if (IS_ENABLED(CONFIG_CLOCK_CONTROL_NPCX_EXTERNAL_SRC)) {
 		inst_cdcg->LFCGCTL2 |= BIT(NPCX_LFCGCTL2_XT_OSC_SL_EN);
diff --git a/drivers/espi/espi_npcx.c b/drivers/espi/espi_npcx.c
index 386abf9..20d29c2 100644
--- a/drivers/espi/espi_npcx.c
+++ b/drivers/espi/espi_npcx.c
@@ -42,11 +42,8 @@
 };
 
 /* 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)
+#define HAL_INSTANCE(dev)                                                                          \
+	((struct espi_reg *)((const struct espi_npcx_config *)(dev)->config)->base)
 
 /* eSPI channels */
 #define NPCX_ESPI_CH_PC              0
@@ -208,7 +205,7 @@
 {
 	int chan;
 	struct espi_reg *const inst = HAL_INSTANCE(dev);
-	struct espi_npcx_data *const data = DRV_DATA(dev);
+	struct espi_npcx_data *const data = dev->data;
 	struct espi_event evt = { .evt_type = ESPI_BUS_EVENT_CHANNEL_READY,
 				  .evt_details = 0,
 				  .evt_data = 0 };
@@ -252,7 +249,7 @@
 #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);
+	struct espi_npcx_data *const data = dev->data;
 
 	LOG_DBG("%s", __func__);
 	k_sem_give(&data->oob_rx_lock);
@@ -338,7 +335,7 @@
 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_npcx_data *const data = dev->data;
 	struct espi_event evt = { ESPI_BUS_EVENT_VWIRE_RECEIVED, 0, 0 };
 	uint8_t wire = 0;
 
@@ -381,7 +378,7 @@
 
 static void espi_vw_notify_plt_rst(const struct device *dev)
 {
-	struct espi_npcx_data *const data = DRV_DATA(dev);
+	struct espi_npcx_data *const data = dev->data;
 	struct espi_reg *const inst = HAL_INSTANCE(dev);
 	struct espi_event evt = { ESPI_BUS_EVENT_VWIRE_RECEIVED,
 		ESPI_VWIRE_SIGNAL_PLTRST, 0
@@ -457,7 +454,7 @@
 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_npcx_data *const data = dev->data;
 	struct espi_event evt = { ESPI_BUS_RESET, 0, 0 };
 
 	data->espi_rst_asserted = !IS_BIT_SET(inst->ESPISTS,
@@ -626,7 +623,7 @@
 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);
+	struct espi_npcx_data *const data = dev->data;
 
 	return espi_manage_callback(&data->callbacks, callback, set);
 }
@@ -722,7 +719,7 @@
 				struct espi_oob_packet *pckt)
 {
 	struct espi_reg *const inst = HAL_INSTANCE(dev);
-	struct espi_npcx_data *const data = DRV_DATA(dev);
+	struct espi_npcx_data *const data = dev->data;
 	uint8_t *oob_buf = pckt->buf;
 	uint32_t oob_data;
 	int idx_rx_buf, sz_oob_rx, ret;
@@ -850,8 +847,8 @@
 
 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);
+	const struct espi_npcx_config *const config = dev->config;
+	struct espi_npcx_data *const data = dev->data;
 	struct espi_reg *const inst = HAL_INSTANCE(dev);
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int i, ret;
diff --git a/drivers/gpio/gpio_npcx.c b/drivers/gpio/gpio_npcx.c
index c15fb13..598c2e3 100644
--- a/drivers/gpio/gpio_npcx.c
+++ b/drivers/gpio/gpio_npcx.c
@@ -43,11 +43,8 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct gpio_npcx_config *)(dev)->config)
-
-#define DRV_DATA(dev) ((struct gpio_npcx_data *)(dev)->data)
-
-#define HAL_INSTANCE(dev) ((struct gpio_reg *)DRV_CONFIG(dev)->base)
+#define HAL_INSTANCE(dev)                                                                          \
+	((struct gpio_reg *)((const struct gpio_npcx_config *)(dev)->config)->base)
 
 /* Platform specific GPIO functions */
 const struct device *npcx_get_gpio_dev(int port)
@@ -60,7 +57,7 @@
 
 void npcx_gpio_enable_io_pads(const struct device *dev, int pin)
 {
-	const struct gpio_npcx_config *const config = DRV_CONFIG(dev);
+	const struct gpio_npcx_config *const config = dev->config;
 	const struct npcx_wui *io_wui = &config->wui_maps[pin];
 
 	/*
@@ -74,7 +71,7 @@
 
 void npcx_gpio_disable_io_pads(const struct device *dev, int pin)
 {
-	const struct gpio_npcx_config *const config = DRV_CONFIG(dev);
+	const struct gpio_npcx_config *const config = dev->config;
 	const struct npcx_wui *io_wui = &config->wui_maps[pin];
 
 	/*
@@ -90,7 +87,7 @@
 static int gpio_npcx_config(const struct device *dev,
 			     gpio_pin_t pin, gpio_flags_t flags)
 {
-	const struct gpio_npcx_config *const config = DRV_CONFIG(dev);
+	const struct gpio_npcx_config *const config = dev->config;
 	struct gpio_reg *const inst = HAL_INSTANCE(dev);
 	uint32_t mask = BIT(pin);
 
@@ -214,7 +211,7 @@
 					     enum gpio_int_mode mode,
 					     enum gpio_int_trig trig)
 {
-	const struct gpio_npcx_config *const config = DRV_CONFIG(dev);
+	const struct gpio_npcx_config *const config = dev->config;
 
 	if (config->wui_maps[pin].table == NPCX_MIWU_TABLE_NONE) {
 		LOG_ERR("Cannot configure GPIO(%x, %d)", config->port, pin);
@@ -272,7 +269,7 @@
 static int gpio_npcx_manage_callback(const struct device *dev,
 				      struct gpio_callback *callback, bool set)
 {
-	const struct gpio_npcx_config *const config = DRV_CONFIG(dev);
+	const struct gpio_npcx_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;
 
@@ -311,8 +308,9 @@
 {
 	ARG_UNUSED(dev);
 
-	__ASSERT(DRV_CONFIG(dev)->wui_size == NPCX_GPIO_PORT_PIN_NUM,
-			"wui_maps array size must equal to its pin number");
+	__ASSERT(((const struct gpio_npcx_config *)dev->config)->wui_size ==
+			 NPCX_GPIO_PORT_PIN_NUM,
+		 "wui_maps array size must equal to its pin number");
 	return 0;
 }
 
diff --git a/drivers/i2c/i2c_npcx_controller.c b/drivers/i2c/i2c_npcx_controller.c
index 6a139ac..4c22a81 100644
--- a/drivers/i2c/i2c_npcx_controller.c
+++ b/drivers/i2c/i2c_npcx_controller.c
@@ -150,14 +150,11 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct i2c_ctrl_config *)(dev)->config)
+#define HAL_I2C_INSTANCE(dev)                                                                      \
+	((struct smb_reg *)((const struct i2c_ctrl_config *)(dev)->config)->base)
 
-#define DRV_DATA(dev) ((struct i2c_ctrl_data *)(dev)->data)
-
-#define HAL_I2C_INSTANCE(dev) ((struct smb_reg *)DRV_CONFIG(dev)->base)
-
-#define HAL_I2C_FIFO_INSTANCE(dev) \
-	((struct smb_fifo_reg *)DRV_CONFIG(dev)->base)
+#define HAL_I2C_FIFO_INSTANCE(dev)                                                                 \
+	((struct smb_fifo_reg *)((const struct i2c_ctrl_config *)(dev)->config)->base)
 
 /* Recommended I2C timing values are based on 15 MHz */
 static const struct npcx_i2c_timing_cfg npcx_15m_speed_confs[] = {
@@ -207,7 +204,7 @@
 
 static inline void i2c_ctrl_irq_enable(const struct device *dev, int enable)
 {
-	const struct i2c_ctrl_config *const config = DRV_CONFIG(dev);
+	const struct i2c_ctrl_config *const config = dev->config;
 
 	if (enable) {
 		irq_enable(config->irq);
@@ -338,7 +335,7 @@
 						enum npcx_i2c_freq bus_freq)
 {
 	struct smb_reg *const inst = HAL_I2C_INSTANCE(dev);
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 	const struct npcx_i2c_timing_cfg bus_cfg =
 						data->ptr_speed_confs[bus_freq];
 
@@ -423,7 +420,7 @@
 static int i2c_ctrl_recovery(const struct device *dev)
 {
 	struct smb_fifo_reg *const inst_fifo = HAL_I2C_FIFO_INSTANCE(dev);
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 	int ret;
 
 	if (data->oper_state != NPCX_I2C_ERROR_RECOVERY) {
@@ -471,7 +468,7 @@
 
 static void i2c_ctrl_notify(const struct device *dev, int error)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	data->trans_err = error;
 	k_sem_give(&data->sync_sem);
@@ -479,7 +476,7 @@
 
 static int i2c_ctrl_wait_completion(const struct device *dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	if (k_sem_take(&data->sync_sem, I2C_TRANS_TIMEOUT) == 0) {
 		return data->trans_err;
@@ -490,7 +487,7 @@
 
 size_t i2c_ctrl_calculate_msg_remains(const struct device *dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 	uint8_t *buf_end = data->msg->buf + data->msg->len;
 
 	return (buf_end > data->ptr_msg) ? (buf_end - data->ptr_msg) : 0;
@@ -498,7 +495,7 @@
 
 static void i2c_ctrl_handle_write_int_event(const struct device *dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	/* START condition is issued */
 	if (data->oper_state == NPCX_I2C_WAIT_START) {
@@ -546,7 +543,7 @@
 
 static void i2c_ctrl_handle_read_int_event(const struct device *dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	/* START or RESTART condition is issued */
 	if (data->oper_state == NPCX_I2C_WAIT_START ||
@@ -621,7 +618,7 @@
 static int i2c_ctrl_proc_write_msg(const struct device *dev,
 							struct i2c_msg *msg)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	data->is_write = 1;
 	data->ptr_msg = msg->buf;
@@ -648,7 +645,7 @@
 
 static int i2c_ctrl_proc_read_msg(const struct device *dev, struct i2c_msg *msg)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 
 	data->is_write = 0;
 	data->ptr_msg = msg->buf;
@@ -692,7 +689,7 @@
 static void i2c_ctrl_isr(const struct device *dev)
 {
 	struct smb_fifo_reg *const inst_fifo = HAL_I2C_FIFO_INSTANCE(dev);
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	struct i2c_ctrl_data *const data = dev->data;
 	uint8_t status, tmp;
 
 	status = inst_fifo->SMBST & NPCX_VALID_SMBST_MASK;
@@ -750,21 +747,21 @@
 /* NPCX specific I2C controller functions */
 void npcx_i2c_ctrl_mutex_lock(const struct device *i2c_dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(i2c_dev);
+	struct i2c_ctrl_data *const data = i2c_dev->data;
 
 	k_sem_take(&data->lock_sem, K_FOREVER);
 }
 
 void npcx_i2c_ctrl_mutex_unlock(const struct device *i2c_dev)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(i2c_dev);
+	struct i2c_ctrl_data *const data = i2c_dev->data;
 
 	k_sem_give(&data->lock_sem);
 }
 
 int npcx_i2c_ctrl_configure(const struct device *i2c_dev, uint32_t dev_config)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(i2c_dev);
+	struct i2c_ctrl_data *const data = i2c_dev->data;
 
 	switch (I2C_SPEED_GET(dev_config)) {
 	case I2C_SPEED_STANDARD:
@@ -788,7 +785,7 @@
 
 int npcx_i2c_ctrl_get_speed(const struct device *i2c_dev, uint32_t *speed)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(i2c_dev);
+	struct i2c_ctrl_data *const data = i2c_dev->data;
 
 	if (!data->is_configured) {
 		return -EIO;
@@ -814,7 +811,7 @@
 int npcx_i2c_ctrl_transfer(const struct device *i2c_dev, struct i2c_msg *msgs,
 			      uint8_t num_msgs, uint16_t addr, int port)
 {
-	struct i2c_ctrl_data *const data = DRV_DATA(i2c_dev);
+	struct i2c_ctrl_data *const data = i2c_dev->data;
 	int ret = 0;
 	uint8_t i;
 
@@ -887,8 +884,8 @@
 /* I2C controller driver registration */
 static int i2c_ctrl_init(const struct device *dev)
 {
-	const struct i2c_ctrl_config *const config = DRV_CONFIG(dev);
-	struct i2c_ctrl_data *const data = DRV_DATA(dev);
+	const struct i2c_ctrl_config *const config = dev->config;
+	struct i2c_ctrl_data *const data = dev->data;
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	uint32_t i2c_rate;
 
diff --git a/drivers/i2c/i2c_npcx_port.c b/drivers/i2c/i2c_npcx_port.c
index 340a7d4..8e82b59 100644
--- a/drivers/i2c/i2c_npcx_port.c
+++ b/drivers/i2c/i2c_npcx_port.c
@@ -50,15 +50,11 @@
 	const struct device *i2c_ctrl;
 };
 
-/* Driver convenience defines */
-#define DRV_CONFIG(dev) \
-	((const struct i2c_npcx_port_config *)(dev)->config)
-
 /* I2C api functions */
 static int i2c_npcx_port_configure(const struct device *dev,
 							uint32_t dev_config)
 {
-	const struct i2c_npcx_port_config *const config = DRV_CONFIG(dev);
+	const struct i2c_npcx_port_config *const config = dev->config;
 
 	if (config->i2c_ctrl == NULL) {
 		LOG_ERR("Cannot find i2c controller on port%02x!",
@@ -80,7 +76,7 @@
 
 static int i2c_npcx_port_get_config(const struct device *dev, uint32_t *dev_config)
 {
-	const struct i2c_npcx_port_config *const config = DRV_CONFIG(dev);
+	const struct i2c_npcx_port_config *const config = dev->config;
 	uint32_t speed;
 	int ret;
 
@@ -100,7 +96,7 @@
 static int i2c_npcx_port_transfer(const struct device *dev,
 		struct i2c_msg *msgs, uint8_t num_msgs, uint16_t addr)
 {
-	const struct i2c_npcx_port_config *const config = DRV_CONFIG(dev);
+	const struct i2c_npcx_port_config *const config = dev->config;
 	int ret = 0;
 	int idx_ctrl = (config->port & 0xF0) >> 4;
 	int idx_port = (config->port & 0x0F);
@@ -130,7 +126,7 @@
 /* I2C driver registration */
 static int i2c_npcx_port_init(const struct device *dev)
 {
-	const struct i2c_npcx_port_config *const config = DRV_CONFIG(dev);
+	const struct i2c_npcx_port_config *const config = dev->config;
 	uint32_t i2c_config;
 	int ret;
 
diff --git a/drivers/interrupt_controller/intc_miwu.c b/drivers/interrupt_controller/intc_miwu.c
index c80a0d9..da720b6 100644
--- a/drivers/interrupt_controller/intc_miwu.c
+++ b/drivers/interrupt_controller/intc_miwu.c
@@ -79,10 +79,6 @@
  */
 sys_slist_t cb_list_generic;
 
-/* Driver convenience defines */
-#define DRV_CONFIG(dev) \
-	((const struct intc_miwu_config *)(dev)->config)
-
 BUILD_ASSERT(sizeof(struct miwu_io_callback) == sizeof(struct gpio_callback),
 	"Size of struct miwu_io_callback must equal to struct gpio_callback");
 
@@ -135,7 +131,8 @@
 static void intc_miwu_isr_pri(int wui_table, int wui_group)
 {
 	int wui_bit;
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui_table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui_table]->config;
+	const uint32_t base = config->base;
 	uint8_t mask = NPCX_WKPND(base, wui_group) & NPCX_WKEN(base, wui_group);
 
 	/* Clear pending bits before dispatch ISR */
@@ -158,42 +155,48 @@
 /* Platform specific MIWU functions */
 void npcx_miwu_irq_enable(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 
 	NPCX_WKEN(base, wui->group) |= BIT(wui->bit);
 }
 
 void npcx_miwu_irq_disable(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 
 	NPCX_WKEN(base, wui->group) &= ~BIT(wui->bit);
 }
 
 void npcx_miwu_io_enable(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 
 	NPCX_WKINEN(base, wui->group) |= BIT(wui->bit);
 }
 
 void npcx_miwu_io_disable(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 
 	NPCX_WKINEN(base, wui->group) &= ~BIT(wui->bit);
 }
 
 bool npcx_miwu_irq_get_state(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 
 	return IS_BIT_SET(NPCX_WKEN(base, wui->group), wui->bit);
 }
 
 bool npcx_miwu_irq_get_and_clear_pending(const struct npcx_wui *wui)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 	bool pending = IS_BIT_SET(NPCX_WKPND(base, wui->group), wui->bit);
 
 	if (pending) {
@@ -206,7 +209,8 @@
 int npcx_miwu_interrupt_configure(const struct npcx_wui *wui,
 		enum miwu_int_mode mode, enum miwu_int_trig trig)
 {
-	const uint32_t base = DRV_CONFIG(miwu_devs[wui->table])->base;
+	const struct intc_miwu_config *config = miwu_devs[wui->table]->config;
+	const uint32_t base = config->base;
 	uint8_t pmask = BIT(wui->bit);
 
 	/* Disable interrupt of wake-up input source before configuring it */
@@ -350,7 +354,8 @@
 	static int intc_miwu_init##inst(const struct device *dev)              \
 	{                                                                      \
 		int i;                                                         \
-		const uint32_t base = DRV_CONFIG(dev)->base;                   \
+		const struct intc_miwu_config *config = dev->config;           \
+		const uint32_t base = config->base;                            \
 									       \
 		/* Clear all MIWUs' pending and enable bits of MIWU device */  \
 		for (i = 0; i < NPCX_MIWU_GROUP_COUNT; i++) {                  \
diff --git a/drivers/ps2/ps2_npcx_channel.c b/drivers/ps2/ps2_npcx_channel.c
index 03955bb..00ae916 100644
--- a/drivers/ps2/ps2_npcx_channel.c
+++ b/drivers/ps2/ps2_npcx_channel.c
@@ -35,14 +35,11 @@
 	const struct device *ps2_ctrl;
 };
 
-/* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct ps2_npcx_ch_config *)(dev)->config)
-
 /* PS/2 api functions */
 static int ps2_npcx_ch_configure(const struct device *dev,
 				 ps2_callback_t callback_isr)
 {
-	const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev);
+	const struct ps2_npcx_ch_config *const config = dev->config;
 	int ret;
 
 	ret = ps2_npcx_ctrl_configure(config->ps2_ctrl, config->channel_id,
@@ -56,14 +53,14 @@
 
 static int ps2_npcx_ch_write(const struct device *dev, uint8_t value)
 {
-	const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev);
+	const struct ps2_npcx_ch_config *const config = dev->config;
 
 	return ps2_npcx_ctrl_write(config->ps2_ctrl, config->channel_id, value);
 }
 
 static int ps2_npcx_ch_enable_interface(const struct device *dev)
 {
-	const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev);
+	const struct ps2_npcx_ch_config *const config = dev->config;
 
 	return ps2_npcx_ctrl_enable_interface(config->ps2_ctrl,
 					      config->channel_id, 1);
@@ -71,7 +68,7 @@
 
 static int ps2_npcx_ch_inhibit_interface(const struct device *dev)
 {
-	const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev);
+	const struct ps2_npcx_ch_config *const config = dev->config;
 
 	return ps2_npcx_ctrl_enable_interface(config->ps2_ctrl,
 					      config->channel_id, 0);
@@ -80,7 +77,7 @@
 /* PS/2 driver registration */
 static int ps2_npcx_channel_init(const struct device *dev)
 {
-	const struct ps2_npcx_ch_config *const config = DRV_CONFIG(dev);
+	const struct ps2_npcx_ch_config *const config = dev->config;
 
 	if (!device_is_ready(config->ps2_ctrl)) {
 		LOG_ERR("%s device not ready", config->ps2_ctrl->name);
diff --git a/drivers/ps2/ps2_npcx_controller.c b/drivers/ps2/ps2_npcx_controller.c
index 1823c11..f94bee3 100644
--- a/drivers/ps2/ps2_npcx_controller.c
+++ b/drivers/ps2/ps2_npcx_controller.c
@@ -65,11 +65,8 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct ps2_npcx_ctrl_config *)(dev)->config)
-
-#define DRV_DATA(dev) ((struct ps2_npcx_ctrl_data *)(dev)->data)
-
-#define HAL_PS2_INSTANCE(dev) ((struct ps2_reg *)DRV_CONFIG(dev)->base)
+#define HAL_PS2_INSTANCE(dev)                                                                      \
+	((struct ps2_reg *)((const struct ps2_npcx_ctrl_config *)(dev)->config)->base)
 
 static uint8_t ps2_npcx_ctrl_get_ch_clk_mask(uint8_t channel_id)
 {
@@ -79,7 +76,7 @@
 int ps2_npcx_ctrl_configure(const struct device *dev, uint8_t channel_id,
 			    ps2_callback_t callback_isr)
 {
-	struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev);
+	struct ps2_npcx_ctrl_data *const data = dev->data;
 
 	if (channel_id >= NPCX_PS2_CH_COUNT) {
 		LOG_ERR("unexpected channel ID: %d", channel_id);
@@ -100,7 +97,7 @@
 int ps2_npcx_ctrl_enable_interface(const struct device *dev, uint8_t channel_id,
 				   bool enable)
 {
-	struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev);
+	struct ps2_npcx_ctrl_data *const data = dev->data;
 	struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev);
 	uint8_t ch_clk_mask;
 
@@ -155,7 +152,7 @@
 int ps2_npcx_ctrl_write(const struct device *dev, uint8_t channel_id,
 			uint8_t value)
 {
-	struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev);
+	struct ps2_npcx_ctrl_data *const data = dev->data;
 	struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev);
 	int i = 0;
 
@@ -242,7 +239,7 @@
 {
 	uint8_t active_ch, mask;
 	struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev);
-	struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev);
+	struct ps2_npcx_ctrl_data *const data = dev->data;
 
 	/*
 	 * ACH = 1 : Channel 0
@@ -326,8 +323,8 @@
 
 static int ps2_npcx_ctrl_init(const struct device *dev)
 {
-	const struct ps2_npcx_ctrl_config *const config = DRV_CONFIG(dev);
-	struct ps2_npcx_ctrl_data *const data = DRV_DATA(dev);
+	const struct ps2_npcx_ctrl_config *const config = dev->config;
+	struct ps2_npcx_ctrl_data *const data = dev->data;
 	struct ps2_reg *const inst = HAL_PS2_INSTANCE(dev);
 	const struct device *clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int ret;
diff --git a/drivers/pwm/pwm_npcx.c b/drivers/pwm/pwm_npcx.c
index dd8b1f5..5fae4b5 100644
--- a/drivers/pwm/pwm_npcx.c
+++ b/drivers/pwm/pwm_npcx.c
@@ -52,16 +52,12 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct pwm_npcx_config *)(dev)->config)
-
-#define DRV_DATA(dev) ((struct pwm_npcx_data *)(dev)->data)
-
-#define HAL_INSTANCE(dev) ((struct pwm_reg *)DRV_CONFIG(dev)->base)
+#define HAL_INSTANCE(dev) ((struct pwm_reg *)((const struct pwm_npcx_config *)(dev)->config)->base)
 
 /* PWM local functions */
 static void pwm_npcx_configure(const struct device *dev, int clk_bus)
 {
-	const struct pwm_npcx_config *const config = DRV_CONFIG(dev);
+	const struct pwm_npcx_config *const config = dev->config;
 	struct pwm_reg *const inst = HAL_INSTANCE(dev);
 
 	/* Disable PWM for module configuration first */
@@ -98,7 +94,7 @@
 {
 	/* Single channel for each pwm device */
 	ARG_UNUSED(pwm);
-	struct pwm_npcx_data *const data = DRV_DATA(dev);
+	struct pwm_npcx_data *const data = dev->data;
 	struct pwm_reg *const inst = HAL_INSTANCE(dev);
 	int prescaler;
 
@@ -151,7 +147,7 @@
 {
 	/* Single channel for each pwm device */
 	ARG_UNUSED(pwm);
-	struct pwm_npcx_data *const data = DRV_DATA(dev);
+	struct pwm_npcx_data *const data = dev->data;
 
 	*cycles = data->cycles_per_sec;
 	return 0;
@@ -165,8 +161,8 @@
 
 static int pwm_npcx_init(const struct device *dev)
 {
-	const struct pwm_npcx_config *const config = DRV_CONFIG(dev);
-	struct pwm_npcx_data *const data = DRV_DATA(dev);
+	const struct pwm_npcx_config *const config = dev->config;
+	struct pwm_npcx_data *const data = dev->data;
 	struct pwm_reg *const inst = HAL_INSTANCE(dev);
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int ret;
diff --git a/drivers/sensor/nuvoton_tach_npcx/tach_nuvoton_npcx.c b/drivers/sensor/nuvoton_tach_npcx/tach_nuvoton_npcx.c
index 3cb4fb5..0725572 100644
--- a/drivers/sensor/nuvoton_tach_npcx/tach_nuvoton_npcx.c
+++ b/drivers/sensor/nuvoton_tach_npcx/tach_nuvoton_npcx.c
@@ -75,11 +75,8 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct tach_npcx_config *)(dev)->config)
-
-#define DRV_DATA(dev) ((struct tach_npcx_data *)(dev)->data)
-
-#define HAL_INSTANCE(dev) ((struct tach_reg *)DRV_CONFIG(dev)->base)
+#define HAL_INSTANCE(dev)                                                                          \
+	((struct tach_reg *)((const struct tach_npcx_config *)(dev)->config)->base)
 
 /* Maximum count of prescaler */
 #define NPCX_TACHO_PRSC_MAX 0xff
@@ -94,7 +91,7 @@
 /* TACH inline local functions */
 static inline void tach_npcx_start_port_a(const struct device *dev)
 {
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	struct tach_npcx_data *const data = dev->data;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	/* Set the default value of counter and capture register of timer 1. */
@@ -119,7 +116,7 @@
 static inline void tach_npcx_start_port_b(const struct device *dev)
 {
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	struct tach_npcx_data *const data = dev->data;
 
 	/* Set the default value of counter and capture register of timer 2. */
 	inst->TCNT2 = NPCX_TACHO_CNT_MAX;
@@ -142,7 +139,7 @@
 
 static inline bool tach_npcx_is_underflow(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
+	const struct tach_npcx_config *const config = dev->config;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	LOG_DBG("port A is underflow %d, port b is underflow %d",
@@ -162,7 +159,7 @@
 
 static inline void tach_npcx_clear_underflow_flag(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
+	const struct tach_npcx_config *const config = dev->config;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	if (config->port == NPCX_TACH_PORT_A) {
@@ -174,7 +171,7 @@
 
 static inline bool tach_npcx_is_captured(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
+	const struct tach_npcx_config *const config = dev->config;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	LOG_DBG("port A is captured %d, port b is captured %d",
@@ -194,7 +191,7 @@
 
 static inline void tach_npcx_clear_captured_flag(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
+	const struct tach_npcx_config *const config = dev->config;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	if (config->port == NPCX_TACH_PORT_A) {
@@ -206,7 +203,7 @@
 
 static inline uint16_t tach_npcx_get_captured_count(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
+	const struct tach_npcx_config *const config = dev->config;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	if (config->port == NPCX_TACH_PORT_A) {
@@ -219,8 +216,8 @@
 /* TACH local functions */
 static int tach_npcx_configure(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	const struct tach_npcx_config *const config = dev->config;
+	struct tach_npcx_data *const data = dev->data;
 	struct tach_reg *const inst = HAL_INSTANCE(dev);
 
 	/* Set mode 5 to tachometer module */
@@ -256,7 +253,7 @@
 int tach_npcx_sample_fetch(const struct device *dev, enum sensor_channel chan)
 {
 	ARG_UNUSED(chan);
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	struct tach_npcx_data *const data = dev->data;
 
 	/* Check whether underflow flag of tachometer is occurred */
 	if (tach_npcx_is_underflow(dev)) {
@@ -285,8 +282,8 @@
 				enum sensor_channel chan,
 				struct sensor_value *val)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	const struct tach_npcx_config *const config = dev->config;
+	struct tach_npcx_data *const data = dev->data;
 
 	if (chan != SENSOR_CHAN_RPM) {
 		return -ENOTSUP;
@@ -314,8 +311,8 @@
 /* TACH driver registration */
 static int tach_npcx_init(const struct device *dev)
 {
-	const struct tach_npcx_config *const config = DRV_CONFIG(dev);
-	struct tach_npcx_data *const data = DRV_DATA(dev);
+	const struct tach_npcx_config *const config = dev->config;
+	struct tach_npcx_data *const data = dev->data;
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int ret;
 
diff --git a/drivers/serial/uart_npcx.c b/drivers/serial/uart_npcx.c
index 41cdb20..d1b9572 100644
--- a/drivers/serial/uart_npcx.c
+++ b/drivers/serial/uart_npcx.c
@@ -57,11 +57,8 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct uart_npcx_config *)(dev)->config)
-
-#define DRV_DATA(dev) ((struct uart_npcx_data *)(dev)->data)
-
-#define HAL_INSTANCE(dev) ((struct uart_reg *)DRV_CONFIG(dev)->uconf.base)
+#define HAL_INSTANCE(dev)                                                                          \
+	((struct uart_reg *)((const struct uart_npcx_config *)(dev)->config)->uconf.base)
 
 #if defined(CONFIG_PM) && defined(CONFIG_UART_INTERRUPT_DRIVEN)
 static void uart_npcx_pm_constraint_set(struct uart_npcx_data *data,
@@ -147,7 +144,7 @@
 	while ((size - tx_bytes > 0) && uart_npcx_tx_fifo_ready(dev)) {
 		/* Put a character into Tx FIFO */
 #ifdef CONFIG_PM
-		struct uart_npcx_data *data = DRV_DATA(dev);
+		struct uart_npcx_data *data = dev->data;
 
 		uart_npcx_pm_constraint_set(data, UART_PM_CONSTRAINT_TX_FLAG);
 		inst->UTBUF = tx_data[tx_bytes++];
@@ -249,7 +246,7 @@
 static void uart_npcx_irq_callback_set(const struct device *dev, uart_irq_callback_user_data_t cb,
 				       void *cb_data)
 {
-	struct uart_npcx_data *data = DRV_DATA(dev);
+	struct uart_npcx_data *data = dev->data;
 
 	data->user_cb = cb;
 	data->user_data = cb_data;
@@ -257,7 +254,7 @@
 
 static void uart_npcx_isr(const struct device *dev)
 {
-	struct uart_npcx_data *data = DRV_DATA(dev);
+	struct uart_npcx_data *data = dev->data;
 
 	/*
 	 * Set pm constraint to prevent the system enter suspend state within
@@ -364,7 +361,7 @@
 	 * the CONFIG_UART_CONSOLE_INPUT_EXPIRED_TIMEOUT period.
 	 */
 #ifdef CONFIG_UART_CONSOLE_INPUT_EXPIRED
-	struct uart_npcx_data *data = DRV_DATA(dev);
+	struct uart_npcx_data *data = dev->data;
 	k_timeout_t delay = K_MSEC(CONFIG_UART_CONSOLE_INPUT_EXPIRED_TIMEOUT);
 
 	uart_npcx_pm_constraint_set(data, UART_PM_CONSTRAINT_RX_FLAG);
@@ -413,8 +410,8 @@
 
 static int uart_npcx_init(const struct device *dev)
 {
-	const struct uart_npcx_config *const config = DRV_CONFIG(dev);
-	struct uart_npcx_data *const data = DRV_DATA(dev);
+	const struct uart_npcx_config *const config = dev->config;
+	struct uart_npcx_data *const data = dev->data;
 	struct uart_reg *const inst = HAL_INSTANCE(dev);
 	const struct device *const clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	uint32_t uart_rate;
diff --git a/drivers/spi/spi_npcx_fiu.c b/drivers/spi/spi_npcx_fiu.c
index f1f4675..b10af0c 100644
--- a/drivers/spi/spi_npcx_fiu.c
+++ b/drivers/spi/spi_npcx_fiu.c
@@ -29,9 +29,8 @@
 };
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct npcx_spi_fiu_config *)(dev)->config)
-#define DRV_DATA(dev) ((struct npcx_spi_fiu_data *)(dev)->data)
-#define HAL_INSTANCE(dev) ((struct fiu_reg *)DRV_CONFIG(dev)->base)
+#define HAL_INSTANCE(dev)                                                                          \
+	((struct fiu_reg *)((const struct npcx_spi_fiu_config *)(dev)->config)->base)
 
 static inline void spi_npcx_fiu_cs_level(const struct device *dev, int level)
 {
@@ -50,7 +49,7 @@
 	struct fiu_reg *const inst = HAL_INSTANCE(dev);
 
 #ifdef CONFIG_ASSERT
-	struct npcx_spi_fiu_data *data = DRV_DATA(dev);
+	struct npcx_spi_fiu_data *data = dev->data;
 	struct spi_context *ctx = &data->ctx;
 
 	/* Flash mutex must be held while executing UMA commands */
@@ -70,7 +69,7 @@
 				   const struct spi_buf_set *tx_bufs,
 				   const struct spi_buf_set *rx_bufs)
 {
-	struct npcx_spi_fiu_data *data = DRV_DATA(dev);
+	struct npcx_spi_fiu_data *data = dev->data;
 	struct fiu_reg *const inst = HAL_INSTANCE(dev);
 	struct spi_context *ctx = &data->ctx;
 	size_t cur_xfer_len;
@@ -129,7 +128,7 @@
 int spi_npcx_fiu_release(const struct device *dev,
 			 const struct spi_config *config)
 {
-	struct npcx_spi_fiu_data *data = DRV_DATA(dev);
+	struct npcx_spi_fiu_data *data = dev->data;
 	struct spi_context *ctx = &data->ctx;
 
 	if (!spi_context_configured(ctx, config)) {
@@ -142,7 +141,7 @@
 
 static int spi_npcx_fiu_init(const struct device *dev)
 {
-	const struct npcx_spi_fiu_config *const config = DRV_CONFIG(dev);
+	const struct npcx_spi_fiu_config *const config = dev->config;
 	const struct device *clk_dev = DEVICE_DT_GET(NPCX_CLK_CTRL_NODE);
 	int ret;
 
@@ -160,7 +159,7 @@
 	}
 
 	/* Make sure the context is unlocked */
-	spi_context_unlock_unconditionally(&DRV_DATA(dev)->ctx);
+	spi_context_unlock_unconditionally(&((struct npcx_spi_fiu_data *)dev->data)->ctx);
 
 	return 0;
 }
diff --git a/drivers/watchdog/wdt_npcx.c b/drivers/watchdog/wdt_npcx.c
index 46cb96b..86c245f 100644
--- a/drivers/watchdog/wdt_npcx.c
+++ b/drivers/watchdog/wdt_npcx.c
@@ -82,9 +82,7 @@
 struct miwu_dev_callback miwu_cb;
 
 /* Driver convenience defines */
-#define DRV_CONFIG(dev) ((const struct wdt_npcx_config *)(dev)->config)
-#define DRV_DATA(dev) ((struct wdt_npcx_data *)(dev)->data)
-#define HAL_INSTANCE(dev) ((struct twd_reg *)DRV_CONFIG(dev)->base)
+#define HAL_INSTANCE(dev) ((struct twd_reg *)((const struct wdt_npcx_config *)(dev)->config)->base)
 
 /* WDT local inline functions */
 static inline int wdt_t0out_reload(const struct device *dev)
@@ -133,7 +131,7 @@
 /* WDT local functions */
 static void wdt_t0out_isr(const struct device *dev, struct npcx_wui *wui)
 {
-	struct wdt_npcx_data *const data = DRV_DATA(dev);
+	struct wdt_npcx_data *const data = dev->data;
 	ARG_UNUSED(wui);
 
 	LOG_DBG("WDT reset will issue after %d delay cycle! WUI(%d %d %d)",
@@ -147,7 +145,7 @@
 
 static void wdt_config_t0out_interrupt(const struct device *dev)
 {
-	const struct wdt_npcx_config *const config = DRV_CONFIG(dev);
+	const struct wdt_npcx_config *const config = dev->config;
 
 	/* Initialize a miwu device input and its callback function */
 	npcx_miwu_init_dev_callback(&miwu_cb, &config->t0out, wdt_t0out_isr,
@@ -166,7 +164,7 @@
 static int wdt_npcx_install_timeout(const struct device *dev,
 				   const struct wdt_timeout_cfg *cfg)
 {
-	struct wdt_npcx_data *const data = DRV_DATA(dev);
+	struct wdt_npcx_data *const data = dev->data;
 	struct twd_reg *const inst = HAL_INSTANCE(dev);
 
 	/* If watchdog is already running */
@@ -204,8 +202,8 @@
 static int wdt_npcx_setup(const struct device *dev, uint8_t options)
 {
 	struct twd_reg *const inst = HAL_INSTANCE(dev);
-	const struct wdt_npcx_config *const config = DRV_CONFIG(dev);
-	struct wdt_npcx_data *const data = DRV_DATA(dev);
+	const struct wdt_npcx_config *const config = dev->config;
+	struct wdt_npcx_data *const data = dev->data;
 	int rv;
 
 	/* Disable irq of t0-out expired event first */
@@ -258,8 +256,8 @@
 
 static int wdt_npcx_disable(const struct device *dev)
 {
-	const struct wdt_npcx_config *const config = DRV_CONFIG(dev);
-	struct wdt_npcx_data *const data = DRV_DATA(dev);
+	const struct wdt_npcx_config *const config = dev->config;
+	struct wdt_npcx_data *const data = dev->data;
 	struct twd_reg *const inst = HAL_INSTANCE(dev);
 
 	/*
@@ -289,7 +287,7 @@
 static int wdt_npcx_feed(const struct device *dev, int channel_id)
 {
 	ARG_UNUSED(channel_id);
-	struct wdt_npcx_data *const data = DRV_DATA(dev);
+	struct wdt_npcx_data *const data = dev->data;
 	struct twd_reg *const inst = HAL_INSTANCE(dev);
 
 	/* Feed watchdog by writing 5Ch to WDSDM */