ITE: drivers/usb/device: Add USB Device Controller Support

Add USB Device Driver (usb_dc) of ITE IT82xx2

TEST=west build -p always -b it82xx2_evb
1. zephyr/sample/subsys/usb/hid
2. zephyr/sample/subsys/usb/hid-mouse

Signed-off-by: BJ Chen <bj.chen@ite.com.tw>
diff --git a/boards/riscv/it82xx2_evb/it82xx2_evb.dts b/boards/riscv/it82xx2_evb/it82xx2_evb.dts
index 0f25b5a..e0cbf2e 100644
--- a/boards/riscv/it82xx2_evb/it82xx2_evb.dts
+++ b/boards/riscv/it82xx2_evb/it82xx2_evb.dts
@@ -197,6 +197,13 @@
 	pinctrl-names = "default";
 };
 
+zephyr_udc0: &usb0 {
+	status = "okay";
+	pinctrl-0 = <&usb0_dm_gph5_default
+		     &usb0_dp_gph6_default>;
+	pinctrl-names = "default";
+};
+
 &flash0 {
 	partitions {
 		compatible = "fixed-partitions";
diff --git a/boards/riscv/it82xx2_evb/it82xx2_evb.yaml b/boards/riscv/it82xx2_evb/it82xx2_evb.yaml
index 2446107..45eb445 100644
--- a/boards/riscv/it82xx2_evb/it82xx2_evb.yaml
+++ b/boards/riscv/it82xx2_evb/it82xx2_evb.yaml
@@ -13,6 +13,7 @@
   - adc
   - espi
   - gpio
+  - usb_device
   - i2c
   - kscan
   - pm
diff --git a/drivers/usb/device/CMakeLists.txt b/drivers/usb/device/CMakeLists.txt
index 1ae7a94..534195e 100644
--- a/drivers/usb/device/CMakeLists.txt
+++ b/drivers/usb/device/CMakeLists.txt
@@ -18,5 +18,6 @@
 zephyr_library_sources_ifdef(CONFIG_USB_NRFX         usb_dc_nrfx.c)
 zephyr_library_sources_ifdef(CONFIG_USB_MCUX         usb_dc_mcux.c)
 zephyr_library_sources_ifdef(CONFIG_USB_DC_SMARTBOND usb_dc_smartbond.c)
+zephyr_library_sources_ifdef(CONFIG_USB_DC_IT82XX2   usb_dc_it82xx2.c)
 
 endif()
diff --git a/drivers/usb/device/Kconfig b/drivers/usb/device/Kconfig
index 31d8e1e..2b1adfb 100644
--- a/drivers/usb/device/Kconfig
+++ b/drivers/usb/device/Kconfig
@@ -188,6 +188,13 @@
 
 endif # USB_MCUX
 
+config USB_DC_IT82XX2
+	bool "ITE IT82XX2 USB Device Controller Driver"
+	default y
+	depends on DT_HAS_ITE_IT82XX2_USB_ENABLED
+	help
+	  ITE IT82XX2 USB Device Controller Driver
+
 config USB_NATIVE_POSIX
 	bool "Native Posix USB Device Controller Driver"
 	help
diff --git a/drivers/usb/device/usb_dc_it82xx2.c b/drivers/usb/device/usb_dc_it82xx2.c
new file mode 100644
index 0000000..1d92ce1
--- /dev/null
+++ b/drivers/usb/device/usb_dc_it82xx2.c
@@ -0,0 +1,1672 @@
+/*
+ * Copyright (c) 2023 ITE Technology Corporation.
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+#define DT_DRV_COMPAT ite_it82xx2_usb
+
+#include <zephyr/kernel.h>
+#include <zephyr/usb/usb_device.h>
+#include <zephyr/drivers/pinctrl.h>
+#include <soc.h>
+#include <soc_dt.h>
+#include <string.h>
+#include <zephyr/irq.h>
+#include <zephyr/pm/policy.h>
+#include <zephyr/drivers/interrupt_controller/wuc_ite_it8xxx2.h>
+#include <zephyr/dt-bindings/interrupt-controller/it8xxx2-wuc.h>
+
+#include <zephyr/logging/log.h>
+LOG_MODULE_REGISTER(usb_dc_it82xx2, CONFIG_USB_DRIVER_LOG_LEVEL);
+
+/* USB Device Controller Registers Bits & Constants */
+#define IT8XXX2_USB_IRQ			DT_INST_IRQ_BY_IDX(0, 0, irq)
+#define IT8XXX2_WU90_IRQ		DT_INST_IRQ_BY_IDX(0, 1, irq)
+
+#define MAX_NUM_ENDPOINTS		16
+#define FIFO_NUM			3
+#define SETUP_DATA_CNT			8
+#define DC_ADDR_NULL			0x00
+#define DC_ADDR_MASK			0x7F
+
+/* The related definitions of the register EP STATUS:
+ * 0x41/0x45/0x49/0x4D
+ */
+#define EP_STATUS_ERROR			0x0F
+
+/* The related definitions of the register dc_line_status: 0x51 */
+#define RX_LINE_STATE_MASK		(RX_LINE_FULL_SPD | RX_LINE_LOW_SPD)
+#define RX_LINE_LOW_SPD			0x02
+#define RX_LINE_FULL_SPD		0x01
+#define RX_LINE_RESET			0x00
+
+/* EPN Extend Control 2 Register Mask Definition */
+#define READY_BITS			0x0F
+#define COMPLETED_TRANS			0xF0
+
+/* EP Definitions */
+#define EP_VALID_MASK			0x0F
+#define EP_INVALID_MASK			~(USB_EP_DIR_MASK | EP_VALID_MASK)
+
+/* Bit [1:0] represents the TRANSACTION_TYPE as follows: */
+enum it82xx2_transaction_types {
+	DC_SETUP_TRANS,
+	DC_IN_TRANS,
+	DC_OUTDATA_TRANS,
+	DC_ALL_TRANS
+};
+
+/* The bit definitions of the register EP RX/TX FIFO Control:
+ * EP_RX_FIFO_CONTROL: 0X64/0x84/0xA4/0xC4
+ * EP_TX_FIFO_CONTROL: 0X74/0x94/0xB4/0xD4
+ */
+#define FIFO_FORCE_EMPTY		BIT(0)
+
+/* The bit definitions of the register Host/Device Control: 0XE0 */
+#define RESET_CORE			BIT(1)
+
+/* Bit definitions of the register Port0/Port1 MISC Control: 0XE4/0xE8 */
+#define PULL_DOWN_EN			BIT(4)
+
+/* Bit definitions of the register EPN0N1_EXTEND_CONTROL_REG: 0X98 ~ 0X9D */
+#define EPN1_OUTDATA_SEQ		BIT(4)
+#define EPN0_ISO_ENABLE			BIT(2)
+#define EPN0_SEND_STALL			BIT(1)
+#define EPN0_OUTDATA_SEQ		BIT(0)
+
+/* ENDPOINT[3..0]_STATUS_REG */
+#define DC_STALL_SENT			BIT(5)
+
+/* DC_INTERRUPT_STATUS_REG */
+#define DC_TRANS_DONE			BIT(0)
+#define DC_RESUME_INT			BIT(1)
+#define DC_RESET_EVENT			BIT(2)
+#define DC_SOF_RECEIVED			BIT(3)
+#define DC_NAK_SENT_INT			BIT(4)
+
+/* DC_CONTROL_REG */
+#define DC_GLOBAL_ENABLE		BIT(0)
+#define DC_TX_LINE_STATE_DM		BIT(1)
+#define DC_DIRECT_CONTROL		BIT(3)
+#define DC_FULL_SPEED_LINE_POLARITY	BIT(4)
+#define DC_FULL_SPEED_LINE_RATE		BIT(5)
+#define DC_CONNECT_TO_HOST		BIT(6) /* internal pull-up */
+
+/* ENDPOINT[3..0]_CONTROL_REG */
+#define ENDPOINT_EN			BIT(0)
+#define ENDPOINT_RDY			BIT(1)
+#define EP_OUTDATA_SEQ			BIT(2)
+#define EP_SEND_STALL			BIT(3)
+#define EP_ISO_ENABLE			BIT(4)
+#define EP_DIRECTION			BIT(5)
+
+enum it82xx2_ep_status {
+	EP_INIT,
+	EP_CHECK,
+	EP_CONFIG,
+	EP_CONFIG_IN,
+	EP_CONFIG_OUT,
+};
+
+enum it82xx2_trans_type {
+	SETUP_TOKEN,
+	IN_TOKEN,
+	OUT_TOKEN,
+};
+
+enum it82xx2_setup_stage {
+	INIT_ST,
+	SETUP_ST,
+	DIN_ST,
+	DOUT_ST,
+	STATUS_ST,
+	STALL_SEND,
+};
+
+enum it82xx2_extend_ep_ctrl {
+	/* EPN0N1_EXTEND_CONTROL_REG */
+	EXT_EP_ISO_DISABLE,
+	EXT_EP_ISO_ENABLE,
+	EXT_EP_SEND_STALL,
+	EXT_EP_CLEAR_STALL,
+	EXT_EP_CHECK_STALL,
+	EXT_EP_DATA_SEQ_1,
+	EXT_EP_DATA_SEQ_0,
+	EXT_EP_DATA_SEQ_INV,
+	/* EPN_EXTEND_CONTROL1_REG */
+	EXT_EP_DIR_IN,
+	EXT_EP_DIR_OUT,
+	EXT_EP_ENABLE,
+	EXT_EP_DISABLE,
+	/* EPN_EXTEND_CONTROL2_REG */
+	EXT_EP_READY,
+};
+
+struct usb_it8xxx2_wuc {
+	/* WUC control device structure */
+	const struct device *wucs;
+	/* WUC pin mask */
+	uint8_t mask;
+};
+
+struct usb_it82xx2_config {
+	struct usb_it82xx2_regs *const base;
+	const struct pinctrl_dev_config *pcfg;
+	const struct usb_it8xxx2_wuc *wuc_list;
+};
+
+static const struct usb_it8xxx2_wuc usb_wuc0[IT8XXX2_DT_INST_WUCCTRL_LEN(0)] =
+		IT8XXX2_DT_WUC_ITEMS_LIST(0);
+
+PINCTRL_DT_INST_DEFINE(0);
+
+static const struct usb_it82xx2_config ucfg0 = {
+	.base = (struct usb_it82xx2_regs *)DT_INST_REG_ADDR(0),
+	.pcfg = PINCTRL_DT_INST_DEV_CONFIG_GET(0),
+	.wuc_list = usb_wuc0
+};
+
+struct it82xx2_endpoint_data {
+	usb_dc_ep_callback cb_in;
+	usb_dc_ep_callback cb_out;
+	enum it82xx2_ep_status ep_status;
+	enum usb_dc_ep_transfer_type ep_type;
+	uint16_t remaining; /* remaining bytes */
+	uint16_t mps;
+};
+
+struct usb_it82xx2_data {
+	struct it82xx2_endpoint_data ep_data[MAX_NUM_ENDPOINTS];
+	enum it82xx2_setup_stage st_state; /* Setup State */
+
+	/* EP0 status */
+	enum it82xx2_trans_type last_token;
+
+	/* EP0 status */
+	enum it82xx2_trans_type now_token;
+
+	uint8_t attached;
+	uint8_t addr;
+	bool no_data_ctrl;
+	bool suspended;
+	usb_dc_status_callback usb_status_cb;
+
+	/* Check the EP interrupt status for (ep > 0) */
+	bool ep_ready[3];
+
+	struct k_sem ep_sem[3];
+};
+
+/* Mapped to the bit definitions in the EPN_EXTEND_CONTROL1 Register
+ * (D6h to DDh) for configuring the FIFO direction and for enabling/disabling
+ * the endpoints.
+ */
+static uint8_t ext_ep_bit_shift[12] = {0, 0, 0, 1, 1, 1, 2, 2, 2, 3, 3, 3};
+
+/* The ep_fifo_res[ep_idx % FIFO_NUM] where the FIFO_NUM is 3 represents the
+ * EP mapping because when (ep_idx % FIFO_NUM) is 3, it actually means the EP0.
+ */
+static const uint8_t ep_fifo_res[3] = {3, 1, 2};
+
+/* Mapping the enum it82xx2_extend_ep_ctrl code to their corresponding bit in
+ * the EP45/67/89/1011/1213/1415 Extended Control Registers.
+ */
+static const uint8_t ext_ctrl_tbl[7] = {
+	EPN0_ISO_ENABLE,
+	EPN0_ISO_ENABLE,
+	EPN0_SEND_STALL,
+	EPN0_SEND_STALL,
+	EPN0_SEND_STALL,
+	EPN0_OUTDATA_SEQ,
+	EPN0_OUTDATA_SEQ,
+};
+
+/* Indexing of the following control codes:
+ * EXT_EP_DIR_IN, EXT_EP_DIR_OUT, EXT_EP_ENABLE, EXT_EP_DISABLE
+ */
+static const uint8_t epn_ext_ctrl_tbl[4] = {1, 0, 1, 0};
+
+static struct usb_it82xx2_data udata0;
+
+static struct usb_it82xx2_regs *it82xx2_get_usb_regs(void)
+{
+	const struct device *dev = DEVICE_DT_GET(DT_NODELABEL(usb0));
+	const struct usb_it82xx2_config *cfg = dev->config;
+	struct usb_it82xx2_regs *const usb_regs = cfg->base;
+
+	return usb_regs;
+}
+
+/* WU90 (USB D+) Enable/Disable */
+static void it82xx2_enable_wu90_irq(const struct device *dev, bool enable)
+{
+	const struct usb_it82xx2_config *cfg = dev->config;
+
+	if (enable) {
+		irq_enable(IT8XXX2_WU90_IRQ);
+	} else {
+		irq_disable(IT8XXX2_WU90_IRQ);
+		/* Clear pending interrupt */
+		it8xxx2_wuc_clear_status(cfg->wuc_list[0].wucs,
+					cfg->wuc_list[0].mask);
+	}
+}
+
+static void it82xx2_wu90_isr(const struct device *dev)
+{
+	it82xx2_enable_wu90_irq(dev, false);
+	LOG_DBG("USB D+ (WU90) Triggered");
+}
+
+/* WU90 (USB D+) Initializations */
+static void it8xxx2_usb_dc_wuc_init(const struct device *dev)
+{
+	const struct usb_it82xx2_config *cfg = dev->config;
+
+	/* Initializing the WUI */
+	it8xxx2_wuc_set_polarity(cfg->wuc_list[0].wucs,
+				cfg->wuc_list[0].mask,
+				WUC_TYPE_EDGE_FALLING);
+	it8xxx2_wuc_clear_status(cfg->wuc_list[0].wucs,
+				cfg->wuc_list[0].mask);
+
+	/* Enabling the WUI */
+	it8xxx2_wuc_enable(cfg->wuc_list[0].wucs, cfg->wuc_list[0].mask);
+
+	/* Connect WU90 (USB D+) interrupt but make it disabled initally */
+	IRQ_CONNECT(IT8XXX2_WU90_IRQ, 0, it82xx2_wu90_isr, 0, 0);
+	irq_disable(IT8XXX2_WU90_IRQ);
+
+}
+
+/* Function it82xx2_get_ep_fifo_ctrl_reg_idx(uint8_t ep_idx):
+ *
+ * Calculate the register offset index which determines the corresponding
+ * EP FIFO Ctrl Registers which is defined as ep_fifo_ctrl[reg_idx] here
+ *
+ * The ep_fifo_res[ep_idx % FIFO_NUM] represents the EP mapping because when
+ * (ep_idx % FIFO_NUM) is 3, it actually means the EP0.
+ */
+static uint8_t it82xx2_get_ep_fifo_ctrl_reg_idx(uint8_t ep_idx)
+{
+
+	uint8_t reg_idx = (ep_idx < EP8) ?
+		((ep_fifo_res[ep_idx % FIFO_NUM] - 1) * 2) :
+		((ep_fifo_res[ep_idx % FIFO_NUM] - 1) * 2 + 1);
+
+	return reg_idx;
+}
+
+/* Function it82xx2_get_ep_fifo_ctrl_reg_val(uint8_t ep_idx):
+ *
+ * Calculate the register value written to the ep_fifo_ctrl which is defined as
+ * ep_fifo_ctrl[reg_idx] here for selecting the corresponding control bit.
+ */
+static uint8_t it82xx2_get_ep_fifo_ctrl_reg_val(uint8_t ep_idx)
+{
+	uint8_t reg_val = (ep_idx < EP8) ?
+		(1 << ep_idx) : (1 << (ep_idx - EP8));
+
+	return reg_val;
+}
+
+/*
+ * Functions it82xx2_epn0n1_ext_ctrl_cfg() and epn0n1_ext_ctrl_cfg_seq_inv()
+ * provide the entrance of configuring the EPN0N1 Extended Ctrl Registers.
+ *
+ * The variable set_clr determines if we set/clear the corresponding bit.
+ */
+static void it82xx2_epn0n1_ext_ctrl_cfg(uint8_t reg_idx, uint8_t bit_mask,
+			bool set_clr)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	volatile uint8_t *epn0n1_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_9X].ext_4_15.epn0n1_ext_ctrl;
+
+	(set_clr) ? (epn0n1_ext_ctrl[reg_idx] |= bit_mask) :
+		(epn0n1_ext_ctrl[reg_idx] &= ~(bit_mask));
+}
+
+static void it82xx2_epn0n1_ext_ctrl_cfg_seq_inv(uint8_t reg_idx,
+			uint8_t bit_mask, bool set_clr)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	volatile uint8_t *epn0n1_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_9X].ext_4_15.epn0n1_ext_ctrl;
+
+	bool check = (set_clr) ?
+		(epn0n1_ext_ctrl[reg_idx] & EPN0_OUTDATA_SEQ) :
+		(epn0n1_ext_ctrl[reg_idx] & EPN1_OUTDATA_SEQ);
+
+	(check) ? (epn0n1_ext_ctrl[reg_idx] &= ~(bit_mask)) :
+		(epn0n1_ext_ctrl[reg_idx] |= bit_mask);
+}
+
+/* Return the status of STALL bit in the EPN0N1 Extend Control Registers */
+static bool it82xx2_epn01n1_check_stall(uint8_t reg_idx, uint8_t bit_mask)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	volatile uint8_t *epn0n1_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_9X].ext_4_15.epn0n1_ext_ctrl;
+
+	return !!(epn0n1_ext_ctrl[reg_idx] & bit_mask);
+}
+
+/* Configuring the EPN Extended Ctrl Registers. */
+static void it82xx2_epn_ext_ctrl_cfg1(uint8_t reg_idx, uint8_t bit_mask,
+			bool set_clr)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct epn_ext_ctrl_regs *epn_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_DX].ext_0_3.epn_ext_ctrl;
+
+	(set_clr) ? (epn_ext_ctrl[reg_idx].epn_ext_ctrl1 |= bit_mask) :
+		(epn_ext_ctrl[reg_idx].epn_ext_ctrl1 &= ~(bit_mask));
+}
+
+static void it82xx2_epn_ext_ctrl_cfg2(uint8_t reg_idx, uint8_t bit_mask,
+			bool set_clr)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct epn_ext_ctrl_regs *epn_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_DX].ext_0_3.epn_ext_ctrl;
+
+	(set_clr) ? (epn_ext_ctrl[reg_idx].epn_ext_ctrl2 |= bit_mask) :
+		(epn_ext_ctrl[reg_idx].epn_ext_ctrl2 &= ~(bit_mask));
+}
+
+/* From 98h to 9Dh, the EP45/67/89/1011/1213/1415 Extended Control Registers
+ * are defined, and their bits definitions are as follows:
+ *
+ * Bit    Description
+ *  7     Reserved
+ *  6     EPPOINT5_ISO_ENABLE
+ *  5     EPPOINT5_SEND_STALL
+ *  4     EPPOINT5_OUT_DATA_SEQUENCE
+ *  3     Reserved
+ *  2     EPPOINT4_ISO_ENABLE
+ *  1     EPPOINT4_SEND_STALL
+ *  0     EPPOINT4_OUT_DATA_SEQUENCE
+ *
+ * Apparently, we can tell that the EP4 and EP5 share the same register, and
+ * the EP6 and EP7 share the same one, and the other EPs are defined in the
+ * same way.
+ *
+ * In the function it82xx2_usb_extend_ep_ctrl() we will obtain the mask/flag
+ * according to the bits definitions mentioned above. As for the control code,
+ * please refer to the definition of enum it82xx2_extend_ep_ctrl.
+ */
+static int it82xx2_usb_extend_ep_ctrl(uint8_t ep_idx,
+			enum it82xx2_extend_ep_ctrl ctrl)
+{
+	uint8_t reg_idx, mask;
+	bool flag;
+
+	if (ep_idx < EP4) {
+		return -EINVAL;
+	}
+
+	if ((ctrl >= EXT_EP_DIR_IN) && (ctrl < EXT_EP_READY)) {
+		/* From EXT_EP_DIR_IN to EXT_EP_DISABLE */
+		reg_idx = ep_fifo_res[ep_idx % FIFO_NUM];
+		mask = 1 << (ext_ep_bit_shift[ep_idx - 4] * 2 + 1);
+		flag = epn_ext_ctrl_tbl[ctrl - EXT_EP_DIR_IN];
+		it82xx2_epn_ext_ctrl_cfg1(reg_idx, mask, flag);
+
+	} else if ((ctrl >= EXT_EP_ISO_DISABLE) && (ctrl < EXT_EP_DIR_IN)) {
+		/* From EXT_EP_ISO_DISABLE to EXT_EP_DATA_SEQ_0 */
+		reg_idx = (ep_idx - 4) >> 1;
+		flag = !!(ep_idx & 1);
+		mask = flag ? (ext_ctrl_tbl[ctrl] << 4) : (ext_ctrl_tbl[ctrl]);
+
+		if (ctrl == EXT_EP_CHECK_STALL) {
+			return it82xx2_epn01n1_check_stall(reg_idx, mask);
+		} else if (ctrl == EXT_EP_DATA_SEQ_INV) {
+			it82xx2_epn0n1_ext_ctrl_cfg_seq_inv(
+				reg_idx, mask, flag);
+		} else {
+			it82xx2_epn0n1_ext_ctrl_cfg(reg_idx, mask, flag);
+		}
+	} else if (ctrl == EXT_EP_READY) {
+		reg_idx = (ep_idx - 4) >> 1;
+		mask = 1 << (ext_ep_bit_shift[ep_idx - 4]);
+		it82xx2_epn_ext_ctrl_cfg2(reg_idx, mask, true);
+	} else {
+		LOG_ERR("Invalid Control Code of Endpoint");
+		return -EINVAL;
+	}
+
+	return 0;
+}
+
+static int it82xx2_usb_dc_ip_init(uint8_t p_action)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+
+	if (p_action == 0) {
+		/* Reset Device Controller */
+		usb_regs->host_device_control = RESET_CORE;
+		k_msleep(1);
+		usb_regs->port0_misc_control &= ~(PULL_DOWN_EN);
+		usb_regs->port1_misc_control &= ~(PULL_DOWN_EN);
+		/* clear reset bit */
+		usb_regs->host_device_control = 0;
+	}
+
+	usb_regs->dc_control =
+		DC_GLOBAL_ENABLE | DC_FULL_SPEED_LINE_POLARITY |
+		DC_FULL_SPEED_LINE_RATE | DC_CONNECT_TO_HOST;
+
+	usb_regs->dc_interrupt_status =
+		DC_TRANS_DONE | DC_RESET_EVENT | DC_SOF_RECEIVED;
+
+	usb_regs->dc_interrupt_mask = 0x00;
+	usb_regs->dc_interrupt_mask =
+		DC_TRANS_DONE | DC_RESET_EVENT;
+
+	usb_regs->dc_address = DC_ADDR_NULL;
+
+	return 0;
+}
+
+static int it82xx2_usb_dc_attach_init(void)
+{
+	struct gctrl_it8xxx2_regs *const gctrl_regs = GCTRL_IT8XXX2_REGS_BASE;
+	/*
+	 * Disable USB debug path , prevent CPU enter
+	 * JTAG mode and then reset by USB command.
+	 */
+	gctrl_regs->GCTRL_MCCR &= ~(IT8XXX2_GCTRL_MCCR_USB_EN);
+	gctrl_regs->gctrl_pmer2 |= IT8XXX2_GCTRL_PMER2_USB_PAD_EN;
+
+	/* Disabling WU90 (USB D+) of WUI */
+	irq_disable(IT8XXX2_WU90_IRQ);
+
+	return it82xx2_usb_dc_ip_init(0);
+}
+
+/* Check the condition that SETUP_TOKEN following OUT_TOKEN and return it */
+static bool it82xx2_check_setup_following_out(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	return ((ep_regs[EP0].ep_transtype_sts & DC_ALL_TRANS) == 0 ||
+		(udata0.last_token == IN_TOKEN &&
+		ff_regs[EP0].ep_rx_fifo_dcnt_lsb == SETUP_DATA_CNT));
+}
+
+static int it82xx2_setup_done(uint8_t ep_ctrl, uint8_t idx)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	LOG_DBG("SETUP(%d)", idx);
+	/* wrong trans*/
+	if (ep_ctrl & EP_SEND_STALL) {
+		ep_regs[idx].ep_ctrl &= ~EP_SEND_STALL;
+		udata0.st_state = STALL_SEND;
+		ff_regs[idx].ep_rx_fifo_ctrl = FIFO_FORCE_EMPTY;
+		LOG_DBG("Clear Stall Bit & RX FIFO");
+		return -EINVAL;
+	}
+	/* handle status interrupt */
+	/* status out */
+	if (udata0.st_state == DIN_ST) {
+		LOG_DBG("Status OUT");
+		udata0.last_token = udata0.now_token;
+		udata0.now_token = OUT_TOKEN;
+		udata0.st_state = STATUS_ST;
+		udata0.ep_data[idx].cb_out(idx, USB_DC_EP_DATA_OUT);
+
+	} else if (udata0.st_state == DOUT_ST || udata0.st_state == SETUP_ST) {
+		/* Status IN*/
+		LOG_DBG("Status IN");
+		udata0.last_token = udata0.now_token;
+		udata0.now_token = IN_TOKEN;
+		udata0.st_state = STATUS_ST;
+		udata0.ep_data[idx].cb_in(idx | 0x80, USB_DC_EP_DATA_IN);
+	}
+
+	udata0.last_token = udata0.now_token;
+	udata0.now_token = SETUP_TOKEN;
+	udata0.st_state = SETUP_ST;
+
+	ep_regs[idx].ep_ctrl |= EP_OUTDATA_SEQ;
+	udata0.ep_data[idx].cb_out(USB_EP_DIR_OUT, USB_DC_EP_SETUP);
+
+	/* Set ready bit to no-data control in */
+	if (udata0.no_data_ctrl) {
+		ep_regs[EP0].ep_ctrl |= ENDPOINT_RDY;
+		LOG_DBG("(%d): Set Ready Bit for no-data control", __LINE__);
+
+		udata0.no_data_ctrl = false;
+	}
+
+	return 0;
+}
+
+static int it82xx2_in_done(uint8_t ep_ctrl, uint8_t idx)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	/* stall send check */
+	if (ep_ctrl & EP_SEND_STALL) {
+		ep_regs[EP0].ep_ctrl &= ~EP_SEND_STALL;
+		udata0.st_state = STALL_SEND;
+		LOG_DBG("Clear Stall Bit");
+		return -EINVAL;
+	}
+
+	if (udata0.st_state >= STATUS_ST) {
+		return -EINVAL;
+	}
+
+	LOG_DBG("IN(%d)(%d)", idx, !!(ep_regs[idx].ep_ctrl & EP_OUTDATA_SEQ));
+
+	udata0.last_token = udata0.now_token;
+	udata0.now_token = IN_TOKEN;
+
+	if (udata0.addr != DC_ADDR_NULL &&
+		udata0.addr != usb_regs->dc_address) {
+		usb_regs->dc_address = udata0.addr;
+		LOG_DBG("Address Is Set Successfully");
+	}
+
+	/* set setup stage */
+	if (udata0.st_state == DOUT_ST) {
+		udata0.st_state = STATUS_ST;
+		/* no data status in */
+	} else if (udata0.ep_data[EP0].remaining == 0 &&
+	udata0.st_state == SETUP_ST) {
+		udata0.st_state = STATUS_ST;
+	} else {
+		udata0.st_state = DIN_ST;
+	}
+
+	if (!!(ep_regs[idx].ep_ctrl & EP_OUTDATA_SEQ)) {
+		ep_regs[idx].ep_ctrl &= ~EP_OUTDATA_SEQ;
+	} else {
+		ep_regs[idx].ep_ctrl |= EP_OUTDATA_SEQ;
+	}
+	udata0.ep_data[idx].cb_in(idx | 0x80, USB_DC_EP_DATA_IN);
+
+	/* set ready bit for status out */
+	LOG_DBG("Remaining Bytes: %d, Stage: %d",
+	udata0.ep_data[EP0].remaining, udata0.st_state);
+
+	if (udata0.st_state == DIN_ST && udata0.ep_data[EP0].remaining == 0) {
+		ep_regs[EP0].ep_ctrl |= ENDPOINT_RDY;
+		LOG_DBG("Set EP%d Ready (%d)", idx, __LINE__);
+	}
+
+	return 0;
+}
+
+static int it82xx2_out_done(uint8_t idx)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	/* ep0 wrong enter check */
+	if (udata0.st_state >= STATUS_ST) {
+		return -EINVAL;
+	}
+
+	LOG_DBG("OUT(%d)", idx);
+
+	udata0.last_token = udata0.now_token;
+	udata0.now_token = OUT_TOKEN;
+
+	if (udata0.st_state == SETUP_ST) {
+		udata0.st_state = DOUT_ST;
+	} else {
+		udata0.st_state = STATUS_ST;
+	}
+
+	udata0.ep_data[idx].cb_out(idx, USB_DC_EP_DATA_OUT);
+
+	/* SETUP_TOKEN follow OUT_TOKEN */
+	if (it82xx2_check_setup_following_out()) {
+		LOG_WRN("[%s] OUT => SETUP", __func__);
+		udata0.last_token = udata0.now_token;
+		udata0.now_token = SETUP_TOKEN;
+		udata0.st_state = SETUP_ST;
+		ep_regs[EP0].ep_ctrl |= EP_OUTDATA_SEQ;
+		udata0.ep_data[EP0].cb_out(USB_EP_DIR_OUT, USB_DC_EP_SETUP);
+
+		/* NOTE: set ready bit to no-data control in */
+		if (udata0.no_data_ctrl) {
+			ep_regs[EP0].ep_ctrl |= ENDPOINT_RDY;
+			LOG_DBG("Set Ready Bit for no-data control");
+			udata0.no_data_ctrl = false;
+		}
+	}
+
+	return 0;
+}
+
+/* Functions it82xx2_ep_in_out_config():
+ * Dealing with the ep_ctrl configurations in this subroutine when it's
+ * invoked in the it82xx2_usb_dc_trans_done().
+ */
+static void it82xx2_ep_in_out_config(uint8_t idx)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct epn_ext_ctrl_regs *epn_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_DX].ext_0_3.epn_ext_ctrl;
+
+	uint8_t ep_trans = (epn_ext_ctrl[idx].epn_ext_ctrl2 >> 4) & READY_BITS;
+
+	if (udata0.ep_data[ep_trans].ep_status == EP_CONFIG_IN) {
+		if (ep_trans < 4) {
+			if (!!(ep_regs[idx].ep_ctrl & EP_OUTDATA_SEQ)) {
+				ep_regs[idx].ep_ctrl &= ~EP_OUTDATA_SEQ;
+			} else {
+				ep_regs[idx].ep_ctrl |= EP_OUTDATA_SEQ;
+			}
+		} else {
+			it82xx2_usb_extend_ep_ctrl(ep_trans,
+				EXT_EP_DATA_SEQ_INV);
+		}
+
+		if (udata0.ep_data[ep_trans].cb_in) {
+			udata0.ep_data[ep_trans].cb_in(ep_trans | 0x80,
+				USB_DC_EP_DATA_IN);
+		}
+
+		k_sem_give(&udata0.ep_sem[idx - 1]);
+
+	} else {
+		if (udata0.ep_data[ep_trans].cb_out) {
+			udata0.ep_data[ep_trans].cb_out(ep_trans,
+				USB_DC_EP_DATA_OUT);
+		}
+	}
+}
+
+static void it82xx2_usb_dc_trans_done(uint8_t ep_ctrl, uint8_t ep_trans_type)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct epn_ext_ctrl_regs *epn_ext_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_DX].ext_0_3.epn_ext_ctrl;
+
+	int ret;
+
+	for (uint8_t idx = 0 ; idx < EP4 ; idx++) {
+		ep_ctrl = ep_regs[idx].ep_ctrl;
+
+		/* check ready bit ,will be 0 when trans done */
+		if ((ep_ctrl & ENDPOINT_EN) && !(ep_ctrl & ENDPOINT_RDY)) {
+			if (idx == EP0) {
+				ep_trans_type = ep_regs[idx].ep_transtype_sts &
+					DC_ALL_TRANS;
+
+				/* set up*/
+				if (ep_trans_type == DC_SETUP_TRANS) {
+					ret = it82xx2_setup_done(ep_ctrl, idx);
+
+					if (ret != 0) {
+						continue;
+					}
+				} else if (ep_trans_type == DC_IN_TRANS) {
+					/* in */
+					ret = it82xx2_in_done(ep_ctrl, idx);
+
+					if (ret != 0) {
+						continue;
+					}
+				} else if (ep_trans_type == DC_OUTDATA_TRANS) {
+					/* out */
+					ret = it82xx2_out_done(idx);
+
+					if (ret != 0) {
+						continue;
+					}
+				}
+			} else {
+				/* prevent wrong entry */
+				if (!udata0.ep_ready[idx - 1]) {
+					continue;
+				}
+
+				if ((epn_ext_ctrl[idx].epn_ext_ctrl2 &
+					COMPLETED_TRANS) == 0) {
+					continue;
+				}
+
+				udata0.ep_ready[idx - 1] = false;
+				it82xx2_ep_in_out_config(idx);
+			}
+		}
+	}
+}
+
+static void it82xx2_usb_dc_isr(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+
+	uint8_t status = usb_regs->dc_interrupt_status &
+		usb_regs->dc_interrupt_mask; /* mask non enable int */
+	uint8_t ep_ctrl, ep_trans_type;
+
+	/* reset */
+	if (status & DC_RESET_EVENT) {
+		if ((usb_regs->dc_line_status & RX_LINE_STATE_MASK) ==
+			RX_LINE_RESET) {
+			usb_dc_reset();
+			usb_regs->dc_interrupt_status = DC_RESET_EVENT;
+
+			if (udata0.usb_status_cb) {
+				(*(udata0.usb_status_cb))(USB_DC_RESET, NULL);
+			}
+
+			return;
+
+		} else {
+			usb_regs->dc_interrupt_status = DC_RESET_EVENT;
+		}
+	}
+	/* resume,not test */
+	if (status & DC_RESUME_INT) {
+		udata0.suspended = false;
+		usb_regs->dc_interrupt_mask &= ~DC_RESUME_INT;
+		usb_regs->dc_interrupt_status = DC_RESUME_INT;
+		if (udata0.usb_status_cb) {
+			(*(udata0.usb_status_cb))(USB_DC_RESUME, NULL);
+		}
+
+		return;
+	}
+	/* transaction done */
+	if (status & DC_TRANS_DONE) {
+		/* clear interrupt before new transaction */
+		usb_regs->dc_interrupt_status = DC_TRANS_DONE;
+		it82xx2_usb_dc_trans_done(ep_ctrl, ep_trans_type);
+		return;
+	}
+
+}
+
+/*
+ * USB Device Controller API
+ */
+int usb_dc_attach(void)
+{
+	int ret;
+
+	pm_policy_state_lock_get(PM_STATE_STANDBY, PM_ALL_SUBSTATES);
+
+	if (udata0.attached) {
+		LOG_DBG("Already Attached");
+		return 0;
+	}
+
+	LOG_DBG("Attached");
+	ret = it82xx2_usb_dc_attach_init();
+
+	if (ret) {
+		return ret;
+	}
+
+	for (int idx = 0 ; idx < MAX_NUM_ENDPOINTS ; idx++) {
+		udata0.ep_data[idx].ep_status = EP_INIT;
+	}
+
+	udata0.attached = 1U;
+
+	/* init ep ready status */
+	udata0.ep_ready[0] = false;
+	udata0.ep_ready[1] = false;
+	udata0.ep_ready[2] = false;
+
+	k_sem_init(&udata0.ep_sem[0], 1, 1);
+	k_sem_init(&udata0.ep_sem[1], 1, 1);
+	k_sem_init(&udata0.ep_sem[2], 1, 1);
+
+	/* Connect and enable USB interrupt */
+	IRQ_CONNECT(IT8XXX2_USB_IRQ, 0, it82xx2_usb_dc_isr, 0, 0);
+	irq_enable(IT8XXX2_USB_IRQ);
+
+	return 0;
+}
+
+int usb_dc_detach(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+
+	pm_policy_state_lock_put(PM_STATE_STANDBY, PM_ALL_SUBSTATES);
+
+	if (!udata0.attached) {
+		LOG_DBG("Already Detached");
+		return 0;
+	}
+
+	LOG_DBG("Detached");
+	irq_disable(IT8XXX2_USB_IRQ);
+
+	/* stop pull-up D+ D-*/
+	usb_regs->dc_control &= ~DC_CONNECT_TO_HOST;
+	udata0.attached = 0U;
+
+	/* Enabling WU90 (USB D+) of WUI */
+	irq_enable(IT8XXX2_WU90_IRQ);
+
+	return 0;
+}
+
+int usb_dc_reset(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	int idx;
+
+	LOG_DBG("USB Device Reset");
+
+	ff_regs[EP0].ep_rx_fifo_ctrl = FIFO_FORCE_EMPTY;
+	ff_regs[EP0].ep_tx_fifo_ctrl = FIFO_FORCE_EMPTY;
+
+	for (idx = 1 ; idx < EP4 ; idx++) {
+		if (udata0.ep_data[idx].ep_status > EP_CHECK) {
+			ff_regs[idx].ep_rx_fifo_ctrl = FIFO_FORCE_EMPTY;
+			ff_regs[idx].ep_tx_fifo_ctrl = FIFO_FORCE_EMPTY;
+		}
+	}
+
+	ep_regs[EP0].ep_ctrl = ENDPOINT_EN;
+	usb_regs->dc_address = DC_ADDR_NULL;
+	udata0.addr = DC_ADDR_NULL;
+	usb_regs->dc_interrupt_status = DC_NAK_SENT_INT | DC_SOF_RECEIVED;
+
+	if (udata0.usb_status_cb) {
+		(*(udata0.usb_status_cb))(USB_DC_RESET, NULL);
+	}
+
+	return 0;
+}
+
+int usb_dc_set_address(const uint8_t addr)
+{
+	LOG_DBG("Set Address(0x%02x) to Data", addr);
+	udata0.addr = addr & DC_ADDR_MASK;
+	return 0;
+}
+
+void usb_dc_set_status_callback(const usb_dc_status_callback cb)
+{
+	udata0.usb_status_cb = cb;
+}
+
+int usb_dc_ep_check_cap(const struct usb_dc_ep_cfg_data * const cfg)
+{
+	uint8_t ep_idx = cfg->ep_addr & EP_VALID_MASK;
+	bool in = !!((cfg->ep_addr) & USB_EP_DIR_MASK);
+
+	if ((cfg->ep_addr & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if ((cfg->ep_type == USB_DC_EP_CONTROL) && ep_idx > EP0) {
+		LOG_ERR("Invalid Endpoint Configuration");
+		return -EINVAL;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_WRN("Invalid Endpoint Number 0x%02x", cfg->ep_addr);
+		return -EINVAL;
+	}
+
+	if ((ep_idx != 0) && (!in && ep_idx % FIFO_NUM != 2)) {
+		LOG_WRN("Invalid Endpoint Number 0x%02x", cfg->ep_addr);
+		return -EINVAL;
+	}
+
+	if ((ep_idx != 0) && (in && ep_idx % FIFO_NUM == 2)) {
+		LOG_WRN("Invalid Endpoint Number 0x%02x", cfg->ep_addr);
+		return -EINVAL;
+	}
+
+	if (udata0.ep_data[ep_idx].ep_status > 0) {
+		LOG_WRN("EP%d have been used", ep_idx);
+		return -EINVAL;
+	}
+
+	if (ep_idx > EP0) {
+		udata0.ep_data[ep_idx].mps = cfg->ep_mps;
+	}
+
+	udata0.ep_data[ep_idx].ep_status = EP_CHECK;
+	LOG_DBG("Check cap(%02x)", cfg->ep_addr);
+
+	return 0;
+}
+
+int usb_dc_ep_configure(const struct usb_dc_ep_cfg_data *const cfg)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	volatile uint8_t *ep_fifo_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_BX].fifo_ctrl.ep_fifo_ctrl;
+
+	uint8_t ep_idx = (cfg->ep_addr) & EP_VALID_MASK;
+	uint8_t reg_idx = it82xx2_get_ep_fifo_ctrl_reg_idx(ep_idx);
+	uint8_t reg_val = it82xx2_get_ep_fifo_ctrl_reg_val(ep_idx);
+	bool in = !!((cfg->ep_addr) & USB_EP_DIR_MASK);
+
+	if ((cfg->ep_addr & EP_INVALID_MASK) != 0) {
+		LOG_DBG("Invalid Address");
+		return -EINVAL;
+	}
+
+	if (!udata0.attached || ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_DBG("Not attached / Invalid Endpoint: 0x%X", cfg->ep_addr);
+		return -EINVAL;
+	}
+
+	if (!cfg->ep_mps) {
+		LOG_DBG("Wrong EP or Descriptor");
+		return -EINVAL;
+	}
+
+	udata0.ep_data[ep_idx].ep_status = EP_CONFIG;
+	udata0.ep_data[ep_idx].mps = cfg->ep_mps;
+
+	LOG_DBG("ep_status: %d, mps: %d",
+		udata0.ep_data[ep_idx].ep_status, udata0.ep_data[ep_idx].mps);
+
+	if (!(ep_idx > EP0)) {
+		return 0;
+	}
+
+	if (ep_idx < EP4) {
+		(in) ? (ep_regs[ep_idx].ep_ctrl |= EP_DIRECTION) :
+			(ep_regs[ep_idx].ep_ctrl &= ~EP_DIRECTION);
+
+	} else {
+
+		(in) ? (it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_DIR_IN)) :
+			(it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_DIR_OUT));
+
+		if (in) {
+			it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_DATA_SEQ_0);
+		}
+
+		LOG_DBG("ep_status %d", udata0.ep_data[ep_idx].ep_status);
+	}
+
+	(in) ? (udata0.ep_data[ep_idx].ep_status = EP_CONFIG_IN) :
+		(udata0.ep_data[ep_idx].ep_status = EP_CONFIG_OUT);
+
+	ep_fifo_ctrl[reg_idx] |= reg_val;
+
+	switch (cfg->ep_type) {
+
+	case USB_DC_EP_CONTROL:
+		return -EINVAL;
+
+	case USB_DC_EP_ISOCHRONOUS:
+		if (ep_idx < EP4) {
+			ep_regs[ep_idx].ep_ctrl |= EP_ISO_ENABLE;
+		} else {
+			it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_ISO_ENABLE);
+		}
+
+		break;
+
+	case USB_DC_EP_BULK:
+	case USB_DC_EP_INTERRUPT:
+	default:
+		if (ep_idx < EP4) {
+			ep_regs[ep_idx].ep_ctrl &= ~EP_ISO_ENABLE;
+		} else {
+			it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_ISO_DISABLE);
+		}
+
+		break;
+
+	}
+
+	udata0.ep_data[ep_idx].ep_type = cfg->ep_type;
+
+	LOG_DBG("EP%d Configured: 0x%2X(%d)", ep_idx, !!(in), cfg->ep_type);
+	return 0;
+}
+
+int usb_dc_ep_set_callback(const uint8_t ep, const usb_dc_ep_callback cb)
+{
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (!udata0.attached || ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("(%d)Not attached / Invalid endpoint: EP 0x%x",
+			__LINE__, ep);
+		return -EINVAL;
+	}
+
+	if (cb == NULL) {
+		LOG_ERR("(%d): NO callback function", __LINE__);
+		return -EINVAL;
+	}
+
+	LOG_DBG("EP%d set callback: %d", ep_idx, !!(ep & USB_EP_DIR_IN));
+
+	(ep & USB_EP_DIR_IN) ?
+		(udata0.ep_data[ep_idx].cb_in = cb) :
+		(udata0.ep_data[ep_idx].cb_out = cb);
+
+	return 0;
+}
+
+int usb_dc_ep_enable(const uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		LOG_DBG("Bit[6:4] has something invalid");
+		return -EINVAL;
+	}
+
+	if (!udata0.attached || ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("Not attached / Invalid endpoint: EP 0x%x", ep_idx);
+		return -EINVAL;
+	}
+
+	if (ep_idx < EP4) {
+		LOG_DBG("ep_idx < 4");
+		ep_regs[ep_idx].ep_ctrl |= ENDPOINT_EN;
+		LOG_DBG("EP%d Enbabled %02x", ep_idx, ep_regs[ep_idx].ep_ctrl);
+	} else {
+		LOG_DBG("ep_idx >= 4");
+		it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_ENABLE);
+	}
+
+	return 0;
+}
+
+int usb_dc_ep_disable(uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (!udata0.attached || ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("Not attached / Invalid endpoint: EP 0x%x", ep_idx);
+		return -EINVAL;
+	}
+
+	if (ep_idx < EP4) {
+		ep_regs[ep_idx].ep_ctrl &= ~ENDPOINT_EN;
+	} else {
+		it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_DISABLE);
+	}
+
+	return 0;
+}
+
+
+int usb_dc_ep_set_stall(const uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	struct gctrl_it8xxx2_regs *const gctrl_regs = GCTRL_IT8XXX2_REGS_BASE;
+
+	if (((ep & EP_INVALID_MASK) != 0) || (ep_idx >= MAX_NUM_ENDPOINTS)) {
+		return -EINVAL;
+	}
+
+	if (ep_idx < EP4) {
+		ep_regs[ep_idx].ep_ctrl |= EP_SEND_STALL;
+	} else {
+		it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_SEND_STALL);
+	}
+
+	if (ep_idx == EP0) {
+		ep_regs[EP0].ep_ctrl |= ENDPOINT_RDY;
+		uint32_t idx = 0;
+		/* polling if stall send for 3ms */
+		while (idx < 198 &&
+			!(ep_regs[EP0].ep_status & DC_STALL_SENT)) {
+			/* wait 15.15us */
+			gctrl_regs->GCTRL_WNCKR = 0;
+			idx++;
+		}
+
+		if (idx < 198) {
+			ep_regs[EP0].ep_ctrl &= ~EP_SEND_STALL;
+		}
+
+		udata0.no_data_ctrl = false;
+		udata0.st_state = STALL_SEND;
+	}
+
+	LOG_DBG("EP(%d) ctrl: 0x%02x", ep_idx, ep_regs[ep_idx].ep_ctrl);
+	LOG_DBG("EP(%d) Set Stall", ep_idx);
+
+	return 0;
+}
+
+int usb_dc_ep_clear_stall(const uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		return -EINVAL;
+	}
+
+	ep_regs[ep_idx].ep_ctrl &= ~EP_SEND_STALL;
+	LOG_DBG("EP(%d) clear stall", ep_idx);
+
+	return 0;
+}
+
+int usb_dc_ep_is_stalled(const uint8_t ep, uint8_t *stalled)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((!stalled) || ((ep & EP_INVALID_MASK) != 0) ||
+		(ep_idx >= MAX_NUM_ENDPOINTS)) {
+		return -EINVAL;
+	}
+
+	if (ep_idx < EP4) {
+		*stalled =
+			(0 != (ep_regs[ep_idx].ep_ctrl & EP_SEND_STALL));
+	} else {
+		*stalled = it82xx2_usb_extend_ep_ctrl(ep_idx,
+			EXT_EP_CHECK_STALL);
+	}
+
+	return 0;
+}
+
+int usb_dc_ep_halt(uint8_t ep)
+{
+	return usb_dc_ep_set_stall(ep);
+}
+
+int usb_dc_ep_flush(uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	bool in = !!(ep & USB_EP_DIR_MASK);
+
+	if (((ep & EP_INVALID_MASK) != 0) || (ep_idx >= MAX_NUM_ENDPOINTS)) {
+		return -EINVAL;
+	}
+
+	if (ep_idx > FIFO_NUM) {
+		ep_idx = ep_fifo_res[ep_idx % FIFO_NUM];
+	}
+
+	in ? (ff_regs[ep_idx].ep_tx_fifo_ctrl = FIFO_FORCE_EMPTY) :
+		(ff_regs[ep_idx].ep_rx_fifo_ctrl = FIFO_FORCE_EMPTY);
+
+	return 0;
+}
+
+int usb_dc_ep_write(uint8_t ep, const uint8_t *buf,
+				uint32_t data_len, uint32_t *ret_bytes)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+	volatile uint8_t *ep_fifo_ctrl =
+		usb_regs->fifo_regs[EP_EXT_REGS_BX].fifo_ctrl.ep_fifo_ctrl;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	uint8_t reg_idx = it82xx2_get_ep_fifo_ctrl_reg_idx(ep_idx);
+	uint8_t reg_val = it82xx2_get_ep_fifo_ctrl_reg_val(ep_idx);
+	uint8_t ep_fifo = (ep_idx > EP0) ?
+		(ep_fifo_res[ep_idx % FIFO_NUM]) : 0;
+	uint32_t idx;
+
+	if ((ep & EP_INVALID_MASK) != 0)
+		return -EINVAL;
+
+	/* status IN */
+	if ((ep_idx == EP0) && (data_len == 0) &&
+		(udata0.now_token == SETUP_TOKEN)) {
+		return 0;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		return -EINVAL;
+	}
+
+	/* clear fifo before write*/
+	if (ep_idx == EP0) {
+		ff_regs[ep_idx].ep_tx_fifo_ctrl = FIFO_FORCE_EMPTY;
+	}
+
+	if ((ep_idx == EP0) && (udata0.st_state == SETUP_ST)) {
+		udata0.st_state = DIN_ST;
+	}
+
+	/* select FIFO */
+	if (ep_idx > EP0) {
+
+		k_sem_take(&udata0.ep_sem[ep_fifo-1], K_FOREVER);
+
+		/* select FIFO */
+		ep_fifo_ctrl[reg_idx] |= reg_val;
+	}
+
+	if (data_len > udata0.ep_data[ep_idx].mps) {
+
+		for (idx = 0 ; idx < udata0.ep_data[ep_idx].mps ; idx++) {
+			ff_regs[ep_fifo].ep_tx_fifo_data = buf[idx];
+		}
+
+		*ret_bytes = udata0.ep_data[ep_idx].mps;
+		udata0.ep_data[ep_idx].remaining =
+			data_len - udata0.ep_data[ep_idx].mps;
+
+		LOG_DBG("data_len: %d, Write Max Packets to TX FIFO(%d)",
+			data_len, ep_idx);
+	} else {
+		for (idx = 0 ; idx < data_len ; idx++) {
+			ff_regs[ep_fifo].ep_tx_fifo_data = buf[idx];
+		}
+
+		*ret_bytes = data_len;
+		udata0.ep_data[ep_idx].remaining = 0;
+		LOG_DBG("Write %d Packets to TX FIFO(%d)", data_len, ep_idx);
+	}
+
+	if (ep_idx > FIFO_NUM) {
+		it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_READY);
+	}
+
+	ep_regs[ep_fifo].ep_ctrl |= ENDPOINT_RDY;
+
+	if (ep_fifo > EP0) {
+		udata0.ep_ready[ep_fifo - 1] = true;
+	}
+
+	LOG_DBG("Set EP%d Ready(%d)", ep_idx, __LINE__);
+
+	return 0;
+}
+
+/* Read data from an OUT endpoint */
+int usb_dc_ep_read(uint8_t ep, uint8_t *buf, uint32_t max_data_len,
+			uint32_t *read_bytes)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	uint8_t ep_fifo = 0;
+	uint16_t rx_fifo_len;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (ep_regs[ep_idx].ep_status & EP_STATUS_ERROR) {
+		LOG_WRN("EP Error Flag: 0x%02x", ep_regs[ep_idx].ep_status);
+	}
+
+	if (max_data_len == 0) {
+
+		*read_bytes = 0;
+
+		if (ep_idx > EP0) {
+			ep_regs[ep_idx].ep_ctrl |= ENDPOINT_RDY;
+			LOG_DBG("Set EP%d Ready(%d)", ep_idx, __LINE__);
+		}
+
+		return 0;
+	}
+
+	if (ep_idx > EP0) {
+		ep_fifo = ep_fifo_res[ep_idx % FIFO_NUM];
+	}
+
+	rx_fifo_len = (uint16_t)ff_regs[ep_fifo].ep_rx_fifo_dcnt_lsb +
+		(((uint16_t)ff_regs[ep_fifo].ep_rx_fifo_dcnt_msb) << 8);
+
+	if (ep_idx == 0) {
+	/* if ep0 check trans_type in OUT_TOKEN to
+	 * prevent wrong read_bytes cause memory error
+	 */
+		if (udata0.st_state == STATUS_ST &&
+			(ep_regs[EP0].ep_transtype_sts & DC_ALL_TRANS) == 0) {
+
+			*read_bytes = 0;
+			return 0;
+
+		} else if (udata0.st_state == STATUS_ST) {
+			/* status out but rx_fifo_len not zero */
+			if (rx_fifo_len != 0) {
+				LOG_ERR("Status OUT length not 0 (%d)",
+					rx_fifo_len);
+			}
+			/* rx_fifo_len = 0; */
+			*read_bytes = 0;
+
+			return 0;
+		} else if (rx_fifo_len == 0 &&
+			udata0.now_token == SETUP_TOKEN) {
+			/* RX fifo error workaround */
+
+			/* wrong length(like 7),
+			 * may read wrong packet so clear fifo then return -1
+			 */
+			LOG_ERR("Setup length 0, reset to 8");
+			rx_fifo_len = 8;
+		} else if (rx_fifo_len != 8 &&
+			udata0.now_token == SETUP_TOKEN) {
+			LOG_ERR("Setup length: %d", rx_fifo_len);
+			/* clear rx fifo */
+			ff_regs[EP0].ep_rx_fifo_ctrl = FIFO_FORCE_EMPTY;
+
+			return -EIO;
+		}
+	}
+
+	if (rx_fifo_len > max_data_len) {
+		*read_bytes = max_data_len;
+		for (int idx = 0 ; idx < max_data_len ; idx++) {
+			buf[idx] = ff_regs[ep_fifo].ep_rx_fifo_data;
+		}
+
+		LOG_DBG("Read Max (%d) Packets", max_data_len);
+	} else {
+
+		*read_bytes = rx_fifo_len;
+
+		for (int idx = 0 ; idx < rx_fifo_len ; idx++) {
+			buf[idx] = ff_regs[ep_fifo].ep_rx_fifo_data;
+		}
+
+		if (ep_fifo == 0 &&
+			udata0.now_token == SETUP_TOKEN) {
+			LOG_DBG("RX buf: (%x)(%x)(%x)(%x)(%x)(%x)(%x)(%x)",
+			buf[0], buf[1], buf[2], buf[3],
+			buf[4], buf[5], buf[6], buf[7]);
+		}
+
+		if (ep_fifo > EP0) {
+			ep_regs[ep_fifo].ep_ctrl |= ENDPOINT_RDY;
+			it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_READY);
+			LOG_DBG("(%d): Set EP%d Ready", __LINE__, ep_idx);
+			udata0.ep_ready[ep_fifo - 1] = true;
+		} else if (udata0.now_token == SETUP_TOKEN) {
+
+			if (!(buf[0] & USB_EP_DIR_MASK)) {
+			/* Host to device transfer check */
+				if (buf[6] != 0 || buf[7] != 0) {
+					/* clear tx fifo */
+					ff_regs[EP0].ep_tx_fifo_ctrl =
+					FIFO_FORCE_EMPTY;
+					/* set status IN after data OUT */
+					ep_regs[EP0].ep_ctrl |=
+					ENDPOINT_RDY | EP_OUTDATA_SEQ;
+					LOG_DBG("Set EP%d Ready(%d)",
+						ep_idx, __LINE__);
+				} else {
+					/* no_data_ctrl status */
+
+					/* clear tx fifo */
+					ff_regs[EP0].ep_tx_fifo_ctrl =
+					FIFO_FORCE_EMPTY;
+					udata0.no_data_ctrl = true;
+				}
+			}
+		}
+
+	}
+
+	return 0;
+}
+
+int usb_dc_ep_read_wait(uint8_t ep, uint8_t *buf, uint32_t max_data_len,
+			uint32_t *read_bytes)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+	struct it82xx2_usb_ep_fifo_regs *ff_regs = usb_regs->fifo_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	uint8_t ep_fifo = 0;
+	uint16_t rx_fifo_len;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("(%d): Wrong Endpoint Index/Address", __LINE__);
+		return -EINVAL;
+	}
+	/* Check if OUT ep */
+	if (!!(ep & USB_EP_DIR_MASK)) {
+		LOG_ERR("Wrong Endpoint Direction");
+		return -EINVAL;
+	}
+
+	if (ep_idx > EP0) {
+		ep_fifo = ep_fifo_res[ep_idx % FIFO_NUM];
+	}
+
+	if (ep_regs[ep_fifo].ep_status & EP_STATUS_ERROR) {
+		LOG_WRN("EP error flag(%02x)", ep_regs[ep_fifo].ep_status);
+	}
+
+	rx_fifo_len = (uint16_t)ff_regs[ep_fifo].ep_rx_fifo_dcnt_lsb +
+		(((uint16_t)ff_regs[ep_fifo].ep_rx_fifo_dcnt_msb) << 8);
+
+	LOG_DBG("ep_read_wait (EP: %d), len: %d", ep_idx, rx_fifo_len);
+
+	*read_bytes = (rx_fifo_len > max_data_len) ?
+		max_data_len : rx_fifo_len;
+
+	for (int idx = 0 ; idx < *read_bytes ; idx++) {
+		buf[idx] = ff_regs[ep_fifo].ep_rx_fifo_data;
+	}
+
+	LOG_DBG("Read %d packets", *read_bytes);
+
+	if (ep_idx > EP0) {
+		LOG_DBG("RX buf[0]: 0x%02X", buf[0]);
+	}
+
+	return 0;
+}
+
+int usb_dc_ep_read_continue(uint8_t ep)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+	struct it82xx2_usb_ep_regs *ep_regs = usb_regs->usb_ep_regs;
+
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+	uint8_t ep_fifo = 2;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("(%d): Wrong Endpoint Index/Address", __LINE__);
+		return -EINVAL;
+	}
+
+	/* Check if OUT ep */
+	if (!!(ep & USB_EP_DIR_MASK)) {
+		LOG_ERR("Wrong Endpoint Direction");
+		return -EINVAL;
+	}
+
+	if (ep_idx > EP0) {
+		ep_fifo = ep_fifo_res[ep_idx % FIFO_NUM];
+	}
+
+	it82xx2_usb_extend_ep_ctrl(ep_idx, EXT_EP_READY);
+	ep_regs[ep_fifo].ep_ctrl |= ENDPOINT_RDY;
+	udata0.ep_ready[ep_fifo - 1] = true;
+	LOG_DBG("EP(%d) Read Continue", ep_idx);
+	return 0;
+}
+
+
+int usb_dc_ep_mps(const uint8_t ep)
+{
+	uint8_t ep_idx = ep & EP_VALID_MASK;
+
+	if ((ep & EP_INVALID_MASK) != 0) {
+		return -EINVAL;
+	}
+
+	if (ep_idx >= MAX_NUM_ENDPOINTS) {
+		LOG_ERR("(%d): Wrong Endpoint Index/Address", __LINE__);
+		return -EINVAL;
+	}
+	/* Not configured, return length 0 */
+	if (udata0.ep_data[ep_idx].ep_status < EP_CONFIG) {
+		LOG_WRN("(%d)EP not set", __LINE__);
+		return 0;
+	}
+
+	return udata0.ep_data[ep_idx].mps;
+}
+
+static bool it82xx2_check_suspend(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+
+	if (usb_regs->dc_interrupt_status & DC_SOF_RECEIVED) {
+		usb_regs->dc_interrupt_status =
+			usb_regs->dc_interrupt_status;
+	}
+	/* Check suspend, no SOF in last 3ms */
+	k_msleep(4);
+
+	if (usb_regs->dc_interrupt_status & DC_SOF_RECEIVED) {
+		return false;
+	}
+
+	usb_regs->dc_interrupt_status = DC_SOF_RECEIVED | DC_RESUME_INT;
+	usb_regs->dc_interrupt_mask |= DC_RESUME_INT;
+	udata0.suspended = true;
+
+	if (udata0.usb_status_cb) {
+		(*(udata0.usb_status_cb))(USB_DC_SUSPEND, NULL);
+	}
+
+	return true;
+}
+
+int usb_dc_wakeup_request(void)
+{
+	struct usb_it82xx2_regs *const usb_regs =
+		(struct usb_it82xx2_regs *)it82xx2_get_usb_regs();
+
+	if (udata0.suspended || it82xx2_check_suspend()) {
+
+		usb_regs->dc_control =
+			DC_GLOBAL_ENABLE | DC_FULL_SPEED_LINE_POLARITY |
+			DC_FULL_SPEED_LINE_RATE | DC_DIRECT_CONTROL |
+			DC_TX_LINE_STATE_DM | DC_CONNECT_TO_HOST;
+
+		/* The remote wakeup device must hold the resume signal for */
+		/* at least 1 ms but for no more than 15 ms                 */
+		k_msleep(2);
+
+		usb_regs->dc_control =
+			DC_GLOBAL_ENABLE | DC_FULL_SPEED_LINE_POLARITY |
+			DC_FULL_SPEED_LINE_RATE | DC_CONNECT_TO_HOST;
+
+		if (udata0.suspended) {
+			udata0.suspended = false;
+			irq_disable(IT8XXX2_WU90_IRQ);
+		}
+	}
+	return 0;
+}
+
+static int it82xx2_usb_dc_init(const struct device *dev)
+{
+	const struct usb_it82xx2_config *cfg = dev->config;
+
+	int status = pinctrl_apply_state(cfg->pcfg, PINCTRL_STATE_DEFAULT);
+
+	if (status < 0) {
+		LOG_ERR("Failed to configure USB pins");
+		return status;
+	}
+
+	/* Initializing WU90 (USB D+) */
+	it8xxx2_usb_dc_wuc_init(dev);
+
+	return 0;
+}
+
+DEVICE_DT_INST_DEFINE(0,
+	&it82xx2_usb_dc_init,
+	NULL,
+	&udata0,
+	&ucfg0,
+	POST_KERNEL, CONFIG_KERNEL_INIT_PRIORITY_DEVICE,
+	NULL);
diff --git a/dts/bindings/usb/ite,it82xx2-usb.yaml b/dts/bindings/usb/ite,it82xx2-usb.yaml
new file mode 100644
index 0000000..7c331c4
--- /dev/null
+++ b/dts/bindings/usb/ite,it82xx2-usb.yaml
@@ -0,0 +1,24 @@
+description: |
+    ITE IT82XX2 USB in device mode
+
+compatible: "ite,it82xx2-usb"
+
+include: [base.yaml, pinctrl-device.yaml, usb-ep.yaml]
+
+properties:
+  reg:
+    required: true
+
+  interrupts:
+    required: true
+
+  pinctrl-0:
+    required: true
+
+  pinctrl-names:
+    required: true
+
+  wucctrl:
+    type: phandles
+    description: |
+      usbd node WUC interrupt.
diff --git a/dts/riscv/ite/it82xx2.dtsi b/dts/riscv/ite/it82xx2.dtsi
index 831e077..7d90890 100644
--- a/dts/riscv/ite/it82xx2.dtsi
+++ b/dts/riscv/ite/it82xx2.dtsi
@@ -968,6 +968,19 @@
 			gpios = <&gpiof 0 0>;
 			uart-dev = <&uart2>;
 		};
+
+		usb0: usbd@f02f00 {
+			compatible = "ite,it82xx2-usb";
+			interrupts = <IT8XXX2_IRQ_USB IRQ_TYPE_LEVEL_HIGH
+				      IT8XXX2_IRQ_WU90 IRQ_TYPE_LEVEL_HIGH>;
+			interrupt-parent = <&intc>;
+			wucctrl = <&wuc_wu90>;
+			reg = <0x00f02f00 256>;
+			status = "disabled";
+			num-bidir-endpoints = <1>;
+			num-in-endpoints = <10>;
+			num-out-endpoints = <5>;
+		};
 	};
 };
 
diff --git a/dts/riscv/ite/it8xxx2-pinctrl-map.dtsi b/dts/riscv/ite/it8xxx2-pinctrl-map.dtsi
index 6345a27..6e4ab0e 100644
--- a/dts/riscv/ite/it8xxx2-pinctrl-map.dtsi
+++ b/dts/riscv/ite/it8xxx2-pinctrl-map.dtsi
@@ -390,4 +390,12 @@
 		pinmuxs = <&pinctrlf 1 IT8XXX2_ALT_FUNC_3>;
 	};
 
+	/* USB alternate function */
+	usb0_dm_gph5_default: usb0_dm_gph5_default {
+		pinmuxs = <&pinctrlh 5 IT8XXX2_ALT_DEFAULT>;
+	};
+	usb0_dp_gph6_default: usb0_dp_gph6_default {
+		pinmuxs = <&pinctrlh 6 IT8XXX2_ALT_DEFAULT>;
+	};
+
 };
diff --git a/include/zephyr/dt-bindings/interrupt-controller/ite-intc.h b/include/zephyr/dt-bindings/interrupt-controller/ite-intc.h
index b3003ca..83ad4e5 100644
--- a/include/zephyr/dt-bindings/interrupt-controller/ite-intc.h
+++ b/include/zephyr/dt-bindings/interrupt-controller/ite-intc.h
@@ -30,6 +30,7 @@
 #define IT8XXX2_IRQ_SMB_C       16
 #define IT8XXX2_IRQ_WU24        17
 #define IT8XXX2_IRQ_WU22        21
+#define IT8XXX2_IRQ_USB         23
 /* Group 3 */
 #define IT8XXX2_IRQ_KBC_IBF     24
 #define IT8XXX2_IRQ_PMC1_IBF    25
diff --git a/soc/riscv/riscv-ite/common/check_regs.c b/soc/riscv/riscv-ite/common/check_regs.c
index 03e2425..efa8a37 100644
--- a/soc/riscv/riscv-ite/common/check_regs.c
+++ b/soc/riscv/riscv-ite/common/check_regs.c
@@ -116,11 +116,16 @@
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_SPCTRL1, 0x0d);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_SPCTRL4, 0x1c);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_RSTC5, 0x21);
+IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, gctrl_pmer2, 0x33);
+IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_EPLR, 0x37);
+IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_IVTBAR, 0x41);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_MCCR2, 0x44);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_P80H81HSR, 0x50);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_P80HDR, 0x51);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_H2ROFSR, 0x53);
+IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_RVILMCR0, 0x5D);
 IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_ECHIPID2, 0x86);
+IT8XXX2_REG_OFFSET_CHECK(gctrl_it8xxx2_regs, GCTRL_ECHIPID3, 0x87);
 
 /* PECI register structure check */
 IT8XXX2_REG_SIZE_CHECK(peci_it8xxx2_regs, 0x0F);
@@ -139,6 +144,51 @@
 IT8XXX2_REG_OFFSET_CHECK(peci_it8xxx2_regs, RFCSV, 0x0C);
 IT8XXX2_REG_OFFSET_CHECK(peci_it8xxx2_regs, AWFCSV, 0x0D);
 IT8XXX2_REG_OFFSET_CHECK(peci_it8xxx2_regs, PADCTLR, 0x0E);
+
+/* USB Device register structure check */
+IT8XXX2_REG_SIZE_CHECK(usb_it82xx2_regs, 0xE9);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_ctrl, 0x00);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_trans_type, 0x01);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_line_ctrl, 0x02);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_sof_enable, 0x03);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_addr, 0x04);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_tx_endp, 0x05);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_frame_num_msp, 0x06);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_frame_num_lsp, 0x07);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_interrupt_status, 0x08);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_interrupt_mask, 0x09);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_rx_status, 0x0A);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_rx_pid, 0x0B);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, misc_control, 0x0C);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, misc_status, 0x0D);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_rx_connect_state, 0x0E);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_sof_timer_msb, 0x0F);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, usb_ep_regs[0].ep_ctrl, 0x40);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, usb_ep_regs[0].ep_status, 0x41);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	usb_ep_regs[EP0].ep_transtype_sts, 0x42);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	usb_ep_regs[EP0].ep_nak_transtype_sts, 0x43);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, usb_ep_regs[3].ep_ctrl, 0x4C);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, usb_ep_regs[3].ep_status, 0x4D);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	usb_ep_regs[EP3].ep_transtype_sts, 0x4E);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	usb_ep_regs[EP3].ep_nak_transtype_sts, 0x4F);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, dc_control, 0x50);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, dc_frame_num_lsp, 0x56);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, fifo_regs[0].ep_rx_fifo_data, 0x60);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, fifo_regs[0].ep_tx_fifo_ctrl, 0x74);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	fifo_regs[EP_EXT_REGS_9X].ext_4_15.epn0n1_ext_ctrl, 0x98);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	fifo_regs[EP_EXT_REGS_BX].fifo_ctrl.ep_fifo_ctrl, 0xB8);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs,
+	fifo_regs[EP_EXT_REGS_DX].ext_0_3.epn_ext_ctrl, 0xD6);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, host_device_control, 0xE0);
+IT8XXX2_REG_OFFSET_CHECK(usb_it82xx2_regs, port1_misc_control, 0xE8);
+
+
 /* KSCAN register structure check */
 IT8XXX2_REG_SIZE_CHECK(kscan_it8xxx2_regs, 0x0F);
 IT8XXX2_REG_OFFSET_CHECK(kscan_it8xxx2_regs, KBS_KSOL, 0x00);
diff --git a/soc/riscv/riscv-ite/common/chip_chipregs.h b/soc/riscv/riscv-ite/common/chip_chipregs.h
index df43959..39588f4 100644
--- a/soc/riscv/riscv-ite/common/chip_chipregs.h
+++ b/soc/riscv/riscv-ite/common/chip_chipregs.h
@@ -445,6 +445,295 @@
 };
 #endif /* !__ASSEMBLER__ */
 
+/**
+ *
+ * (2Fxxh) USB Device Controller (USBDC) Registers
+ *
+ */
+#define EP_EXT_REGS_9X        1
+#define EP_EXT_REGS_BX        2
+#define EP_EXT_REGS_DX        3
+
+#ifndef __ASSEMBLER__
+
+/* EP0 to EP15 Enumeration */
+enum usb_dc_endpoints {
+	EP0,
+	EP1,
+	EP2,
+	EP3,
+	EP4,
+	EP5,
+	EP6,
+	EP7,
+	EP8,
+	EP9,
+	EP10,
+	EP11,
+	EP12,
+	EP13,
+	EP14,
+	EP15
+};
+
+struct it82xx2_usb_ep_regs {
+	volatile uint8_t ep_ctrl;
+	volatile uint8_t ep_status;
+	volatile uint8_t ep_transtype_sts;
+	volatile uint8_t ep_nak_transtype_sts;
+};
+
+/* Reserved EP Extended Registers */
+struct ep_ext_regs_7x {
+	/* 0x75 Reserved */
+	volatile uint8_t ep_ext_ctrl_75;
+	/* 0x76 Reserved */
+	volatile uint8_t ep_ext_ctrl_76;
+	/* 0x77 Reserved */
+	volatile uint8_t ep_ext_ctrl_77;
+	/* 0x78 Reserved */
+	volatile uint8_t ep_ext_ctrl_78;
+	/* 0x79 Reserved */
+	volatile uint8_t ep_ext_ctrl_79;
+	/* 0x7A Reserved */
+	volatile uint8_t ep_ext_ctrl_7a;
+	/* 0x7B Reserved */
+	volatile uint8_t ep_ext_ctrl_7b;
+	/* 0x7C Reserved */
+	volatile uint8_t ep_ext_ctrl_7c;
+	/* 0x7D Reserved */
+	volatile uint8_t ep_ext_ctrl_7d;
+	/* 0x7E Reserved */
+	volatile uint8_t ep_ext_ctrl_7e;
+	/* 0x7F Reserved */
+	volatile uint8_t ep_ext_ctrl_7f;
+};
+
+/* From 98h to 9Dh, the EP45/67/89/1011/1213/1415 Extended Control Registers
+ * are defined, and their bits definitions are as follows:
+ *
+ * Bit    Description
+ *  7     Reserved
+ *  6     EPPOINT5_ISO_ENABLE
+ *  5     EPPOINT5_SEND_STALL
+ *  4     EPPOINT5_OUT_DATA_SEQUENCE
+ *  3     Reserved
+ *  2     EPPOINT4_ISO_ENABLE
+ *  1     EPPOINT4_SEND_STALL
+ *  0     EPPOINT4_OUT_DATA_SEQUENCE
+ *
+ * Apparently, we can tell that the EP4 and EP5 share the same register, and
+ * the EP6 and EP7 share the same one, and the rest EPs are defined in the
+ * same way.
+ */
+struct ep_ext_regs_9x {
+	/* 0x95 Reserved */
+	volatile uint8_t ep_ext_ctrl_95;
+	/* 0x96 Reserved */
+	volatile uint8_t ep_ext_ctrl_96;
+	/* 0x97 Reserved */
+	volatile uint8_t ep_ext_ctrl_97;
+	/* 0x98 ~ 0x9D EP45/67/89/1011/1213/1415 Extended Control Registers */
+	volatile uint8_t epn0n1_ext_ctrl[6];
+	/* 0x9E Reserved */
+	volatile uint8_t ep_ext_ctrl_9e;
+	/* 0x9F Reserved */
+	volatile uint8_t ep_ext_ctrl_9f;
+};
+
+/* From BXh to BDh are EP FIFO 1-3 Control 0/1 Registers, and their
+ * definitions as as follows:
+ * B8h: EP_FIFO1_CONTROL0_REG
+ * B9h: EP_FIFO1_CONTROL1_REG
+ * BAh: EP_FIFO2_CONTROL0_REG
+ * BBh: EP_FIFO2_CONTROL1_REG
+ * BCh: EP_FIFO3_CONTROL0_REG
+ * BDh: EP_FIFO3_CONTROL1_REG
+ *
+ * For each one, its bits definitions are as follows:
+ * (take EP_FIFO1_CONTROL1_REG as example, which controls from EP8 to EP15)
+ *
+ * Bit  Description
+ *
+ *  7   EP15 select FIFO1 as data buffer
+ *  6   EP14 select FIFO1 as data buffer
+ *  5   EP13 select FIFO1 as data buffer
+ *  4   EP12 select FIFO1 as data buffer
+ *  3   EP11 select FIFO1 as data buffer
+ *  2   EP10 select FIFO1 as data buffer
+ *  1   EP9 select FIFO1 as data buffer
+ *  0   EP8 select FIFO1 as data buffer
+ *
+ *  1: Select
+ *  0: Not select
+ */
+struct ep_ext_regs_bx {
+	/* 0xB5 Reserved */
+	volatile uint8_t ep_ext_ctrl_b5;
+	/* 0xB6 Reserved */
+	volatile uint8_t ep_ext_ctrl_b6;
+	/* 0xB7 Reserved */
+	volatile uint8_t ep_ext_ctrl_b7;
+	/* 0xB8 ~ 0xBD EP FIFO 1-3 Control 0/1 Registers */
+	volatile uint8_t ep_fifo_ctrl[6];
+	/* 0xBE Reserved */
+	volatile uint8_t ep_ext_ctrl_be;
+	/* 0xBF Reserved */
+	volatile uint8_t ep_ext_ctrl_bf;
+};
+
+
+/* From D6h to DDh are EP Extended Control Registers, and their
+ * definitions as as follows:
+ * D6h: EP0_EXT_CTRL1
+ * D7h: EP0_EXT_CTRL2
+ * D8h: EP1_EXT_CTRL1
+ * D9h: EP1_EXT_CTRL2
+ * DAh: EP2_EXT_CTRL1
+ * DBh: EP2_EXT_CTRL2
+ * DCh: EP3_EXT_CTRL1
+ * DDh: EP3_EXT_CTRL2
+ *
+ * We classify them into 4 groups which each of them contains Control 1 and 2
+ * according to the EP number as follows:
+ */
+struct epn_ext_ctrl_regs {
+	/* 0xD6/0xD8/0xDA/0xDC EPN Extended Control1 Register */
+	volatile uint8_t epn_ext_ctrl1;
+	/* 0xD7/0xD9/0xDB/0xDD EPB Extended Control2 Register */
+	volatile uint8_t epn_ext_ctrl2;
+};
+
+struct ep_ext_regs_dx {
+	/* 0xD5 Reserved */
+	volatile uint8_t ep_ext_ctrl_d5;
+	/* 0xD6 ~ 0xDD EPN Extended Control 1/2 Registers */
+	struct epn_ext_ctrl_regs epn_ext_ctrl[4];
+	/* 0xDE Reserved */
+	volatile uint8_t ep_ext_ctrl_de;
+	/* 0xDF Reserved */
+	volatile uint8_t ep_ext_ctrl_df;
+};
+
+
+/* The USB EPx FIFO Registers Definitions
+ * EP0: 60h ~ 74h
+ * EP1: 80h ~ 94h
+ * EP2: A0h ~ B4h
+ * EP3: C0h ~ D4h (D6h to DDh will be defined as marcos for usage)
+ */
+struct it82xx2_usb_ep_fifo_regs {
+	/* 0x60 + ep * 0x20 : EP RX FIFO Data Register  */
+	volatile uint8_t ep_rx_fifo_data;
+	/* 0x61 + ep * 0x20 : EP RX FIFO DMA Count Register */
+	volatile uint8_t ep_rx_fifo_dma_count;
+	/* 0x62 + ep * 0x20 : EP RX FIFO Data Count MSB */
+	volatile uint8_t ep_rx_fifo_dcnt_msb;
+	/* 0x63 + ep * 0x20 : EP RX FIFO Data Count LSB */
+	volatile uint8_t ep_rx_fifo_dcnt_lsb;
+	/* 0x64 + ep * 0x20  : EP RX FIFO Control Register */
+	volatile uint8_t ep_rx_fifo_ctrl;
+	/* (0x65 ~ 0x6F) + ep * 0x20 */
+	volatile uint8_t reserved_65_6f_add_20[11];
+	/* 0x70 + ep * 0x20 : EP TX FIFO Data Register  */
+	volatile uint8_t ep_tx_fifo_data;
+	/* (0x71 ~ 0x73) + ep * 0x20 */
+	volatile uint8_t reserved_71_73_add_20[3];
+	/* 0x74 + ep * 0x20 : EP TX FIFO Control Register */
+	volatile uint8_t ep_tx_fifo_ctrl;
+	/* (0x75 ~ 0x7F) + ep * 0x20 */
+	union {
+		struct ep_ext_regs_7x ep_res;
+		struct ep_ext_regs_9x ext_4_15;
+		struct ep_ext_regs_bx fifo_ctrl;
+		struct ep_ext_regs_dx ext_0_3;
+	};
+
+};
+
+struct usb_it82xx2_regs {
+	/* 0x00:  Host TX Contrl Register */
+	volatile uint8_t host_tx_ctrl;
+	/* 0x01:  Host TX Transaction Type Register */
+	volatile uint8_t host_tx_trans_type;
+	/* 0x02:  Host TX Line Control Register */
+	volatile uint8_t host_tx_line_ctrl;
+	/* 0x03:  Host TX SOF Enable Register */
+	volatile uint8_t host_tx_sof_enable;
+	/* 0x04:  Host TX Address Register */
+	volatile uint8_t host_tx_addr;
+	/* 0x05:  Host TX EP Number Register */
+	volatile uint8_t host_tx_endp;
+	/* 0x06:  Host Frame Number MSP Register */
+	volatile uint8_t host_frame_num_msp;
+	/* 0x07:  Host Frame Number LSP Register */
+	volatile uint8_t host_frame_num_lsp;
+	/* 0x08:  Host Interrupt Status Register */
+	volatile uint8_t host_interrupt_status;
+	/* 0x09:  Host Interrupt Mask Register */
+	volatile uint8_t host_interrupt_mask;
+	/* 0x0A:  Host RX Status Register */
+	volatile uint8_t host_rx_status;
+	/* 0x0B:  Host RX PID Register */
+	volatile uint8_t host_rx_pid;
+	/* 0x0C:  MISC Control Register */
+	volatile uint8_t misc_control;
+	/* 0x0D:  MISC Status Register */
+	volatile uint8_t misc_status;
+	/* 0x0E:  Host RX Connect State Register */
+	volatile uint8_t host_rx_connect_state;
+	/* 0x0F:  Host SOF Timer MSB Register */
+	volatile uint8_t host_sof_timer_msb;
+	/* 0x10 ~ 0x1F:  Reserved Registers 10h - 1Fh */
+	volatile uint8_t reserved_10_1f[16];
+	/* 0x20:  Host RX FIFO Data Port Register */
+	volatile uint8_t host_rx_fifo_data;
+	/* 0x21:  Host RX FIFO DMA Input Data Count Register */
+	volatile uint8_t host_rx_fifo_dma_data_count;
+	/* 0x22:  Host TX FIFO Data Count MSB Register */
+	volatile uint8_t host_rx_fifo_data_count_msb;
+	/* 0x23:  Host TX FIFO Data Count LSB Register */
+	volatile uint8_t host_rx_fifo_data_count_lsb;
+	/* 0x24:  Host RX FIFO Data Port Register */
+	volatile uint8_t host_rx_fifo_control;
+	/* 0x25 ~ 0x2F:  Reserved Registers 25h - 2Fh */
+	volatile uint8_t reserved_25_2f[11];
+	/* 0x30:  Host TX FIFO Data Port Register */
+	volatile uint8_t host_tx_fifo_data;
+	/* 0x31 ~ 0x3F:  Reserved Registers 31h - 3Fh */
+	volatile uint8_t reserved_31_3f[15];
+	/* 0x40 ~ 0x4F: Endpoint Registers 40h - 4Fh */
+	struct it82xx2_usb_ep_regs usb_ep_regs[4];
+	/* 0x50:  Device Controller Control Register */
+	volatile uint8_t dc_control;
+	/* 0x51:  Device Controller LINE Status Register */
+	volatile uint8_t dc_line_status;
+	/* 0x52:  Device Controller Interrupt Status Register */
+	volatile uint8_t dc_interrupt_status;
+	/* 0x53:  Device Controller Interrupt Mask Register */
+	volatile uint8_t dc_interrupt_mask;
+	/* 0x54:  Device Controller Address Register */
+	volatile uint8_t dc_address;
+	/* 0x55:  Device Controller Frame Number MSP Register */
+	volatile uint8_t dc_frame_num_msp;
+	/* 0x56:  Device Controller Frame Number LSP Register */
+	volatile uint8_t dc_frame_num_lsp;
+	/* 0x57 ~ 0x5F:  Reserved Registers 57h - 5Fh */
+	volatile uint8_t reserved_57_5f[9];
+	/* 0x60 ~ 0xDF: EP FIFO Registers 60h - DFh */
+	struct it82xx2_usb_ep_fifo_regs fifo_regs[4];
+	/* 0xE0:  Host/Device Control Register */
+	volatile uint8_t host_device_control;
+	/* 0xE1 ~ 0xE3:  Reserved Registers E1h - E3h */
+	volatile uint8_t reserved_e1_e3[3];
+	/* 0xE4:  Port0 MISC Control Register */
+	volatile uint8_t port0_misc_control;
+	/* 0xE5 ~ 0xE7:  Reserved Registers E5h - E7h */
+	volatile uint8_t reserved_e5_e7[3];
+	/* 0xE8:  Port1 MISC Control Register */
+	volatile uint8_t port1_misc_control;
+};
+#endif /* #ifndef __ASSEMBLER__ */
 
 /**
  *
@@ -1123,70 +1412,74 @@
 
 #ifndef __ASSEMBLER__
 struct gctrl_it8xxx2_regs {
-	/* 0x00-0x01: Reserved1 */
-	volatile uint8_t reserved1[2];
+	/* 0x00-0x01: Reserved_00_01 */
+	volatile uint8_t reserved_00_01[2];
 	/* 0x02: Chip Version */
 	volatile uint8_t GCTRL_ECHIPVER;
-	/* 0x03-0x05: Reserved2 */
-	volatile uint8_t reserved2[3];
+	/* 0x03-0x05: Reserved_03_05 */
+	volatile uint8_t reserved_03_05[3];
 	/* 0x06: Reset Status */
 	volatile uint8_t GCTRL_RSTS;
-	/* 0x07-0x09: Reserved3 */
-	volatile uint8_t reserved3[3];
+	/* 0x07-0x09: Reserved_07_09 */
+	volatile uint8_t reserved_07_09[3];
 	/* 0x0A: Base Address Select */
 	volatile uint8_t GCTRL_BADRSEL;
 	/* 0x0B: Wait Next Clock Rising */
 	volatile uint8_t GCTRL_WNCKR;
-	/* 0x0C: Reserved4 */
-	volatile uint8_t reserved4;
+	/* 0x0C: reserved_0c */
+	volatile uint8_t reserved_0c;
 	/* 0x0D: Special Control 1 */
 	volatile uint8_t GCTRL_SPCTRL1;
-	/* 0x0E-0x0F: Reserved5 */
-	volatile uint8_t reserved5[2];
+	/* 0x0E-0x0F: reserved_0e_0f */
+	volatile uint8_t reserved_0e_0f[2];
 	/* 0x10: Reset Control DMM */
 	volatile uint8_t GCTRL_RSTDMMC;
 	/* 0x11: Reset Control 4 */
 	volatile uint8_t GCTRL_RSTC4;
-	/* 0x12-0x1B: Reserved6 */
-	volatile uint8_t reserved6[10];
+	/* 0x12-0x1B: reserved_12_1b */
+	volatile uint8_t reserved_12_1b[10];
 	/* 0x1C: Special Control 4 */
 	volatile uint8_t GCTRL_SPCTRL4;
-	/* 0x1D-0x1F: Reserved7 */
-	volatile uint8_t reserved7[3];
+	/* 0x1D-0x1F: reserved_1d_1f */
+	volatile uint8_t reserved_1d_1f[3];
 	/* 0x20: Memory Controller Configuration 3 */
 	volatile uint8_t GCTRL_MCCR3;
 	/* 0x21: Reset Control 5 */
 	volatile uint8_t GCTRL_RSTC5;
-	/* 0x22-0x2F: Reserved8 */
-	volatile uint8_t reserved8[14];
+	/* 0x22-0x2F: reserved_22_2f */
+	volatile uint8_t reserved_22_2f[14];
 	/* 0x30: Memory Controller Configuration */
 	volatile uint8_t GCTRL_MCCR;
 	/* 0x31: Externel ILM/DLM Size */
 	volatile uint8_t GCTRL_EIDSR;
-	/* 0x32-0x36: Reserved9 */
-	volatile uint8_t reserved9[5];
+	/* 0x32: Reserved_32 */
+	volatile uint8_t reserved_32;
+	/* 0x33: Pin Multi-function Enable 2 */
+	volatile uint8_t gctrl_pmer2;
+	/* 0x34-0x36: Reserved_34_36 */
+	volatile uint8_t reserved_34_36[3];
 	/* 0x37: Eflash Protect Lock */
 	volatile uint8_t GCTRL_EPLR;
-	/* 0x38-0x40: Reserved10 */
-	volatile uint8_t reserved10[9];
+	/* 0x38-0x40: Reserved_38_40 */
+	volatile uint8_t reserved_38_40[9];
 	/* 0x41: Interrupt Vector Table Base Address */
 	volatile uint8_t GCTRL_IVTBAR;
-	/* 0x42-0x43: Reserved11 */
-	volatile uint8_t reserved11[2];
+	/* 0x42-0x43: Reserved_42_43 */
+	volatile uint8_t reserved_42_43[2];
 	/* 0x44: Memory Controller Configuration 2 */
 	volatile uint8_t GCTRL_MCCR2;
-	/* 0x45: Reserved12 */
-	volatile uint8_t reserved12;
+	/* 0x45: Reserved_45 */
+	volatile uint8_t reserved_45;
 	/* 0x46: Pin Multi-function Enable 3 */
 	volatile uint8_t GCTRL_PMER3;
-	/* 0x47-0x4A: Reserved13 */
-	volatile uint8_t reserved13[4];
+	/* 0x47-0x4A: reserved_47_4a */
+	volatile uint8_t reserved_47_4a[4];
 	/* 0x4B: ETWD and UART Control */
 	volatile uint8_t GCTRL_ETWDUARTCR;
 	/* 0x4C: Wakeup MCU Control */
 	volatile uint8_t GCTRL_WMCR;
-	/* 0x4D-0x4F: Reserved14 */
-	volatile uint8_t reserved14[3];
+	/* 0x4D-0x4F: reserved_4d_4f */
+	volatile uint8_t reserved_4d_4f[3];
 	/* 0x50: Port 80h/81h Status Register */
 	volatile uint8_t GCTRL_P80H81HSR;
 	/* 0x51: Port 80h Data Register */
@@ -1195,12 +1488,12 @@
 	volatile uint8_t GCTRL_P81HDR;
 	/* 0x53: H2RAM Offset Register */
 	volatile uint8_t GCTRL_H2ROFSR;
-	/* 0x54-0x5C: Reserved15 */
-	volatile uint8_t reserved15[9];
+	/* 0x54-0x5C: reserved_54_5c */
+	volatile uint8_t reserved_54_5c[9];
 	/* 0x5D: RISCV ILM Configuration 0 */
 	volatile uint8_t GCTRL_RVILMCR0;
-	/* 0x5E-0x84: Reserved16 */
-	volatile uint8_t reserved16[39];
+	/* 0x5E-0x84: reserved_5e_84 */
+	volatile uint8_t reserved_5e_84[39];
 	/* 0x85: Chip ID Byte 1 */
 	volatile uint8_t GCTRL_ECHIPID1;
 	/* 0x86: Chip ID Byte 2 */
@@ -1239,6 +1532,10 @@
 #define IT8XXX2_GCTRL_ILM0_ENABLE	BIT(0)
 /* Accept Port 80h Cycle */
 #define IT8XXX2_GCTRL_ACP80		BIT(6)
+/* USB Debug Enable */
+#define IT8XXX2_GCTRL_MCCR_USB_EN	BIT(7)
+/* USB Pad Power-On Enable */
+#define IT8XXX2_GCTRL_PMER2_USB_PAD_EN	BIT(7)
 
 /*
  * VCC Detector Option.