From 0000000000000000000000000000000000000000 Mon Sep 17 00:00:00 2001
From: Jianhua Lu <lujianhua000@gmail.com>
Date: Thu, 4 Aug 2022 13:26:26 +0800
Subject: Input: Add nt36523 touchscreen driver

---
 drivers/input/touchscreen/Kconfig                     |    2 +
 drivers/input/touchscreen/Makefile                    |    1 +
 drivers/input/touchscreen/nt36523/Kconfig             |   11 +
 drivers/input/touchscreen/nt36523/Makefile            |    8 +
 drivers/input/touchscreen/nt36523/nt36xxx.c           | 1908 ++++++++++
 drivers/input/touchscreen/nt36523/nt36xxx.h           |  240 ++
 drivers/input/touchscreen/nt36523/nt36xxx_fw_update.c |  857 +++++
 drivers/input/touchscreen/nt36523/nt36xxx_mem_map.h   |  390 ++
 8 files changed, 3417 insertions(+)

diff --git a/drivers/input/touchscreen/Kconfig b/drivers/input/touchscreen/Kconfig
index e3e2324547b9..1f8b33c2b03d 100644
--- a/drivers/input/touchscreen/Kconfig
+++ b/drivers/input/touchscreen/Kconfig
@@ -12,6 +12,8 @@ menuconfig INPUT_TOUCHSCREEN
 
 if INPUT_TOUCHSCREEN
 
+source "drivers/input/touchscreen/nt36523/Kconfig"
+
 config TOUCHSCREEN_88PM860X
 	tristate "Marvell 88PM860x touchscreen"
 	depends on MFD_88PM860X
diff --git a/drivers/input/touchscreen/Makefile b/drivers/input/touchscreen/Makefile
index 62bd24f3ac8e..7d52592f4290 100644
--- a/drivers/input/touchscreen/Makefile
+++ b/drivers/input/touchscreen/Makefile
@@ -118,3 +118,4 @@ obj-$(CONFIG_TOUCHSCREEN_IQS5XX)	+= iqs5xx.o
 obj-$(CONFIG_TOUCHSCREEN_IQS7211)	+= iqs7211.o
 obj-$(CONFIG_TOUCHSCREEN_ZINITIX)	+= zinitix.o
 obj-$(CONFIG_TOUCHSCREEN_HIMAX_HX83112B)	+= himax_hx83112b.o
+obj-$(CONFIG_TOUCHSCREEN_NT36523_SPI) += nt36523/
diff --git a/drivers/input/touchscreen/nt36523/Kconfig b/drivers/input/touchscreen/nt36523/Kconfig
new file mode 100644
index 000000000000..5f4ef5abfd6a
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/Kconfig
@@ -0,0 +1,11 @@
+#
+# Novatek NT36523 touchscreen driver configuration
+#
+config TOUCHSCREEN_NT36523_SPI
+	tristate "Novatek NT36523 no flash SPI driver"
+	default n
+	help
+	  Say Y here if you have a Novatek NT36523 no flash touchscreen connected
+	  to your system by SPI bus.
+
+	  If unsure, say N.
diff --git a/drivers/input/touchscreen/nt36523/Makefile b/drivers/input/touchscreen/nt36523/Makefile
new file mode 100644
index 000000000000..d16afc8f127f
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/Makefile
@@ -0,0 +1,8 @@
+#
+# Makefile for the Novatek NT36523 touchscreen driver.
+#
+
+# Each configuration option enables a list of files.
+obj-$(CONFIG_TOUCHSCREEN_NT36523_SPI) += nt36523_ts.o
+nt36523_ts-y := nt36xxx.o \
+	nt36xxx_fw_update.o
diff --git a/drivers/input/touchscreen/nt36523/nt36xxx.c b/drivers/input/touchscreen/nt36523/nt36xxx.c
new file mode 100644
index 000000000000..45500ad5cd91
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/nt36xxx.c
@@ -0,0 +1,1908 @@
+/*
+ * Copyright (C) 2010 - 2018 Novatek, Inc.
+ * Copyright (C) 2021 XiaoMi, Inc.
+ *
+ * $Revision: 73033 $
+ * $Date: 2020-11-26 10:09:14 +0800 (週四, 26 十一月 2020) $
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+ * more details.
+ *
+ */
+#include <linux/kernel.h>
+#include <linux/module.h>
+#include <linux/interrupt.h>
+#include <linux/irq.h>
+#include <linux/gpio.h>
+#include <linux/proc_fs.h>
+#include <linux/input/mt.h>
+#include <linux/debugfs.h>
+#include <linux/of_gpio.h>
+#include <linux/of_irq.h>
+
+#ifdef CONFIG_DRM
+#include <drm/drm_notifier.h>
+#endif
+
+#include "nt36xxx.h"
+
+#if NVT_TOUCH_ESD_PROTECT
+#include <linux/jiffies.h>
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+#if NVT_TOUCH_ESD_PROTECT
+static struct delayed_work nvt_esd_check_work;
+static struct workqueue_struct *nvt_esd_check_wq;
+static unsigned long irq_timer = 0;
+uint8_t esd_check = false;
+uint8_t esd_retry = 0;
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+struct nvt_ts_data *ts;
+
+#if BOOT_UPDATE_FIRMWARE
+static struct workqueue_struct *nvt_fwu_wq;
+extern void Boot_Update_Firmware(struct work_struct *work);
+#endif
+
+#ifdef CONFIG_DRM
+static int nvt_drm_notifier_callback(struct notifier_block *self, unsigned long event, void *data);
+#endif
+
+static int32_t nvt_ts_suspend(struct device *dev);
+static int32_t nvt_ts_resume(struct device *dev);
+
+uint32_t ENG_RST_ADDR  = 0x7FFF80;
+uint32_t SWRST_N8_ADDR = 0; //read from dtsi
+uint32_t SPI_RD_FAST_ADDR = 0;	//read from dtsi
+
+#if TOUCH_KEY_NUM > 0
+const uint16_t touch_key_array[TOUCH_KEY_NUM] = {
+	KEY_BACK,
+	KEY_HOME,
+	KEY_MENU
+};
+#endif
+
+static uint8_t bTouchIsAwake = 0;
+
+/*******************************************************
+Description:
+	Novatek touchscreen irq enable/disable function.
+
+return:
+	n.a.
+*******************************************************/
+static void nvt_irq_enable(bool enable)
+{
+	if (enable) {
+		if (!ts->irq_enabled) {
+			enable_irq(ts->client->irq);
+			ts->irq_enabled = true;
+		}
+	} else {
+		if (ts->irq_enabled) {
+			disable_irq(ts->client->irq);
+			ts->irq_enabled = false;
+		}
+	}
+}
+
+static inline int32_t spi_read_write(struct spi_device *client, uint8_t *buf, size_t len , NVT_SPI_RW rw)
+{
+	struct spi_message m;
+	struct spi_transfer t = {
+		.len    = len,
+	};
+
+	memset(ts->xbuf, 0, len + DUMMY_BYTES);
+	memcpy(ts->xbuf, buf, len);
+
+	switch (rw) {
+		case NVTREAD:
+			t.tx_buf = ts->xbuf;
+			t.rx_buf = ts->rbuf;
+			t.len    = (len + DUMMY_BYTES);
+			break;
+
+		case NVTWRITE:
+			t.tx_buf = ts->xbuf;
+			break;
+	}
+
+	spi_message_init(&m);
+	spi_message_add_tail(&t, &m);
+	return spi_sync(client, &m);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen spi read function.
+
+return:
+	Executive outcomes. 2---succeed. -5---I/O error
+*******************************************************/
+int32_t CTP_SPI_READ(struct spi_device *client, uint8_t *buf, uint16_t len)
+{
+	int32_t ret = -1;
+	int32_t retries = 0;
+
+	mutex_lock(&ts->xbuf_lock);
+
+	buf[0] = SPI_READ_MASK(buf[0]);
+
+	while (retries < 5) {
+		ret = spi_read_write(client, buf, len, NVTREAD);
+		if (ret == 0) break;
+		retries++;
+	}
+
+	if (unlikely(retries == 5)) {
+		NVT_ERR("read error, ret=%d\n", ret);
+		ret = -EIO;
+	} else {
+		memcpy((buf+1), (ts->rbuf+2), (len-1));
+	}
+
+	mutex_unlock(&ts->xbuf_lock);
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen spi write function.
+
+return:
+	Executive outcomes. 1---succeed. -5---I/O error
+*******************************************************/
+int32_t CTP_SPI_WRITE(struct spi_device *client, uint8_t *buf, uint16_t len)
+{
+	int32_t ret = -1;
+	int32_t retries = 0;
+
+	mutex_lock(&ts->xbuf_lock);
+
+	buf[0] = SPI_WRITE_MASK(buf[0]);
+
+	while (retries < 5) {
+		ret = spi_read_write(client, buf, len, NVTWRITE);
+		if (ret == 0)	break;
+		retries++;
+	}
+
+	if (unlikely(retries == 5)) {
+		NVT_ERR("error, ret=%d\n", ret);
+		ret = -EIO;
+	}
+
+	mutex_unlock(&ts->xbuf_lock);
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen set index/page/addr address.
+
+return:
+	Executive outcomes. 0---succeed. -5---access fail.
+*******************************************************/
+int32_t nvt_set_page(uint32_t addr)
+{
+	uint8_t buf[4] = {0};
+
+	buf[0] = 0xFF;	//set index/page/addr command
+	buf[1] = (addr >> 15) & 0xFF;
+	buf[2] = (addr >> 7) & 0xFF;
+
+	return CTP_SPI_WRITE(ts->client, buf, 3);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen write data to specify address.
+
+return:
+	Executive outcomes. 0---succeed. -5---access fail.
+*******************************************************/
+int32_t nvt_write_addr(uint32_t addr, uint8_t data)
+{
+	int32_t ret = 0;
+	uint8_t buf[4] = {0};
+
+	//---set xdata index---
+	buf[0] = 0xFF;	//set index/page/addr command
+	buf[1] = (addr >> 15) & 0xFF;
+	buf[2] = (addr >> 7) & 0xFF;
+	ret = CTP_SPI_WRITE(ts->client, buf, 3);
+	if (ret) {
+		NVT_ERR("set page 0x%06X failed, ret = %d\n", addr, ret);
+		return ret;
+	}
+
+	//---write data to index---
+	buf[0] = addr & (0x7F);
+	buf[1] = data;
+	ret = CTP_SPI_WRITE(ts->client, buf, 2);
+	if (ret) {
+		NVT_ERR("write data to 0x%06X failed, ret = %d\n", addr, ret);
+		return ret;
+	}
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen enable hw bld crc function.
+
+return:
+	N/A.
+*******************************************************/
+void nvt_bld_crc_enable(void)
+{
+	uint8_t buf[4] = {0};
+
+	//---set xdata index to BLD_CRC_EN_ADDR---
+	nvt_set_page(ts->mmap->BLD_CRC_EN_ADDR);
+
+	//---read data from index---
+	buf[0] = ts->mmap->BLD_CRC_EN_ADDR & (0x7F);
+	buf[1] = 0xFF;
+	CTP_SPI_READ(ts->client, buf, 2);
+
+	//---write data to index---
+	buf[0] = ts->mmap->BLD_CRC_EN_ADDR & (0x7F);
+	buf[1] = buf[1] | (0x01 << 7);
+	CTP_SPI_WRITE(ts->client, buf, 2);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen clear status & enable fw crc function.
+
+return:
+	N/A.
+*******************************************************/
+void nvt_fw_crc_enable(void)
+{
+	uint8_t buf[4] = {0};
+
+	//---set xdata index to EVENT BUF ADDR---
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR);
+
+	//---clear fw reset status---
+	buf[0] = EVENT_MAP_RESET_COMPLETE & (0x7F);
+	buf[1] = 0x00;
+	CTP_SPI_WRITE(ts->client, buf, 2);
+
+	//---enable fw crc---
+	buf[0] = EVENT_MAP_HOST_CMD & (0x7F);
+	buf[1] = 0xAE;	//enable fw crc command
+	CTP_SPI_WRITE(ts->client, buf, 2);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen set boot ready function.
+
+return:
+	N/A.
+*******************************************************/
+void nvt_boot_ready(void)
+{
+	//---write BOOT_RDY status cmds---
+	nvt_write_addr(ts->mmap->BOOT_RDY_ADDR, 1);
+
+	mdelay(5);
+
+	if (!ts->hw_crc) {
+		//---write BOOT_RDY status cmds---
+		nvt_write_addr(ts->mmap->BOOT_RDY_ADDR, 0);
+
+		//---write POR_CD cmds---
+		nvt_write_addr(ts->mmap->POR_CD_ADDR, 0xA0);
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen enable auto copy mode function.
+
+return:
+	N/A.
+*******************************************************/
+void nvt_tx_auto_copy_mode(void)
+{
+	//---write TX_AUTO_COPY_EN cmds---
+	nvt_write_addr(ts->mmap->TX_AUTO_COPY_EN, 0x69);
+
+	NVT_ERR("tx auto copy mode enable\n");
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen check spi dma tx info function.
+
+return:
+	N/A.
+*******************************************************/
+int32_t nvt_check_spi_dma_tx_info(void)
+{
+	uint8_t buf[8] = {0};
+	int32_t i = 0;
+	const int32_t retry = 200;
+
+	for (i = 0; i < retry; i++) {
+		//---set xdata index to EVENT BUF ADDR---
+		nvt_set_page(ts->mmap->SPI_DMA_TX_INFO);
+
+		//---read fw status---
+		buf[0] = ts->mmap->SPI_DMA_TX_INFO & 0x7F;
+		buf[1] = 0xFF;
+		CTP_SPI_READ(ts->client, buf, 2);
+
+		if (buf[1] == 0x00)
+			break;
+
+		usleep_range(1000, 1000);
+	}
+
+	if (i >= retry) {
+		NVT_ERR("failed, i=%d, buf[1]=0x%02X\n", i, buf[1]);
+		return -1;
+	} else {
+		return 0;
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen eng reset cmd
+    function.
+
+return:
+	n.a.
+*******************************************************/
+void nvt_eng_reset(void)
+{
+	//---eng reset cmds to ENG_RST_ADDR---
+	nvt_write_addr(ENG_RST_ADDR, 0x5A);
+
+	mdelay(1);	//wait tMCU_Idle2TP_REX_Hi after TP_RST
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen reset MCU
+    function.
+
+return:
+	n.a.
+*******************************************************/
+void nvt_sw_reset(void)
+{
+	//---software reset cmds to SWRST_N8_ADDR---
+	nvt_write_addr(SWRST_N8_ADDR, 0x55);
+
+	msleep(10);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen reset MCU then into idle mode
+    function.
+
+return:
+	n.a.
+*******************************************************/
+void nvt_sw_reset_idle(void)
+{
+	//---MCU idle cmds to SWRST_N8_ADDR---
+	nvt_write_addr(SWRST_N8_ADDR, 0xAA);
+
+	msleep(15);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen reset MCU (boot) function.
+
+return:
+	n.a.
+*******************************************************/
+void nvt_bootloader_reset(void)
+{
+	//---reset cmds to SWRST_N8_ADDR---
+	nvt_write_addr(SWRST_N8_ADDR, 0x69);
+
+	mdelay(5);	//wait tBRST2FR after Bootload RST
+
+	if (SPI_RD_FAST_ADDR) {
+		/* disable SPI_RD_FAST */
+		nvt_write_addr(SPI_RD_FAST_ADDR, 0x00);
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen clear FW status function.
+
+return:
+	Executive outcomes. 0---succeed. -1---fail.
+*******************************************************/
+int32_t nvt_clear_fw_status(void)
+{
+	uint8_t buf[8] = {0};
+	int32_t i = 0;
+	const int32_t retry = 20;
+
+	for (i = 0; i < retry; i++) {
+		//---set xdata index to EVENT BUF ADDR---
+		nvt_set_page(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE);
+
+		//---clear fw status---
+		buf[0] = EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE;
+		buf[1] = 0x00;
+		CTP_SPI_WRITE(ts->client, buf, 2);
+
+		//---read fw status---
+		buf[0] = EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE;
+		buf[1] = 0xFF;
+		CTP_SPI_READ(ts->client, buf, 2);
+
+		if (buf[1] == 0x00)
+			break;
+
+		usleep_range(10000, 10000);
+	}
+
+	if (i >= retry) {
+		NVT_ERR("failed, i=%d, buf[1]=0x%02X\n", i, buf[1]);
+		return -1;
+	} else {
+		return 0;
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen check FW status function.
+
+return:
+	Executive outcomes. 0---succeed. -1---failed.
+*******************************************************/
+int32_t nvt_check_fw_status(void)
+{
+	uint8_t buf[8] = {0};
+	int32_t i = 0;
+	const int32_t retry = 50;
+
+	for (i = 0; i < retry; i++) {
+		//---set xdata index to EVENT BUF ADDR---
+		nvt_set_page(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE);
+
+		//---read fw status---
+		buf[0] = EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE;
+		buf[1] = 0x00;
+		CTP_SPI_READ(ts->client, buf, 2);
+
+		if ((buf[1] & 0xF0) == 0xA0)
+			break;
+
+		usleep_range(10000, 10000);
+	}
+
+	if (i >= retry) {
+		NVT_ERR("failed, i=%d, buf[1]=0x%02X\n", i, buf[1]);
+		return -1;
+	} else {
+		return 0;
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen check FW reset state function.
+
+return:
+	Executive outcomes. 0---succeed. -1---failed.
+*******************************************************/
+int32_t nvt_check_fw_reset_state(RST_COMPLETE_STATE check_reset_state)
+{
+	uint8_t buf[8] = {0};
+	int32_t ret = 0;
+	int32_t retry = 0;
+	int32_t retry_max = (check_reset_state == RESET_STATE_INIT) ? 10 : 50;
+
+	//---set xdata index to EVENT BUF ADDR---
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_RESET_COMPLETE);
+
+	while (1) {
+		//---read reset state---
+		buf[0] = EVENT_MAP_RESET_COMPLETE;
+		buf[1] = 0x00;
+		CTP_SPI_READ(ts->client, buf, 6);
+
+		if ((buf[1] >= check_reset_state) && (buf[1] <= RESET_STATE_MAX)) {
+			ret = 0;
+			break;
+		}
+
+		retry++;
+		if(unlikely(retry > retry_max)) {
+			NVT_ERR("error, retry=%d, buf[1]=0x%02X, 0x%02X, 0x%02X, 0x%02X, 0x%02X\n",
+				retry, buf[1], buf[2], buf[3], buf[4], buf[5]);
+			ret = -1;
+			break;
+		}
+
+		usleep_range(10000, 10000);
+	}
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen get novatek project id information
+	function.
+
+return:
+	Executive outcomes. 0---success. -1---fail.
+*******************************************************/
+int32_t nvt_read_pid(void)
+{
+	uint8_t buf[4] = {0};
+	int32_t ret = 0;
+
+	//---set xdata index to EVENT BUF ADDR---
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_PROJECTID);
+
+	//---read project id---
+	buf[0] = EVENT_MAP_PROJECTID;
+	buf[1] = 0x00;
+	buf[2] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 3);
+
+	ts->nvt_pid = (buf[2] << 8) + buf[1];
+
+	//---set xdata index to EVENT BUF ADDR---
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR);
+
+	NVT_LOG("PID=%04X\n", ts->nvt_pid);
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen get firmware related information
+	function.
+
+return:
+	Executive outcomes. 0---success. -1---fail.
+*******************************************************/
+int32_t nvt_get_fw_info(void)
+{
+	uint8_t buf[64] = {0};
+	uint32_t retry_count = 0;
+	int32_t ret = 0;
+
+info_retry:
+	//---set xdata index to EVENT BUF ADDR---
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_FWINFO);
+
+	//---read fw info---
+	buf[0] = EVENT_MAP_FWINFO;
+	CTP_SPI_READ(ts->client, buf, 39);
+	ts->fw_ver = buf[1];
+	ts->x_num = buf[3];
+	ts->y_num = buf[4];
+	ts->abs_x_max = (uint16_t)((buf[5] << 8) | buf[6]);
+	ts->abs_y_max = (uint16_t)((buf[7] << 8) | buf[8]);
+	ts->max_button_num = buf[11];
+	ts->cascade = buf[34] & 0x01;
+	if (ts->pen_support) {
+		ts->x_gang_num = buf[37];
+		ts->y_gang_num = buf[38];
+	}
+
+	//---clear x_num, y_num if fw info is broken---
+	if ((buf[1] + buf[2]) != 0xFF) {
+		NVT_ERR("FW info is broken! fw_ver=0x%02X, ~fw_ver=0x%02X\n", buf[1], buf[2]);
+		ts->fw_ver = 0;
+		ts->x_num = 18;
+		ts->y_num = 32;
+		ts->abs_x_max = TOUCH_DEFAULT_MAX_WIDTH;
+		ts->abs_y_max = TOUCH_DEFAULT_MAX_HEIGHT;
+		ts->max_button_num = TOUCH_KEY_NUM;
+
+		if(retry_count < 3) {
+			retry_count++;
+			NVT_ERR("retry_count=%d\n", retry_count);
+			goto info_retry;
+		} else {
+			NVT_ERR("Set default fw_ver=%d, x_num=%d, y_num=%d, "
+					"abs_x_max=%d, abs_y_max=%d, max_button_num=%d!\n",
+					ts->fw_ver, ts->x_num, ts->y_num,
+					ts->abs_x_max, ts->abs_y_max, ts->max_button_num);
+			ret = -1;
+		}
+	} else {
+		ret = 0;
+	}
+
+	NVT_LOG("fw_ver = 0x%02X, fw_type = 0x%02X, x_num=%d, y_num=%d\n", ts->fw_ver, buf[14], ts->x_num, ts->y_num);
+
+	//---Get Novatek PID---
+	nvt_read_pid();
+
+	return ret;
+}
+
+static void release_pen_event(void) {
+	if (ts && ts->pen_input_dev) {
+		input_report_abs(ts->pen_input_dev, ABS_X, 0);
+		input_report_abs(ts->pen_input_dev, ABS_Y, 0);
+		input_report_abs(ts->pen_input_dev, ABS_PRESSURE, 0);
+		input_report_abs(ts->pen_input_dev, ABS_TILT_X, 0);
+		input_report_abs(ts->pen_input_dev, ABS_TILT_Y, 0);
+		input_report_abs(ts->pen_input_dev, ABS_DISTANCE, 0);
+		input_report_key(ts->pen_input_dev, BTN_TOUCH, 0);
+		input_report_key(ts->pen_input_dev, BTN_TOOL_PEN, 0);
+		input_report_key(ts->pen_input_dev, BTN_STYLUS, 0);
+		input_report_key(ts->pen_input_dev, BTN_STYLUS2, 0);
+		input_sync(ts->pen_input_dev);
+	}
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen parse device tree function.
+
+return:
+	n.a.
+*******************************************************/
+#ifdef CONFIG_OF
+static int32_t nvt_parse_dt(struct device *dev)
+{
+	struct device_node *np = dev->of_node;
+	int32_t ret = 0;
+
+#if NVT_TOUCH_SUPPORT_HW_RST
+	ts->reset_gpio = of_get_named_gpio_flags(np, "novatek,reset-gpio", 0, &ts->reset_flags);
+	NVT_LOG("novatek,reset-gpio=%d\n", ts->reset_gpio);
+#endif
+	ts->irq_gpio = of_get_named_gpio(np, "novatek,irq-gpio", 0);
+	NVT_LOG("novatek,irq-gpio=%d\n", ts->irq_gpio);
+
+	ts->pen_support = of_property_read_bool(np, "novatek,pen-support");
+	NVT_LOG("novatek,pen-support=%d\n", ts->pen_support);
+
+	ts->wgp_stylus = of_property_read_bool(np, "novatek,wgp-stylus");
+	NVT_LOG("novatek,wgp-stylus=%d\n", ts->wgp_stylus);
+
+	ret = of_property_read_u32(np, "novatek,swrst-n8-addr", &SWRST_N8_ADDR);
+	if (ret) {
+		NVT_ERR("error reading novatek,swrst-n8-addr. ret=%d\n", ret);
+		return ret;
+	} else {
+		NVT_LOG("SWRST_N8_ADDR=0x%06X\n", SWRST_N8_ADDR);
+	}
+
+	ret = of_property_read_u32(np, "novatek,spi-rd-fast-addr", &SPI_RD_FAST_ADDR);
+	if (ret) {
+		NVT_LOG("not support novatek,spi-rd-fast-addr\n");
+		SPI_RD_FAST_ADDR = 0;
+		ret = 0;
+	} else {
+		NVT_LOG("SPI_RD_FAST_ADDR=0x%06X\n", SPI_RD_FAST_ADDR);
+	}
+
+	ret = of_property_read_string(np, "firmware-name", &ts->fw_name);
+	if (ret) {
+		NVT_LOG("Unable to get touchscreen firmware name\n");
+		ts->fw_name = DEFAULT_BOOT_UPDATE_FIRMWARE_NAME;
+	}
+
+	ret = of_property_read_u32(np, "spi-max-frequency", &ts->spi_max_freq);
+	if (ret) {
+		NVT_LOG("Unable to get spi freq\n");
+		return ret;
+	} else {
+		NVT_LOG("spi-max-frequency: %u\n", ts->spi_max_freq);
+	}
+
+	return ret;
+}
+#else
+static int32_t nvt_parse_dt(struct device *dev)
+{
+#if NVT_TOUCH_SUPPORT_HW_RST
+	ts->reset_gpio = NVTTOUCH_RST_PIN;
+#endif
+	ts->irq_gpio = NVTTOUCH_INT_PIN;
+	return 0;
+}
+#endif
+
+/*******************************************************
+Description:
+	Novatek touchscreen config and request gpio
+
+return:
+	Executive outcomes. 0---succeed. not 0---failed.
+*******************************************************/
+static int nvt_gpio_config(struct nvt_ts_data *ts)
+{
+	int32_t ret = 0;
+
+#if NVT_TOUCH_SUPPORT_HW_RST
+	/* request RST-pin (Output/High) */
+	if (gpio_is_valid(ts->reset_gpio)) {
+		ret = gpio_request_one(ts->reset_gpio, GPIOF_OUT_INIT_LOW, "NVT-tp-rst");
+		if (ret) {
+			NVT_ERR("Failed to request NVT-tp-rst GPIO\n");
+			goto err_request_reset_gpio;
+		}
+	}
+#endif
+
+	/* request INT-pin (Input) */
+	if (gpio_is_valid(ts->irq_gpio)) {
+		ret = gpio_request_one(ts->irq_gpio, GPIOF_IN, "NVT-int");
+		if (ret) {
+			NVT_ERR("Failed to request NVT-int GPIO\n");
+			goto err_request_irq_gpio;
+		}
+	}
+
+	return ret;
+
+err_request_irq_gpio:
+#if NVT_TOUCH_SUPPORT_HW_RST
+	gpio_free(ts->reset_gpio);
+err_request_reset_gpio:
+#endif
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen deconfig gpio
+
+return:
+	n.a.
+*******************************************************/
+static void nvt_gpio_deconfig(struct nvt_ts_data *ts)
+{
+	if (gpio_is_valid(ts->irq_gpio))
+		gpio_free(ts->irq_gpio);
+#if NVT_TOUCH_SUPPORT_HW_RST
+	if (gpio_is_valid(ts->reset_gpio))
+		gpio_free(ts->reset_gpio);
+#endif
+}
+
+static uint8_t nvt_fw_recovery(uint8_t *point_data)
+{
+	uint8_t i = 0;
+	uint8_t detected = true;
+
+	/* check pattern */
+	for (i=1 ; i<7 ; i++) {
+		if (point_data[i] != 0x77) {
+			detected = false;
+			break;
+		}
+	}
+
+	return detected;
+}
+
+void nvt_set_dbgfw_status(bool enable)
+{
+	ts->fw_debug = enable;
+}
+
+bool nvt_get_dbgfw_status(void)
+{
+	return ts->fw_debug;
+}
+
+#if NVT_TOUCH_ESD_PROTECT
+void nvt_esd_check_enable(uint8_t enable)
+{
+	/* update interrupt timer */
+	irq_timer = jiffies;
+	/* clear esd_retry counter, if protect function is enabled */
+	esd_retry = enable ? 0 : esd_retry;
+	/* enable/disable esd check flag */
+	esd_check = enable;
+}
+
+static void nvt_esd_check_func(struct work_struct *work)
+{
+	unsigned int timer = jiffies_to_msecs(jiffies - irq_timer);
+
+	//NVT_LOG("esd_check = %d (retry %d)\n", esd_check, esd_retry);	//DEBUG
+
+	if ((timer > NVT_TOUCH_ESD_CHECK_PERIOD) && esd_check) {
+		mutex_lock(&ts->lock);
+		NVT_ERR("do ESD recovery, timer = %d, retry = %d\n", timer, esd_retry);
+		/* do esd recovery, reload fw */
+		nvt_update_firmware(ts->fw_name);
+		mutex_unlock(&ts->lock);
+		/* update interrupt timer */
+		irq_timer = jiffies;
+		/* update esd_retry counter */
+		esd_retry++;
+	}
+
+	queue_delayed_work(nvt_esd_check_wq, &nvt_esd_check_work,
+			msecs_to_jiffies(NVT_TOUCH_ESD_CHECK_PERIOD));
+}
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+#if NVT_TOUCH_WDT_RECOVERY
+static uint8_t recovery_cnt = 0;
+static uint8_t nvt_wdt_fw_recovery(uint8_t *point_data)
+{
+   uint32_t recovery_cnt_max = 10;
+   uint8_t recovery_enable = false;
+   uint8_t i = 0;
+
+   recovery_cnt++;
+
+   /* check pattern */
+   for (i=1 ; i<7 ; i++) {
+       if ((point_data[i] != 0xFD) && (point_data[i] != 0xFE)) {
+           recovery_cnt = 0;
+           break;
+       }
+   }
+
+   if (recovery_cnt > recovery_cnt_max){
+       recovery_enable = true;
+       recovery_cnt = 0;
+   }
+
+   return recovery_enable;
+}
+#endif	/* #if NVT_TOUCH_WDT_RECOVERY */
+
+#define PEN_DATA_LEN 14
+#define FW_HISTORY_SIZE 128
+static uint32_t nvt_dump_fw_history(void)
+{
+	int32_t ret = 0;
+	uint8_t buf[FW_HISTORY_SIZE + 1 + DUMMY_BYTES] = {0};
+	int32_t i = 0;
+	char *tmp_dump = NULL;
+	int32_t line_cnt = 0;
+
+	if (ts->mmap->FW_HISTORY_ADDR == 0) {
+		NVT_ERR("FW_HISTORY_ADDR not available!\n");
+		ret = -1;
+		goto exit_nvt_dump_fw_history;
+	}
+	nvt_set_page(ts->mmap->FW_HISTORY_ADDR);
+	buf[0] = ts->mmap->FW_HISTORY_ADDR & 0xFF;
+	CTP_SPI_READ(ts->client, buf, FW_HISTORY_SIZE + 1);
+	if (ret) {
+		NVT_ERR("CTP_SPI_READ failed.(%d)\n", ret);
+		ret = -1;
+		goto exit_nvt_dump_fw_history;
+		}
+
+	tmp_dump = (char *)kzalloc(FW_HISTORY_SIZE * 4, GFP_KERNEL);
+	for (i = 0; i < FW_HISTORY_SIZE; i++) {
+		sprintf(tmp_dump + i * 3 + line_cnt, "%02X ", buf[1 + i]);
+		if ((i + 1) % 16 == 0) {
+			sprintf(tmp_dump + i * 3 + line_cnt + 3, "%c", '\n');
+			line_cnt++;
+		}
+	}
+	NVT_LOG("%s", tmp_dump);
+
+exit_nvt_dump_fw_history:
+	if (tmp_dump) {
+		kfree(tmp_dump);
+		tmp_dump = NULL;
+	}
+	nvt_set_page(ts->mmap->EVENT_BUF_ADDR);
+
+	return ret;
+}
+
+#define POINT_DATA_LEN 65
+/*******************************************************
+Description:
+	Novatek touchscreen work function.
+
+return:
+	n.a.
+*******************************************************/
+static irqreturn_t nvt_ts_work_func(int irq, void *data)
+{
+	int32_t ret = -1;
+	uint8_t point_data[POINT_DATA_LEN + PEN_DATA_LEN + 1 + DUMMY_BYTES] = {0};
+	uint32_t position = 0;
+	uint32_t input_x = 0;
+	uint32_t input_y = 0;
+	uint32_t input_w = 0;
+	uint32_t input_p = 0;
+	uint8_t input_id = 0;
+#if MT_PROTOCOL_B
+	uint8_t press_id[TOUCH_MAX_FINGER_NUM] = {0};
+#endif /* MT_PROTOCOL_B */
+	int32_t i = 0;
+	int32_t finger_cnt = 0;
+	uint8_t pen_format_id = 0;
+	uint32_t pen_x = 0;
+	uint32_t pen_y = 0;
+	uint32_t pen_pressure = 0;
+	uint32_t pen_distance = 0;
+	int8_t pen_tilt_x = 0;
+	int8_t pen_tilt_y = 0;
+	uint32_t pen_btn1 = 0;
+	uint32_t pen_btn2 = 0;
+	uint32_t pen_battery = 0;
+
+	mutex_lock(&ts->lock);
+
+	if (ts->dev_pm_suspend) {
+		ret = wait_for_completion_timeout(&ts->dev_pm_suspend_completion, msecs_to_jiffies(500));
+		if (!ret) {
+			NVT_ERR("system(spi) can't finished resuming procedure, skip it\n");
+			goto XFER_ERROR;
+		}
+	}
+
+	if (ts->pen_support)
+		ret = CTP_SPI_READ(ts->client, point_data, POINT_DATA_LEN + PEN_DATA_LEN + 1);
+	else
+		ret = CTP_SPI_READ(ts->client, point_data, POINT_DATA_LEN + 1);
+	if (ret < 0) {
+		NVT_ERR("CTP_SPI_READ failed.(%d)\n", ret);
+		goto XFER_ERROR;
+	}
+
+	/*--- dump SPI buf ---
+	for (i = 0; i < 10; i++) {
+		NVT_LOG("%02X %02X %02X %02X %02X %02X  \n",
+			point_data[1+i*6], point_data[2+i*6], point_data[3+i*6], point_data[4+i*6], point_data[5+i*6], point_data[6+i*6]);
+	}
+	*/
+
+#if NVT_TOUCH_WDT_RECOVERY
+	/* ESD protect by WDT */
+	if (nvt_wdt_fw_recovery(point_data)) {
+		NVT_ERR("Recover for fw reset, %02X\n", point_data[1]);
+		if (point_data[1] == 0xFD) {
+			NVT_ERR("Dump FW history:\n");
+			nvt_dump_fw_history();
+		}
+		nvt_update_firmware(ts->fw_name);
+		goto XFER_ERROR;
+	}
+#endif /* #if NVT_TOUCH_WDT_RECOVERY */
+
+	/* ESD protect by FW handshake */
+	if (nvt_fw_recovery(point_data)) {
+#if NVT_TOUCH_ESD_PROTECT
+		nvt_esd_check_enable(true);
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+		goto XFER_ERROR;
+	}
+
+	finger_cnt = 0;
+
+	for (i = 0; i < ts->max_touch_num; i++) {
+		position = 1 + 6 * i;
+		input_id = (uint8_t)(point_data[position + 0] >> 3);
+		if ((input_id == 0) || (input_id > ts->max_touch_num))
+			continue;
+
+		if (((point_data[position] & 0x07) == 0x01) || ((point_data[position] & 0x07) == 0x02)) {	//finger down (enter & moving)
+#if NVT_TOUCH_ESD_PROTECT
+			/* update interrupt timer */
+			irq_timer = jiffies;
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+			input_x = (uint32_t)(point_data[position + 1] << 4) + (uint32_t) (point_data[position + 3] >> 4);
+			input_y = (uint32_t)(point_data[position + 2] << 4) + (uint32_t) (point_data[position + 3] & 0x0F);
+			if ((input_x < 0) || (input_y < 0))
+				continue;
+			if ((input_x > ts->abs_x_max) || (input_y > ts->abs_y_max))
+				continue;
+			input_w = (uint32_t)(point_data[position + 4]);
+			if (input_w == 0)
+				input_w = 1;
+			if (i < 2) {
+				input_p = (uint32_t)(point_data[position + 5]) + (uint32_t)(point_data[i + 63] << 8);
+				if (input_p > TOUCH_FORCE_NUM)
+					input_p = TOUCH_FORCE_NUM;
+			} else {
+				input_p = (uint32_t)(point_data[position + 5]);
+			}
+			if (input_p == 0)
+				input_p = 1;
+
+#if MT_PROTOCOL_B
+			press_id[input_id - 1] = 1;
+			input_mt_slot(ts->input_dev, input_id - 1);
+			input_mt_report_slot_state(ts->input_dev, MT_TOOL_FINGER, true);
+#else /* MT_PROTOCOL_B */
+			input_report_abs(ts->input_dev, ABS_MT_TRACKING_ID, input_id - 1);
+			input_report_key(ts->input_dev, BTN_TOUCH, 1);
+#endif /* MT_PROTOCOL_B */
+
+			input_report_abs(ts->input_dev, ABS_MT_POSITION_X, input_x);
+			input_report_abs(ts->input_dev, ABS_MT_POSITION_Y, input_y);
+			input_report_abs(ts->input_dev, ABS_MT_TOUCH_MAJOR, input_w);
+			input_report_abs(ts->input_dev, ABS_MT_PRESSURE, input_p);
+
+#if MT_PROTOCOL_B
+#else /* MT_PROTOCOL_B */
+			input_mt_sync(ts->input_dev);
+#endif /* MT_PROTOCOL_B */
+
+			finger_cnt++;
+		}
+	}
+
+#if MT_PROTOCOL_B
+	for (i = 0; i < ts->max_touch_num; i++) {
+		if (press_id[i] != 1) {
+			input_mt_slot(ts->input_dev, i);
+			input_report_abs(ts->input_dev, ABS_MT_TOUCH_MAJOR, 0);
+			input_report_abs(ts->input_dev, ABS_MT_PRESSURE, 0);
+			input_mt_report_slot_state(ts->input_dev, MT_TOOL_FINGER, false);
+		}
+	}
+	input_report_key(ts->input_dev, BTN_TOUCH, (finger_cnt > 0));
+#else /* MT_PROTOCOL_B */
+	if (finger_cnt == 0) {
+		input_report_key(ts->input_dev, BTN_TOUCH, 0);
+		input_mt_sync(ts->input_dev);
+	}
+#endif /* MT_PROTOCOL_B */
+
+#if TOUCH_KEY_NUM > 0
+	if (point_data[61] == 0xF8) {
+#if NVT_TOUCH_ESD_PROTECT
+		/* update interrupt timer */
+		irq_timer = jiffies;
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+		for (i = 0; i < ts->max_button_num; i++) {
+			input_report_key(ts->input_dev, touch_key_array[i], ((point_data[62] >> i) & 0x01));
+		}
+	} else {
+		for (i = 0; i < ts->max_button_num; i++) {
+			input_report_key(ts->input_dev, touch_key_array[i], 0);
+		}
+	}
+#endif
+
+	input_sync(ts->input_dev);
+
+	if (ts->pen_support && ts->pen_input_dev_enable && !(ts->pen_is_charge)) {
+/*
+		//--- dump pen buf ---
+		printk("%02X %02X %02X %02X %02X %02X %02X %02X %02X %02X %02X %02X %02X %02X\n",
+			point_data[66], point_data[67], point_data[68], point_data[69], point_data[70],
+			point_data[71], point_data[72], point_data[73], point_data[74], point_data[75],
+			point_data[76], point_data[77], point_data[78], point_data[79]);
+*/
+		// parse and handle pen report
+		pen_format_id = point_data[66];
+		if (pen_format_id != 0xFF) {
+			if (pen_format_id == 0x01) {
+				// report pen data
+				pen_x = (uint32_t)(point_data[67] << 8) + (uint32_t)(point_data[68]);
+				pen_y = (uint32_t)(point_data[69] << 8) + (uint32_t)(point_data[70]);
+				if (pen_x >= ts->abs_x_max * 2 - 1) {
+					pen_x -= 1;
+				}
+				if (pen_y >= ts->abs_y_max * 2 - 1) {
+					pen_y -= 1;
+				}
+				pen_pressure = (uint32_t)(point_data[71] << 8) + (uint32_t)(point_data[72]);
+				pen_tilt_x = (int32_t)point_data[73];
+				pen_tilt_y = (int32_t)point_data[74];
+				pen_distance = (uint32_t)(point_data[75] << 8) + (uint32_t)(point_data[76]);
+				pen_btn1 = (uint32_t)(point_data[77] & 0x01);
+				pen_btn2 = (uint32_t)((point_data[77] >> 1) & 0x01);
+				pen_battery = (uint32_t)point_data[78];
+//				printk("x=%d,y=%d,p=%d,tx=%d,ty=%d,d=%d,b1=%d,b2=%d,bat=%d\n", pen_x, pen_y, pen_pressure,
+//						pen_tilt_x, pen_tilt_y, pen_distance, pen_btn1, pen_btn2, pen_battery);
+
+				input_report_abs(ts->pen_input_dev, ABS_X, pen_x);
+				input_report_abs(ts->pen_input_dev, ABS_Y, pen_y);
+				input_report_abs(ts->pen_input_dev, ABS_PRESSURE, pen_pressure);
+				input_report_key(ts->pen_input_dev, BTN_TOUCH, !!pen_pressure);
+				input_report_abs(ts->pen_input_dev, ABS_TILT_X, pen_tilt_x);
+				input_report_abs(ts->pen_input_dev, ABS_TILT_Y, pen_tilt_y);
+				input_report_abs(ts->pen_input_dev, ABS_DISTANCE, pen_distance);
+				input_report_key(ts->pen_input_dev, BTN_TOOL_PEN, !!pen_distance || !!pen_pressure);
+				input_report_key(ts->pen_input_dev, BTN_STYLUS, pen_btn1);
+				input_report_key(ts->pen_input_dev, BTN_STYLUS2, pen_btn2);
+				input_sync(ts->pen_input_dev);
+				// TBD: pen battery event report
+				// NVT_LOG("pen_battery=%d\n", pen_battery);
+			} else if (pen_format_id == 0xF0) {
+				// report Pen ID
+			} else {
+				NVT_ERR("Unknown pen format id!\n");
+				goto XFER_ERROR;
+			}
+		} else { // pen_format_id = 0xFF, i.e. no pen present
+			release_pen_event();
+		}
+	} /* if (ts->pen_support) */
+
+XFER_ERROR:
+
+	mutex_unlock(&ts->lock);
+	return IRQ_HANDLED;
+}
+
+
+/*******************************************************
+Description:
+	Novatek touchscreen check chip version trim function.
+
+return:
+	Executive outcomes. 0---NVT IC. -1---not NVT IC.
+*******************************************************/
+static int8_t nvt_ts_check_chip_ver_trim(uint32_t chip_ver_trim_addr)
+{
+
+	ts->mmap = &NT36523_memory_map;
+	ts->carrier_system = NT36523_hw_info.carrier_system;
+	ts->hw_crc = NT36523_hw_info.hw_crc;
+	return 0;
+}
+
+static void nvt_suspend_work(struct work_struct *work)
+{
+	struct nvt_ts_data *ts_core = container_of(work, struct nvt_ts_data, suspend_work);
+	nvt_ts_suspend(&ts_core->client->dev);
+}
+
+static void nvt_resume_work(struct work_struct *work)
+{
+	struct nvt_ts_data *ts_core = container_of(work, struct nvt_ts_data, resume_work);
+	nvt_ts_resume(&ts_core->client->dev);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen driver probe function.
+
+return:
+	Executive outcomes. 0---succeed. negative---failed
+*******************************************************/
+static int32_t nvt_ts_probe(struct spi_device *client)
+{
+	int32_t ret = 0;
+#if (TOUCH_KEY_NUM > 0)
+	int32_t retry = 0;
+#endif
+
+	NVT_LOG("probe start\n");
+
+	ts = kzalloc(sizeof(struct nvt_ts_data), GFP_KERNEL);
+	if (ts == NULL) {
+		NVT_ERR("failed to allocated memory for nvt ts data\n");
+		return -ENOMEM;
+	}
+
+	ts->xbuf = (uint8_t *)kzalloc((NVT_TRANSFER_LEN+1+DUMMY_BYTES), GFP_KERNEL);
+	if(ts->xbuf == NULL) {
+		NVT_ERR("kzalloc for xbuf failed!\n");
+		ret = -ENOMEM;
+		goto err_malloc_xbuf;
+	}
+
+	ts->rbuf = (uint8_t *)kzalloc(NVT_READ_LEN, GFP_KERNEL);
+	if(ts->rbuf == NULL) {
+		NVT_ERR("kzalloc for rbuf failed!\n");
+		ret = -ENOMEM;
+		goto err_malloc_rbuf;
+	}
+
+	ts->client = client;
+	spi_set_drvdata(client, ts);
+
+	//---prepare for spi parameter---
+	if (ts->client->master->flags & SPI_MASTER_HALF_DUPLEX) {
+		NVT_ERR("Full duplex not supported by master\n");
+		ret = -EIO;
+		goto err_ckeck_full_duplex;
+	}
+	ts->client->bits_per_word = 8;
+	ts->client->mode = SPI_MODE_0;
+
+	ret = spi_setup(ts->client);
+	if (ret < 0) {
+		NVT_ERR("Failed to perform SPI setup\n");
+		goto err_spi_setup;
+	}
+
+#ifdef CONFIG_MTK_SPI
+    /* old usage of MTK spi API */
+    memcpy(&ts->spi_ctrl, &spi_ctrdata, sizeof(struct mt_chip_conf));
+    ts->client->controller_data = (void *)&ts->spi_ctrl;
+#endif
+
+#ifdef CONFIG_SPI_MT65XX
+    /* new usage of MTK spi API */
+    memcpy(&ts->spi_ctrl, &spi_ctrdata, sizeof(struct mtk_chip_config));
+    ts->client->controller_data = (void *)&ts->spi_ctrl;
+#endif
+
+	NVT_LOG("mode=%d, max_speed_hz=%d\n", ts->client->mode, ts->client->max_speed_hz);
+
+	//---parse dts---
+	ret = nvt_parse_dt(&client->dev);
+	if (ret) {
+		NVT_ERR("parse dt error\n");
+		goto err_spi_setup;
+	}
+
+	//---request and config GPIOs---
+	ret = nvt_gpio_config(ts);
+	if (ret) {
+		NVT_ERR("gpio config error!\n");
+		goto err_gpio_config_failed;
+	}
+
+	mutex_init(&ts->lock);
+	mutex_init(&ts->xbuf_lock);
+
+	//---eng reset before TP_RESX high
+	nvt_eng_reset();
+
+#if NVT_TOUCH_SUPPORT_HW_RST
+	gpio_set_value(ts->reset_gpio, 1);
+#endif
+
+	// need 10ms delay after POR(power on reset)
+	msleep(10);
+
+	//---check chip version trim---
+	ret = nvt_ts_check_chip_ver_trim(CHIP_VER_TRIM_ADDR);
+	if (ret) {
+		NVT_LOG("try to check from old chip ver trim address\n");
+		ret = nvt_ts_check_chip_ver_trim(CHIP_VER_TRIM_OLD_ADDR);
+		if (ret) {
+			NVT_ERR("chip is not identified\n");
+			ret = -EINVAL;
+			goto err_chipvertrim_failed;
+		}
+	}
+
+	ts->abs_x_max = TOUCH_DEFAULT_MAX_WIDTH;
+	ts->abs_y_max = TOUCH_DEFAULT_MAX_HEIGHT;
+
+	//---allocate input device---
+	ts->input_dev = input_allocate_device();
+	if (ts->input_dev == NULL) {
+		NVT_ERR("allocate input device failed\n");
+		ret = -ENOMEM;
+		goto err_input_dev_alloc_failed;
+	}
+
+	ts->max_touch_num = TOUCH_MAX_FINGER_NUM;
+
+#if TOUCH_KEY_NUM > 0
+	ts->max_button_num = TOUCH_KEY_NUM;
+#endif
+
+	ts->int_trigger_type = INT_TRIGGER_TYPE;
+
+	//---set input device info.---
+	ts->input_dev->evbit[0] = BIT_MASK(EV_SYN) | BIT_MASK(EV_KEY) | BIT_MASK(EV_ABS);
+	ts->input_dev->keybit[BIT_WORD(BTN_TOUCH)] = BIT_MASK(BTN_TOUCH);
+	ts->input_dev->propbit[0] = BIT(INPUT_PROP_DIRECT);
+
+	ts->db_wakeup = 0;
+	ts->fw_ver = 0;
+	ts->x_num = 32;
+	ts->y_num = 50;
+	ts->x_gang_num = 4;
+	ts->y_gang_num = 6;
+	ts->abs_x_max = TOUCH_DEFAULT_MAX_WIDTH;
+	ts->abs_y_max = TOUCH_DEFAULT_MAX_HEIGHT;
+	ts->max_button_num = TOUCH_KEY_NUM;
+	NVT_LOG("Set default fw_ver=%d, x_num=%d, y_num=%d, "
+					"abs_x_max=%d, abs_y_max=%d, max_button_num=%d!\n",
+					ts->fw_ver, ts->x_num, ts->y_num,
+					ts->abs_x_max, ts->abs_y_max, ts->max_button_num);
+
+#if MT_PROTOCOL_B
+	input_mt_init_slots(ts->input_dev, ts->max_touch_num, 0);
+#endif
+
+	input_set_abs_params(ts->input_dev, ABS_MT_PRESSURE, 0, TOUCH_FORCE_NUM, 0, 0);    //pressure = TOUCH_FORCE_NUM
+
+#if TOUCH_MAX_FINGER_NUM > 1
+	input_set_abs_params(ts->input_dev, ABS_MT_TOUCH_MAJOR, 0, 255, 0, 0);    //area = 255
+
+	input_set_abs_params(ts->input_dev, ABS_MT_POSITION_X, 0, ts->abs_x_max - 1, 0, 0);
+	input_set_abs_params(ts->input_dev, ABS_MT_POSITION_Y, 0, ts->abs_y_max - 1, 0, 0);
+#if MT_PROTOCOL_B
+	// no need to set ABS_MT_TRACKING_ID, input_mt_init_slots() already set it
+#else
+	input_set_abs_params(ts->input_dev, ABS_MT_TRACKING_ID, 0, ts->max_touch_num, 0, 0);
+#endif //MT_PROTOCOL_B
+#endif //TOUCH_MAX_FINGER_NUM > 1
+
+#if TOUCH_KEY_NUM > 0
+	for (retry = 0; retry < ts->max_button_num; retry++) {
+		input_set_capability(ts->input_dev, EV_KEY, touch_key_array[retry]);
+	}
+#endif
+
+	sprintf(ts->phys, "input/ts");
+	ts->input_dev->name = NVT_TS_NAME;
+	ts->input_dev->phys = ts->phys;
+	ts->input_dev->id.bustype = BUS_SPI;
+
+	//---register input device---
+	ret = input_register_device(ts->input_dev);
+	if (ret) {
+		NVT_ERR("register input device (%s) failed. ret=%d\n", ts->input_dev->name, ret);
+		goto err_input_register_device_failed;
+	}
+
+	if (ts->pen_support) {
+		//---allocate pen input device---
+		ts->pen_input_dev = input_allocate_device();
+		if (ts->pen_input_dev == NULL) {
+			NVT_ERR("allocate pen input device failed\n");
+			ret = -ENOMEM;
+			goto err_pen_input_dev_alloc_failed;
+		}
+
+		//---set pen input device info.---
+		ts->pen_input_dev->evbit[0] = BIT_MASK(EV_SYN) | BIT_MASK(EV_KEY) | BIT_MASK(EV_ABS);
+		ts->pen_input_dev->keybit[BIT_WORD(BTN_TOUCH)] = BIT_MASK(BTN_TOUCH);
+		ts->pen_input_dev->keybit[BIT_WORD(BTN_TOOL_PEN)] |= BIT_MASK(BTN_TOOL_PEN);
+		//ts->pen_input_dev->keybit[BIT_WORD(BTN_TOOL_RUBBER)] |= BIT_MASK(BTN_TOOL_RUBBER);
+		ts->pen_input_dev->keybit[BIT_WORD(BTN_STYLUS)] |= BIT_MASK(BTN_STYLUS);
+		ts->pen_input_dev->keybit[BIT_WORD(BTN_STYLUS2)] |= BIT_MASK(BTN_STYLUS2);
+		ts->pen_input_dev->propbit[0] = BIT(INPUT_PROP_DIRECT);
+
+		if (ts->wgp_stylus) {
+			input_set_abs_params(ts->pen_input_dev, ABS_X, 0, ts->abs_x_max * 2 - 1, 0, 0);
+			input_set_abs_params(ts->pen_input_dev, ABS_Y, 0, ts->abs_y_max * 2 - 1, 0, 0);
+		} else {
+			input_set_abs_params(ts->pen_input_dev, ABS_X, 0, ts->abs_x_max - 1, 0, 0);
+			input_set_abs_params(ts->pen_input_dev, ABS_Y, 0, ts->abs_y_max - 1, 0, 0);
+		}
+
+		input_set_abs_params(ts->pen_input_dev, ABS_PRESSURE, 0, PEN_PRESSURE_MAX, 0, 0);
+		input_set_abs_params(ts->pen_input_dev, ABS_DISTANCE, 0, PEN_DISTANCE_MAX, 0, 0);
+		input_set_abs_params(ts->pen_input_dev, ABS_TILT_X, PEN_TILT_MIN, PEN_TILT_MAX, 0, 0);
+		input_set_abs_params(ts->pen_input_dev, ABS_TILT_Y, PEN_TILT_MIN, PEN_TILT_MAX, 0, 0);
+
+		sprintf(ts->pen_phys, "input/pen");
+		ts->pen_input_dev->name = NVT_PEN_NAME;
+		ts->pen_input_dev->phys = ts->pen_phys;
+		ts->pen_input_dev->id.bustype = BUS_SPI;
+
+		//---register pen input device---
+		ret = input_register_device(ts->pen_input_dev);
+		if (ret) {
+			NVT_ERR("register pen input device (%s) failed. ret=%d\n", ts->pen_input_dev->name, ret);
+			goto err_pen_input_register_device_failed;
+		}
+	} /* if (ts->pen_support) */
+
+	//---set int-pin & request irq---
+	client->irq = gpio_to_irq(ts->irq_gpio);
+	if (client->irq) {
+		NVT_LOG("int_trigger_type=%d\n", ts->int_trigger_type);
+		ts->irq_enabled = true;
+		ret = request_threaded_irq(client->irq, NULL, nvt_ts_work_func,
+				ts->int_trigger_type | IRQF_ONESHOT, NVT_SPI_NAME, ts);
+		if (ret != 0) {
+			NVT_ERR("request irq failed. ret=%d\n", ret);
+			goto err_int_request_failed;
+		} else {
+			nvt_irq_enable(false);
+			NVT_LOG("request irq %d succeed\n", client->irq);
+		}
+	}
+
+	ts->pen_is_charge = false;
+
+	ts->lkdown_readed =false;
+	pm_stay_awake(&client->dev);
+
+	ts->ic_state = NVT_IC_INIT;
+	ts->dev_pm_suspend = false;
+	ts->gesture_command_delayed = -1;
+	init_completion(&ts->dev_pm_suspend_completion);
+	ts->fw_debug = false;
+
+#ifdef CONFIG_FACTORY_BUILD
+	ts->pen_input_dev_enable = 1;
+#else
+	ts->pen_input_dev_enable = 0;
+#endif
+
+#if BOOT_UPDATE_FIRMWARE
+	nvt_fwu_wq = alloc_workqueue("nvt_fwu_wq", WQ_UNBOUND | WQ_MEM_RECLAIM, 1);
+	if (!nvt_fwu_wq) {
+		NVT_ERR("nvt_fwu_wq create workqueue failed\n");
+		ret = -ENOMEM;
+		goto err_create_nvt_fwu_wq_failed;
+	}
+	INIT_DELAYED_WORK(&ts->nvt_fwu_work, Boot_Update_Firmware);
+	// please make sure boot update start after display reset(RESX) sequence
+	queue_delayed_work(nvt_fwu_wq, &ts->nvt_fwu_work, msecs_to_jiffies(14000));
+#endif
+
+	NVT_LOG("NVT_TOUCH_ESD_PROTECT is %d\n", NVT_TOUCH_ESD_PROTECT);
+#if NVT_TOUCH_ESD_PROTECT
+	INIT_DELAYED_WORK(&nvt_esd_check_work, nvt_esd_check_func);
+	nvt_esd_check_wq = alloc_workqueue("nvt_esd_check_wq", WQ_MEM_RECLAIM, 1);
+	if (!nvt_esd_check_wq) {
+		NVT_ERR("nvt_esd_check_wq create workqueue failed\n");
+		ret = -ENOMEM;
+		goto err_create_nvt_esd_check_wq_failed;
+	}
+	queue_delayed_work(nvt_esd_check_wq, &nvt_esd_check_work,
+			msecs_to_jiffies(NVT_TOUCH_ESD_CHECK_PERIOD));
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+	ts->event_wq = alloc_workqueue("nvt-event-queue",
+		WQ_UNBOUND | WQ_HIGHPRI | WQ_CPU_INTENSIVE, 1);
+	if (!ts->event_wq) {
+		NVT_ERR("Can not create work thread for suspend/resume!!");
+		ret = -ENOMEM;
+		goto err_alloc_work_thread_failed;
+	}
+	INIT_WORK(&ts->resume_work, nvt_resume_work);
+	INIT_WORK(&ts->suspend_work, nvt_suspend_work);
+
+#ifdef CONFIG_DRM
+	ts->drm_notif.notifier_call = nvt_drm_notifier_callback;
+	ret = mi_drm_register_client(&ts->drm_notif);
+	if(ret) {
+		NVT_ERR("register drm_notifier failed. ret=%d\n", ret);
+		goto err_register_drm_notif_failed;
+	}
+#endif
+
+	bTouchIsAwake = 1;
+	NVT_LOG("end\n");
+
+	nvt_irq_enable(true);
+
+	return 0;
+
+#ifdef CONFIG_DRM
+	if (mi_drm_unregister_client(&ts->drm_notif))
+		NVT_ERR("Error occurred while unregistering drm_notifier.\n");
+err_register_drm_notif_failed:
+#endif
+
+err_alloc_work_thread_failed:
+
+#if NVT_TOUCH_ESD_PROTECT
+	if (nvt_esd_check_wq) {
+		cancel_delayed_work_sync(&nvt_esd_check_work);
+		destroy_workqueue(nvt_esd_check_wq);
+		nvt_esd_check_wq = NULL;
+	}
+err_create_nvt_esd_check_wq_failed:
+#endif
+#if BOOT_UPDATE_FIRMWARE
+	if (nvt_fwu_wq) {
+		cancel_delayed_work_sync(&ts->nvt_fwu_work);
+		destroy_workqueue(nvt_fwu_wq);
+		nvt_fwu_wq = NULL;
+	}
+err_create_nvt_fwu_wq_failed:
+
+#endif
+	free_irq(client->irq, ts);
+err_int_request_failed:
+	if (ts->pen_support) {
+		input_unregister_device(ts->pen_input_dev);
+		ts->pen_input_dev = NULL;
+	}
+err_pen_input_register_device_failed:
+	if (ts->pen_support) {
+		if (ts->pen_input_dev) {
+			input_free_device(ts->pen_input_dev);
+			ts->pen_input_dev = NULL;
+		}
+	}
+err_pen_input_dev_alloc_failed:
+	input_unregister_device(ts->input_dev);
+	ts->input_dev = NULL;
+err_input_register_device_failed:
+	if (ts->input_dev) {
+		input_free_device(ts->input_dev);
+		ts->input_dev = NULL;
+	}
+err_input_dev_alloc_failed:
+err_chipvertrim_failed:
+	mutex_destroy(&ts->xbuf_lock);
+	mutex_destroy(&ts->lock);
+	nvt_gpio_deconfig(ts);
+err_gpio_config_failed:
+err_spi_setup:
+err_ckeck_full_duplex:
+	spi_set_drvdata(client, NULL);
+	if (ts->rbuf) {
+		kfree(ts->rbuf);
+		ts->rbuf = NULL;
+	}
+err_malloc_rbuf:
+	if (ts->xbuf) {
+		kfree(ts->xbuf);
+		ts->xbuf = NULL;
+	}
+err_malloc_xbuf:
+	if (ts) {
+		kfree(ts);
+		ts = NULL;
+	}
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen driver release function.
+
+return:
+	Executive outcomes. 0---succeed.
+*******************************************************/
+static void nvt_ts_remove(struct spi_device *client)
+{
+	NVT_LOG("Removing driver...\n");
+
+#ifdef CONFIG_DRM
+	if (mi_drm_unregister_client(&ts->drm_notif))
+		NVT_ERR("Error occurred while unregistering drm_notifier.\n");
+#endif
+
+#if NVT_TOUCH_ESD_PROTECT
+	if (nvt_esd_check_wq) {
+		cancel_delayed_work_sync(&nvt_esd_check_work);
+		nvt_esd_check_enable(false);
+		destroy_workqueue(nvt_esd_check_wq);
+		nvt_esd_check_wq = NULL;
+	}
+#endif
+
+#if BOOT_UPDATE_FIRMWARE
+	if (nvt_fwu_wq) {
+		cancel_delayed_work_sync(&ts->nvt_fwu_work);
+		destroy_workqueue(nvt_fwu_wq);
+		nvt_fwu_wq = NULL;
+	}
+#endif
+
+	nvt_irq_enable(false);
+	free_irq(client->irq, ts);
+
+	mutex_destroy(&ts->xbuf_lock);
+	mutex_destroy(&ts->lock);
+
+	nvt_gpio_deconfig(ts);
+
+	if (ts->pen_support) {
+		if (ts->pen_input_dev) {
+			input_unregister_device(ts->pen_input_dev);
+			ts->pen_input_dev = NULL;
+		}
+	}
+
+	if (ts->input_dev) {
+		input_unregister_device(ts->input_dev);
+		ts->input_dev = NULL;
+	}
+
+	spi_set_drvdata(client, NULL);
+
+	if (ts) {
+		kfree(ts);
+		ts = NULL;
+	}
+}
+
+static void nvt_ts_shutdown(struct spi_device *client)
+{
+	NVT_LOG("Shutdown driver...\n");
+
+	nvt_irq_enable(false);
+
+#ifdef CONFIG_DRM
+	if (mi_drm_unregister_client(&ts->drm_notif))
+		NVT_ERR("Error occurred while unregistering drm_notifier.\n");
+#endif
+
+	destroy_workqueue(ts->event_wq);
+
+#if NVT_TOUCH_ESD_PROTECT
+	if (nvt_esd_check_wq) {
+		cancel_delayed_work_sync(&nvt_esd_check_work);
+		nvt_esd_check_enable(false);
+		destroy_workqueue(nvt_esd_check_wq);
+		nvt_esd_check_wq = NULL;
+	}
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+#if BOOT_UPDATE_FIRMWARE
+	if (nvt_fwu_wq) {
+		cancel_delayed_work_sync(&ts->nvt_fwu_work);
+		destroy_workqueue(nvt_fwu_wq);
+		nvt_fwu_wq = NULL;
+	}
+#endif
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen driver suspend function.
+
+return:
+	Executive outcomes. 0---succeed.
+*******************************************************/
+static int32_t nvt_ts_suspend(struct device *dev)
+{
+	uint8_t buf[4] = {0};
+#if MT_PROTOCOL_B
+	uint32_t i = 0;
+#endif
+
+	if (!bTouchIsAwake) {
+		NVT_LOG("Touch is already suspend\n");
+		return 0;
+	}
+
+	pm_stay_awake(dev);
+	ts->ic_state = NVT_IC_SUSPEND_IN;
+
+	if (!ts->db_wakeup) {
+		if (!ts->irq_enabled)
+			NVT_LOG("IRQ already disabled\n");
+		else
+			nvt_irq_enable(false);
+	}
+
+#if NVT_TOUCH_ESD_PROTECT
+	NVT_LOG("cancel delayed work sync\n");
+	cancel_delayed_work_sync(&nvt_esd_check_work);
+	nvt_esd_check_enable(false);
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+	mutex_lock(&ts->lock);
+
+	NVT_LOG("suspend start\n");
+
+	bTouchIsAwake = 0;
+
+	if (ts->pen_input_dev_enable) {
+		NVT_LOG("if enable pen,will close it");
+	}
+
+	if (ts->db_wakeup) {
+		/*---write command to enter "wakeup gesture mode"---*/
+		/*DoubleClick wakeup CMD was sent by display to meet timing*/
+		/*
+		buf[0] = EVENT_MAP_HOST_CMD;
+		buf[1] = 0x13;
+		CTP_SPI_WRITE(ts->client, buf, 2);
+		*/
+		enable_irq_wake(ts->client->irq);
+
+		NVT_LOG("Enabled touch wakeup gesture\n");
+	} else {
+		/*---write command to enter "deep sleep mode"---*/
+		buf[0] = EVENT_MAP_HOST_CMD;
+		buf[1] = 0x11;
+		CTP_SPI_WRITE(ts->client, buf, 2);
+	}
+
+	mutex_unlock(&ts->lock);
+
+	/* release all touches */
+#if MT_PROTOCOL_B
+	for (i = 0; i < ts->max_touch_num; i++) {
+		input_mt_slot(ts->input_dev, i);
+		input_report_abs(ts->input_dev, ABS_MT_TOUCH_MAJOR, 0);
+		input_report_abs(ts->input_dev, ABS_MT_PRESSURE, 0);
+		input_mt_report_slot_state(ts->input_dev, MT_TOOL_FINGER, 0);
+	}
+#endif
+	input_report_key(ts->input_dev, BTN_TOUCH, 0);
+#if !MT_PROTOCOL_B
+	input_mt_sync(ts->input_dev);
+#endif
+	input_sync(ts->input_dev);
+
+	msleep(50);
+	/* release pen event */
+	release_pen_event();
+	if (likely(ts->ic_state == NVT_IC_SUSPEND_IN))
+		ts->ic_state = NVT_IC_SUSPEND_OUT;
+	else
+		NVT_ERR("IC state may error,caused by suspend/resume flow, please CHECK!!");
+	pm_relax(dev);
+	NVT_LOG("end\n");
+
+	return 0;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen driver resume function.
+
+return:
+	Executive outcomes. 0---succeed.
+*******************************************************/
+static int32_t nvt_ts_resume(struct device *dev)
+{
+	int ret = 0;
+	if (bTouchIsAwake) {
+		NVT_LOG("Touch is already resume\n");
+		return 0;
+	}
+
+	if (ts->dev_pm_suspend)
+		pm_stay_awake(dev);
+
+	mutex_lock(&ts->lock);
+
+	NVT_LOG("resume start\n");
+	ts->ic_state = NVT_IC_RESUME_IN;
+
+	// please make sure display reset(RESX) sequence and mipi dsi cmds sent before this
+#if NVT_TOUCH_SUPPORT_HW_RST
+	gpio_set_value(ts->reset_gpio, 1);
+#endif
+	ret = nvt_update_firmware(ts->fw_name);
+	if (ret)
+		NVT_ERR("download firmware failed\n");
+
+	nvt_check_fw_reset_state(RESET_STATE_REK);
+
+	if (!ts->db_wakeup && !ts->irq_enabled) {
+		nvt_irq_enable(true);
+	}
+
+#if NVT_TOUCH_ESD_PROTECT
+	nvt_esd_check_enable(false);
+	queue_delayed_work(nvt_esd_check_wq, &nvt_esd_check_work,
+			msecs_to_jiffies(NVT_TOUCH_ESD_CHECK_PERIOD));
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+	bTouchIsAwake = 1;
+
+	mutex_unlock(&ts->lock);
+
+	if (likely(ts->ic_state == NVT_IC_RESUME_IN)) {
+		ts->ic_state = NVT_IC_RESUME_OUT;
+	} else {
+		NVT_ERR("IC state may error,caused by suspend/resume flow, please CHECK!!");
+	}
+	if (ts->gesture_command_delayed >= 0){
+		ts->db_wakeup = ts->gesture_command_delayed;
+		ts->gesture_command_delayed = -1;
+		NVT_LOG("execute delayed command, set double click wakeup %d\n", ts->db_wakeup);
+	}
+
+	if (ts->dev_pm_suspend)
+		pm_relax(dev);
+	NVT_LOG("end\n");
+
+	return 0;
+}
+
+
+#ifdef CONFIG_DRM
+static int nvt_drm_notifier_callback(struct notifier_block *self, unsigned long event, void *data)
+{
+	int blank = *(enum drm_notifier_data *)data;
+	struct nvt_ts_data *ts_data =
+		container_of(self, struct nvt_ts_data, drm_notif);
+
+	if (data && ts_data) {
+		if (event == MI_DRM_EARLY_EVENT_BLANK) {
+			if (blank == MI_DRM_BLANK_POWERDOWN) {
+				NVT_LOG("event=%lu, *blank=%d\n", event, blank);
+				flush_workqueue(ts_data->event_wq);
+				queue_work(ts_data->event_wq, &ts_data->suspend_work);
+			}
+		} else if (event == MI_DRM_EVENT_BLANK) {
+			if (blank == MI_DRM_BLANK_UNBLANK) {
+				NVT_LOG("event=%lu, *blank=%d\n", event, blank);
+				flush_workqueue(ts_data->event_wq);
+				queue_work(ts_data->event_wq, &ts_data->resume_work);
+			}
+		}
+	}
+
+	return 0;
+}
+#endif
+
+static int nvt_pm_suspend(struct device *dev)
+{
+	if (device_may_wakeup(dev) && ts->db_wakeup) {
+		NVT_LOG("enable touch irq wake\n");
+		enable_irq_wake(ts->client->irq);
+	}
+	ts->dev_pm_suspend = true;
+	reinit_completion(&ts->dev_pm_suspend_completion);
+
+	return 0;
+}
+
+static int nvt_pm_resume(struct device *dev)
+{
+	if (device_may_wakeup(dev) && ts->db_wakeup) {
+		NVT_LOG("disable touch irq wake\n");
+		disable_irq_wake(ts->client->irq);
+	}
+	ts->dev_pm_suspend = false;
+	complete(&ts->dev_pm_suspend_completion);
+
+	return 0;
+}
+
+static const struct dev_pm_ops nvt_dev_pm_ops = {
+	.suspend = nvt_pm_suspend,
+	.resume = nvt_pm_resume,
+};
+
+static const struct spi_device_id nvt_ts_id[] = {
+	{ NVT_SPI_NAME, 0 },
+	{ }
+};
+
+#ifdef CONFIG_OF
+static struct of_device_id nvt_match_table[] = {
+	{ .compatible = "novatek,NVT-ts-spi",},
+	{ },
+};
+#endif
+
+static struct spi_driver nvt_spi_driver = {
+	.probe		= nvt_ts_probe,
+	.remove		= nvt_ts_remove,
+	.shutdown	= nvt_ts_shutdown,
+	.id_table	= nvt_ts_id,
+	.driver = {
+		.name	= NVT_SPI_NAME,
+		.owner	= THIS_MODULE,
+#ifdef CONFIG_PM
+		.pm = &nvt_dev_pm_ops,
+#endif
+#ifdef CONFIG_OF
+		.of_match_table = nvt_match_table,
+#endif
+	},
+};
+
+module_spi_driver(nvt_spi_driver);
+
+MODULE_DESCRIPTION("Novatek Touchscreen Driver");
+MODULE_LICENSE("GPL");
diff --git a/drivers/input/touchscreen/nt36523/nt36xxx.h b/drivers/input/touchscreen/nt36523/nt36xxx.h
new file mode 100644
index 000000000000..2ec9ccb3b522
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/nt36xxx.h
@@ -0,0 +1,240 @@
+/*
+ * Copyright (C) 2010 - 2018 Novatek, Inc.
+ * Copyright (C) 2021 XiaoMi, Inc.
+ *
+ * $Revision: 69262 $
+ * $Date: 2020-09-23 15:07:14 +0800 (週三, 23 九月 2020) $
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+ * more details.
+ *
+ */
+#ifndef 	_LINUX_NVT_TOUCH_H
+#define		_LINUX_NVT_TOUCH_H
+
+#include <linux/delay.h>
+#include <linux/input.h>
+#include <linux/of.h>
+#include <linux/spi/spi.h>
+#include <linux/uaccess.h>
+
+#include "nt36xxx_mem_map.h"
+
+#define NVT_DEBUG 1
+
+//---GPIO number---
+#define NVTTOUCH_RST_PIN 980
+#define NVTTOUCH_INT_PIN 943
+
+#define PINCTRL_STATE_ACTIVE		"pmx_ts_active"
+#define PINCTRL_STATE_SUSPEND		"pmx_ts_suspend"
+
+//---INT trigger mode---
+//#define IRQ_TYPE_EDGE_RISING 1
+//#define IRQ_TYPE_EDGE_FALLING 2
+#define INT_TRIGGER_TYPE IRQ_TYPE_EDGE_RISING
+
+
+//---SPI driver info.---
+#define NVT_SPI_NAME "NVT-ts"
+
+#if NVT_DEBUG
+#define NVT_LOG(fmt, args...)    pr_err("[%s] %s %d: " fmt, NVT_SPI_NAME, __func__, __LINE__, ##args)
+#else
+#define NVT_LOG(fmt, args...)    pr_info("[%s] %s %d: " fmt, NVT_SPI_NAME, __func__, __LINE__, ##args)
+#endif
+#define NVT_ERR(fmt, args...)    pr_err("[%s] %s %d: " fmt, NVT_SPI_NAME, __func__, __LINE__, ##args)
+
+//---Input device info.---
+#define NVT_TS_NAME "NVTCapacitiveTouchScreen"
+#define NVT_PEN_NAME "NVTCapacitivePen"
+
+//---Touch info.---
+#define TOUCH_DEFAULT_MAX_WIDTH 1600
+#define TOUCH_DEFAULT_MAX_HEIGHT 2560
+#define TOUCH_MAX_FINGER_NUM 10
+#define TOUCH_KEY_NUM 0
+#if TOUCH_KEY_NUM > 0
+extern const uint16_t touch_key_array[TOUCH_KEY_NUM];
+#endif
+#define TOUCH_FORCE_NUM 1000
+//---for Pen---
+#define PEN_PRESSURE_MAX (4095)
+#define PEN_DISTANCE_MAX (1)
+#define PEN_TILT_MIN (-60)
+#define PEN_TILT_MAX (60)
+
+/* Enable only when module have tp reset pin and connected to host */
+#define NVT_TOUCH_SUPPORT_HW_RST 0
+
+//---Customerized func.---
+#define NVT_TOUCH_MP 0
+#define NVT_TOUCH_MP_SETTING_CRITERIA_FROM_CSV 0
+#define MT_PROTOCOL_B 1
+#define FUNCPAGE_PALM 4
+#define PACKET_PALM_ON 3
+#define PACKET_PALM_OFF 4
+
+#define BOOT_UPDATE_FIRMWARE 1
+#define DEFAULT_BOOT_UPDATE_FIRMWARE_NAME "novatek/nt36523.bin"
+#define DEFAULT_MP_UPDATE_FIRMWARE_NAME   "novatek_ts_mp.bin"
+
+//---ESD Protect.---
+#define NVT_TOUCH_ESD_PROTECT 1
+#define NVT_TOUCH_ESD_CHECK_PERIOD 1500	/* ms */
+#define NVT_TOUCH_WDT_RECOVERY 1
+
+enum nvt_ic_state {
+	NVT_IC_SUSPEND_IN,
+	NVT_IC_SUSPEND_OUT,
+	NVT_IC_RESUME_IN,
+	NVT_IC_RESUME_OUT,
+	NVT_IC_INIT,
+};
+
+struct nvt_config_info {
+	u8 tp_vendor;
+	u8 tp_color;
+	u8 display_maker;
+	u8 glass_vendor;
+	const char *nvt_fw_name;
+	const char *nvt_mp_name;
+	const char *nvt_limit_name;
+};
+
+struct nvt_ts_data {
+	struct spi_device *client;
+	struct input_dev *input_dev;
+	struct delayed_work nvt_fwu_work;
+	struct work_struct switch_mode_work;
+	struct work_struct pen_charge_state_change_work;
+	bool pen_is_charge;
+	struct notifier_block pen_charge_state_notifier;
+	uint16_t addr;
+	int8_t phys[32];
+#if defined(CONFIG_FB)
+#ifdef CONFIG_DRM
+	struct notifier_block drm_notif;
+#else
+	struct notifier_block fb_notif;
+#endif
+#endif
+	uint32_t config_array_size;
+	struct nvt_config_info *config_array;
+	const char *fw_name;
+	bool lkdown_readed;
+	uint8_t fw_ver;
+	uint8_t x_num;
+	uint8_t y_num;
+	int ic_state;
+	uint16_t abs_x_max;
+	uint16_t abs_y_max;
+	uint8_t max_touch_num;
+	uint8_t max_button_num;
+	uint32_t int_trigger_type;
+	int32_t irq_gpio;
+	uint32_t irq_flags;
+	int32_t reset_gpio;
+	uint32_t reset_flags;
+	struct mutex lock;
+	const struct nvt_ts_mem_map *mmap;
+	uint8_t carrier_system;
+	uint8_t hw_crc;
+	uint16_t nvt_pid;
+	uint8_t *rbuf;
+	uint8_t *xbuf;
+	struct mutex xbuf_lock;
+	bool irq_enabled;
+	uint8_t cascade;
+	bool pen_support;
+	bool wgp_stylus;
+	uint8_t x_gang_num;
+	uint8_t y_gang_num;
+	struct input_dev *pen_input_dev;
+	bool pen_input_dev_enable;
+	int8_t pen_phys[32];
+	struct workqueue_struct *event_wq;
+	struct work_struct suspend_work;
+	struct work_struct resume_work;
+	int result_type;
+	int panel_index;
+	uint32_t spi_max_freq;
+	int db_wakeup;
+	uint8_t debug_flag;
+	bool fw_debug;
+	bool dev_pm_suspend;
+	struct completion dev_pm_suspend_completion;
+	bool palm_sensor_switch;
+	int gesture_command_delayed;
+	struct pinctrl *ts_pinctrl;
+	struct pinctrl_state *pinctrl_state_active;
+	struct pinctrl_state *pinctrl_state_suspend;
+};
+
+typedef enum {
+	RESET_STATE_INIT = 0xA0,// IC reset
+	RESET_STATE_REK,		// ReK baseline
+	RESET_STATE_REK_FINISH,	// baseline is ready
+	RESET_STATE_NORMAL_RUN,	// normal run
+	RESET_STATE_MAX  = 0xAF
+} RST_COMPLETE_STATE;
+
+typedef enum {
+    EVENT_MAP_HOST_CMD                      = 0x50,
+    EVENT_MAP_HANDSHAKING_or_SUB_CMD_BYTE   = 0x51,
+    EVENT_MAP_RESET_COMPLETE                = 0x60,
+    EVENT_MAP_FWINFO                        = 0x78,
+    EVENT_MAP_PROJECTID                     = 0x9A,
+} SPI_EVENT_MAP;
+
+//---SPI READ/WRITE---
+#define SPI_WRITE_MASK(a)	(a | 0x80)
+#define SPI_READ_MASK(a)	(a & 0x7F)
+
+#define DUMMY_BYTES (1)
+#define NVT_TRANSFER_LEN	(63*1024)
+#define NVT_READ_LEN		(2*1024)
+
+typedef enum {
+	NVTWRITE = 0,
+	NVTREAD  = 1
+} NVT_SPI_RW;
+
+//---extern structures---
+extern struct nvt_ts_data *ts;
+
+//---extern functions---
+int32_t CTP_SPI_READ(struct spi_device *client, uint8_t *buf, uint16_t len);
+int32_t CTP_SPI_WRITE(struct spi_device *client, uint8_t *buf, uint16_t len);
+void nvt_bootloader_reset(void);
+void nvt_eng_reset(void);
+void nvt_sw_reset(void);
+void nvt_sw_reset_idle(void);
+void nvt_boot_ready(void);
+void nvt_bld_crc_enable(void);
+void nvt_fw_crc_enable(void);
+void nvt_tx_auto_copy_mode(void);
+void nvt_set_dbgfw_status(bool enable);
+void nvt_match_fw(void);
+int32_t nvt_update_firmware(const char *firmware_name);
+int32_t nvt_check_fw_reset_state(RST_COMPLETE_STATE check_reset_state);
+int32_t nvt_get_fw_info(void);
+int32_t nvt_clear_fw_status(void);
+int32_t nvt_check_fw_status(void);
+int32_t nvt_check_spi_dma_tx_info(void);
+int32_t nvt_set_page(uint32_t addr);
+int32_t nvt_write_addr(uint32_t addr, uint8_t data);
+bool nvt_get_dbgfw_status(void);
+int32_t nvt_set_pocket_palm_switch(uint8_t pocket_palm_switch);
+#if NVT_TOUCH_ESD_PROTECT
+extern void nvt_esd_check_enable(uint8_t enable);
+#endif /* #if NVT_TOUCH_ESD_PROTECT */
+
+#endif /* _LINUX_NVT_TOUCH_H */
diff --git a/drivers/input/touchscreen/nt36523/nt36xxx_fw_update.c b/drivers/input/touchscreen/nt36523/nt36xxx_fw_update.c
new file mode 100644
index 000000000000..4f383dac2c3c
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/nt36xxx_fw_update.c
@@ -0,0 +1,857 @@
+/*
+ * Copyright (C) 2010 - 2018 Novatek, Inc.
+ * Copyright (C) 2021 XiaoMi, Inc.
+ *
+ * $Revision: 68983 $
+ * $Date: 2020-09-17 09:43:23 +0800 (週四, 17 九月 2020) $
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+ * more details.
+ *
+ */
+
+#include <linux/firmware.h>
+#include <linux/gpio.h>
+
+#include "nt36xxx.h"
+
+#if BOOT_UPDATE_FIRMWARE
+
+#define SIZE_4KB 4096
+#define FLASH_SECTOR_SIZE SIZE_4KB
+#define FW_BIN_VER_OFFSET (fw_need_write_size - SIZE_4KB)
+#define FW_BIN_VER_BAR_OFFSET (FW_BIN_VER_OFFSET + 1)
+#define NVT_FLASH_END_FLAG_LEN 3
+#define NVT_FLASH_END_FLAG_ADDR (fw_need_write_size - NVT_FLASH_END_FLAG_LEN)
+
+static ktime_t start, end;
+const struct firmware *fw_entry = NULL;
+static size_t fw_need_write_size = 0;
+static uint8_t *fwbuf = NULL;
+
+struct nvt_ts_bin_map {
+	char name[12];
+	uint32_t BIN_addr;
+	uint32_t SRAM_addr;
+	uint32_t size;
+	uint32_t crc;
+};
+
+static struct nvt_ts_bin_map *bin_map;
+
+/*******************************************************
+Description:
+	Novatek touchscreen init variable and allocate buffer
+for download firmware function.
+
+return:
+	n.a.
+*******************************************************/
+static int32_t nvt_download_init(void)
+{
+	/* allocate buffer for transfer firmware */
+	//NVT_LOG("NVT_TRANSFER_LEN = 0x%06X\n", NVT_TRANSFER_LEN);
+
+	if (fwbuf == NULL) {
+		fwbuf = (uint8_t *)kzalloc((NVT_TRANSFER_LEN + 1 + DUMMY_BYTES), GFP_KERNEL);
+		if(fwbuf == NULL) {
+			NVT_ERR("kzalloc for fwbuf failed!\n");
+			return -ENOMEM;
+		}
+	}
+
+	return 0;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen checksum function. Calculate bin
+file checksum for comparison.
+
+return:
+	n.a.
+*******************************************************/
+static uint32_t CheckSum(const u8 *data, size_t len)
+{
+	uint32_t i = 0;
+	uint32_t checksum = 0;
+
+	for (i = 0 ; i < len+1 ; i++)
+		checksum += data[i];
+
+	checksum += len;
+	checksum = ~checksum +1;
+
+	return checksum;
+}
+
+static uint32_t byte_to_word(const uint8_t *data)
+{
+	return data[0] + (data[1] << 8) + (data[2] << 16) + (data[3] << 24);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen parsing bin header function.
+
+return:
+	n.a.
+*******************************************************/
+static uint32_t partition = 0;
+static uint8_t ilm_dlm_num = 2;
+static uint8_t cascade_2nd_header_info = 0;
+static int32_t nvt_bin_header_parser(const u8 *fwdata, size_t fwsize)
+{
+	uint32_t list = 0;
+	uint32_t pos = 0x00;
+	uint32_t end = 0x00;
+	uint8_t info_sec_num = 0;
+	uint8_t ovly_sec_num = 0;
+	uint8_t ovly_info = 0;
+	uint8_t find_bin_header = 0;
+
+	/* Find the header size */
+	end = fwdata[0] + (fwdata[1] << 8) + (fwdata[2] << 16) + (fwdata[3] << 24);
+
+	/* check cascade next header */
+	cascade_2nd_header_info = (fwdata[0x20] & 0x02) >> 1;
+	NVT_LOG("cascade_2nd_header_info = %d\n", cascade_2nd_header_info);
+
+	if (cascade_2nd_header_info) {
+		pos = 0x30;	// info section start at 0x30 offset
+		while (pos < (end / 2)) {
+			info_sec_num ++;
+			pos += 0x10;	/* each header info is 16 bytes */
+		}
+
+		info_sec_num = info_sec_num + 1; //next header section
+	} else {
+		pos = 0x30;	// info section start at 0x30 offset
+		while (pos < end) {
+			info_sec_num ++;
+			pos += 0x10;	/* each header info is 16 bytes */
+		}
+	}
+
+	/*
+	 * Find the DLM OVLY section
+	 * [0:3] Overlay Section Number
+	 * [4]   Overlay Info
+	 */
+	ovly_info = (fwdata[0x28] & 0x10) >> 4;
+	ovly_sec_num = (ovly_info) ? (fwdata[0x28] & 0x0F) : 0;
+
+	/*
+	 * calculate all partition number
+	 * ilm_dlm_num (ILM & DLM) + ovly_sec_num + info_sec_num
+	 */
+	partition = ilm_dlm_num + ovly_sec_num + info_sec_num;
+	NVT_LOG("ovly_info = %d, ilm_dlm_num = %d, ovly_sec_num = %d, info_sec_num = %d, partition = %d\n",
+			ovly_info, ilm_dlm_num, ovly_sec_num, info_sec_num, partition);
+
+	/* allocated memory for header info */
+	bin_map = (struct nvt_ts_bin_map *)kzalloc((partition+1) * sizeof(struct nvt_ts_bin_map), GFP_KERNEL);
+	if(bin_map == NULL) {
+		NVT_ERR("kzalloc for bin_map failed!\n");
+		return -ENOMEM;
+	}
+
+	for (list = 0; list < partition; list++) {
+		/*
+		 * [1] parsing ILM & DLM header info
+		 * BIN_addr : SRAM_addr : size (12-bytes)
+		 * crc located at 0x18 & 0x1C
+		 */
+		if (list < ilm_dlm_num) {
+			bin_map[list].BIN_addr = byte_to_word(&fwdata[0 + list*12]);
+			bin_map[list].SRAM_addr = byte_to_word(&fwdata[4 + list*12]);
+			bin_map[list].size = byte_to_word(&fwdata[8 + list*12]);
+			if (ts->hw_crc)
+				bin_map[list].crc = byte_to_word(&fwdata[0x18 + list*4]);
+			else { //ts->hw_crc
+				if ((bin_map[list].BIN_addr + bin_map[list].size) < fwsize)
+					bin_map[list].crc = CheckSum(&fwdata[bin_map[list].BIN_addr], bin_map[list].size);
+				else {
+					NVT_ERR("access range (0x%08X to 0x%08X) is larger than bin size!\n",
+							bin_map[list].BIN_addr, bin_map[list].BIN_addr + bin_map[list].size);
+					return -EINVAL;
+				}
+			} //ts->hw_crc
+			if (list == 0)
+				sprintf(bin_map[list].name, "ILM");
+			else if (list == 1)
+				sprintf(bin_map[list].name, "DLM");
+		}
+
+		/*
+		 * [2] parsing others header info
+		 * SRAM_addr : size : BIN_addr : crc (16-bytes)
+		 */
+		if ((list >= ilm_dlm_num) && (list < (ilm_dlm_num + info_sec_num))) {
+			if (find_bin_header == 0) {
+				/* others partition located at 0x30 offset */
+				pos = 0x30 + (0x10 * (list - ilm_dlm_num));
+			} else if (find_bin_header && cascade_2nd_header_info) {
+				/* cascade 2nd header info */
+				pos = end - 0x10;
+			}
+
+			bin_map[list].SRAM_addr = byte_to_word(&fwdata[pos]);
+			bin_map[list].size = byte_to_word(&fwdata[pos+4]);
+			bin_map[list].BIN_addr = byte_to_word(&fwdata[pos+8]);
+			if (ts->hw_crc)
+				bin_map[list].crc = byte_to_word(&fwdata[pos+12]);
+			else { //ts->hw_crc
+				if ((bin_map[list].BIN_addr + bin_map[list].size) < fwsize)
+					bin_map[list].crc = CheckSum(&fwdata[bin_map[list].BIN_addr], bin_map[list].size);
+				else {
+					NVT_ERR("access range (0x%08X to 0x%08X) is larger than bin size!\n",
+							bin_map[list].BIN_addr, bin_map[list].BIN_addr + bin_map[list].size);
+					return -EINVAL;
+				}
+			} //ts->hw_crc
+			/* detect header end to protect parser function */
+			if ((bin_map[list].BIN_addr < end) && (bin_map[list].size != 0)) {
+				sprintf(bin_map[list].name, "Header");
+				find_bin_header = 1;
+			} else {
+				sprintf(bin_map[list].name, "Info-%d", (list - ilm_dlm_num));
+			}
+		}
+
+		/*
+		 * [3] parsing overlay section header info
+		 * SRAM_addr : size : BIN_addr : crc (16-bytes)
+		 */
+		if (list >= (ilm_dlm_num + info_sec_num)) {
+			/* overlay info located at DLM (list = 1) start addr */
+			pos = bin_map[1].BIN_addr + (0x10 * (list- ilm_dlm_num - info_sec_num));
+
+			bin_map[list].SRAM_addr = byte_to_word(&fwdata[pos]);
+			bin_map[list].size = byte_to_word(&fwdata[pos+4]);
+			bin_map[list].BIN_addr = byte_to_word(&fwdata[pos+8]);
+			if (ts->hw_crc)
+				bin_map[list].crc = byte_to_word(&fwdata[pos+12]);
+			else { //ts->hw_crc
+				if ((bin_map[list].BIN_addr + bin_map[list].size) < fwsize)
+					bin_map[list].crc = CheckSum(&fwdata[bin_map[list].BIN_addr], bin_map[list].size);
+				else {
+					NVT_ERR("access range (0x%08X to 0x%08X) is larger than bin size!\n",
+							bin_map[list].BIN_addr, bin_map[list].BIN_addr + bin_map[list].size);
+					return -EINVAL;
+				}
+			} //ts->hw_crc
+			sprintf(bin_map[list].name, "Overlay-%d", (list- ilm_dlm_num - info_sec_num));
+		}
+
+		/* BIN size error detect */
+		if ((bin_map[list].BIN_addr + bin_map[list].size) > fwsize) {
+			NVT_ERR("access range (0x%08X to 0x%08X) is larger than bin size!\n",
+					bin_map[list].BIN_addr, bin_map[list].BIN_addr + bin_map[list].size);
+			return -EINVAL;
+		}
+
+//		NVT_LOG("[%d][%s] SRAM (0x%08X), SIZE (0x%08X), BIN (0x%08X), CRC (0x%08X)\n",
+//				list, bin_map[list].name,
+//				bin_map[list].SRAM_addr, bin_map[list].size,  bin_map[list].BIN_addr, bin_map[list].crc);
+	}
+
+	return 0;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen release update firmware function.
+
+return:
+	n.a.
+*******************************************************/
+static void update_firmware_release(void)
+{
+	if (fw_entry) {
+		release_firmware(fw_entry);
+	}
+
+	fw_entry = NULL;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen request update firmware function.
+
+return:
+	Executive outcomes. 0---succeed. -1,-22---failed.
+*******************************************************/
+static int32_t update_firmware_request(const char *filename)
+{
+	uint8_t retry = 0;
+	int32_t ret = 0;
+
+	if (NULL == filename) {
+		return -ENOENT;
+	}
+
+	while (1) {
+		NVT_LOG("filename is %s\n", filename);
+
+		ret = request_firmware(&fw_entry, filename, &ts->client->dev);
+		if (ret) {
+			NVT_ERR("firmware load failed, ret=%d\n", ret);
+			goto request_fail;
+		}
+
+		fw_need_write_size = fw_entry->size;
+
+		// check if FW version add FW version bar equals 0xFF
+		if (*(fw_entry->data + FW_BIN_VER_OFFSET) + *(fw_entry->data + FW_BIN_VER_BAR_OFFSET) != 0xFF) {
+			NVT_ERR("bin file FW_VER + FW_VER_BAR should be 0xFF!\n");
+			NVT_ERR("FW_VER=0x%02X, FW_VER_BAR=0x%02X\n", *(fw_entry->data+FW_BIN_VER_OFFSET), *(fw_entry->data+FW_BIN_VER_BAR_OFFSET));
+			ret = -ENOEXEC;
+			goto invalid;
+		}
+
+		/* BIN Header Parser */
+		ret = nvt_bin_header_parser(fw_entry->data, fw_entry->size);
+		if (ret) {
+			NVT_ERR("bin header parser failed\n");
+			goto invalid;
+		} else {
+			break;
+		}
+
+invalid:
+		update_firmware_release();
+		if (!IS_ERR_OR_NULL(bin_map)) {
+			kfree(bin_map);
+			bin_map = NULL;
+		}
+
+request_fail:
+		retry++;
+		if(unlikely(retry > 2)) {
+			NVT_ERR("error, retry=%d\n", retry);
+			break;
+		}
+	}
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen write data to sram function.
+
+- fwdata   : The buffer is written
+- SRAM_addr: The sram destination address
+- size     : Number of data bytes in @fwdata being written
+- BIN_addr : The transferred data offset of @fwdata
+
+return:
+	Executive outcomes. 0---succeed. else---fail.
+*******************************************************/
+static int32_t nvt_write_sram(const u8 *fwdata,
+		uint32_t SRAM_addr, uint32_t size, uint32_t BIN_addr)
+{
+	int32_t ret = 0;
+	uint32_t i = 0;
+	uint16_t len = 0;
+	int32_t count = 0;
+
+	if (size % NVT_TRANSFER_LEN)
+		count = (size / NVT_TRANSFER_LEN) + 1;
+	else
+		count = (size / NVT_TRANSFER_LEN);
+
+	for (i = 0 ; i < count ; i++) {
+		len = (size < NVT_TRANSFER_LEN) ? size : NVT_TRANSFER_LEN;
+
+		//---set xdata index to start address of SRAM---
+		ret = nvt_set_page(SRAM_addr);
+		if (ret) {
+			NVT_ERR("set page failed, ret = %d\n", ret);
+			return ret;
+		}
+
+		//---write data into SRAM---
+		fwbuf[0] = SRAM_addr & 0x7F;	//offset
+		memcpy(fwbuf+1, &fwdata[BIN_addr], len);	//payload
+		ret = CTP_SPI_WRITE(ts->client, fwbuf, len+1);
+		if (ret) {
+			NVT_ERR("write to sram failed, ret = %d\n", ret);
+			return ret;
+		}
+
+		SRAM_addr += NVT_TRANSFER_LEN;
+		BIN_addr += NVT_TRANSFER_LEN;
+		size -= NVT_TRANSFER_LEN;
+	}
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen nvt_write_firmware function to write
+firmware into each partition.
+
+return:
+	n.a.
+*******************************************************/
+static int32_t nvt_write_firmware(const u8 *fwdata, size_t fwsize)
+{
+	uint32_t list = 0;
+	char *name;
+	uint32_t BIN_addr, SRAM_addr, size;
+	int32_t ret = 0;
+
+	memset(fwbuf, 0, (NVT_TRANSFER_LEN+1));
+
+	for (list = 0; list < partition; list++) {
+		/* initialize variable */
+		SRAM_addr = bin_map[list].SRAM_addr;
+		size = bin_map[list].size;
+		BIN_addr = bin_map[list].BIN_addr;
+		name = bin_map[list].name;
+
+//		NVT_LOG("[%d][%s] SRAM (0x%08X), SIZE (0x%08X), BIN (0x%08X)\n",
+//				list, name, SRAM_addr, size, BIN_addr);
+
+		/* Check data size */
+		if ((BIN_addr + size) > fwsize) {
+			NVT_ERR("access range (0x%08X to 0x%08X) is larger than bin size!\n",
+					BIN_addr, BIN_addr + size);
+			ret = -EINVAL;
+			goto out;
+		}
+
+		/* ignore reserved partition (Reserved Partition size is zero) */
+		if (!size)
+			continue;
+		else
+			size = size +1;
+
+		/* write data to SRAM */
+		ret = nvt_write_sram(fwdata, SRAM_addr, size, BIN_addr);
+		if (ret) {
+			NVT_ERR("sram program failed, ret = %d\n", ret);
+			goto out;
+		}
+	}
+
+out:
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen check checksum function.
+This function will compare file checksum and fw checksum.
+
+return:
+	n.a.
+*******************************************************/
+static int32_t nvt_check_fw_checksum(void)
+{
+	uint32_t fw_checksum = 0;
+	uint32_t len = partition*4;
+	uint32_t list = 0;
+	int32_t ret = 0;
+
+	memset(fwbuf, 0, (len+1));
+
+	//---set xdata index to checksum---
+	nvt_set_page(ts->mmap->R_ILM_CHECKSUM_ADDR);
+
+	/* read checksum */
+	fwbuf[0] = (ts->mmap->R_ILM_CHECKSUM_ADDR) & 0x7F;
+	ret = CTP_SPI_READ(ts->client, fwbuf, len+1);
+	if (ret) {
+		NVT_ERR("Read fw checksum failed\n");
+		return ret;
+	}
+
+	/*
+	 * Compare each checksum from fw
+	 * ILM + DLM + Overlay + Info
+	 * ilm_dlm_num (ILM & DLM) + ovly_sec_num + info_sec_num
+	 */
+	for (list = 0; list < partition; list++) {
+		fw_checksum = byte_to_word(&fwbuf[1+list*4]);
+
+		/* ignore reserved partition (Reserved Partition size is zero) */
+		if(!bin_map[list].size)
+			continue;
+
+		if (bin_map[list].crc != fw_checksum) {
+			NVT_ERR("[%d] BIN_checksum=0x%08X, FW_checksum=0x%08X\n",
+					list, bin_map[list].crc, fw_checksum);
+			ret = -EIO;
+		}
+	}
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen set bootload crc reg bank function.
+This function will set hw crc reg before enable crc function.
+
+return:
+	n.a.
+*******************************************************/
+static void nvt_set_bld_crc_bank(uint32_t DES_ADDR, uint32_t SRAM_ADDR,
+		uint32_t LENGTH_ADDR, uint32_t size,
+		uint32_t G_CHECKSUM_ADDR, uint32_t crc)
+{
+	/* write destination address */
+	nvt_set_page(DES_ADDR);
+	fwbuf[0] = DES_ADDR & 0x7F;
+	fwbuf[1] = (SRAM_ADDR) & 0xFF;
+	fwbuf[2] = (SRAM_ADDR >> 8) & 0xFF;
+	fwbuf[3] = (SRAM_ADDR >> 16) & 0xFF;
+	CTP_SPI_WRITE(ts->client, fwbuf, 4);
+
+	/* write length */
+	//nvt_set_page(LENGTH_ADDR);
+	fwbuf[0] = LENGTH_ADDR & 0x7F;
+	fwbuf[1] = (size) & 0xFF;
+	fwbuf[2] = (size >> 8) & 0xFF;
+	fwbuf[3] = (size >> 16) & 0x01;
+	if (ts->hw_crc == 1) {
+		CTP_SPI_WRITE(ts->client, fwbuf, 3);
+	} else if (ts->hw_crc > 1) {
+		CTP_SPI_WRITE(ts->client, fwbuf, 4);
+	}
+
+	/* write golden dlm checksum */
+	//nvt_set_page(G_CHECKSUM_ADDR);
+	fwbuf[0] = G_CHECKSUM_ADDR & 0x7F;
+	fwbuf[1] = (crc) & 0xFF;
+	fwbuf[2] = (crc >> 8) & 0xFF;
+	fwbuf[3] = (crc >> 16) & 0xFF;
+	fwbuf[4] = (crc >> 24) & 0xFF;
+	CTP_SPI_WRITE(ts->client, fwbuf, 5);
+
+	return;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen set BLD hw crc function.
+This function will set ILM and DLM crc information to register.
+
+return:
+	n.a.
+*******************************************************/
+static void nvt_set_bld_hw_crc(void)
+{
+	/* [0] ILM */
+	/* write register bank */
+	nvt_set_bld_crc_bank(ts->mmap->ILM_DES_ADDR, bin_map[0].SRAM_addr,
+			ts->mmap->ILM_LENGTH_ADDR, bin_map[0].size,
+			ts->mmap->G_ILM_CHECKSUM_ADDR, bin_map[0].crc);
+
+	/* [1] DLM */
+	/* write register bank */
+	nvt_set_bld_crc_bank(ts->mmap->DLM_DES_ADDR, bin_map[1].SRAM_addr,
+			ts->mmap->DLM_LENGTH_ADDR, bin_map[1].size,
+			ts->mmap->G_DLM_CHECKSUM_ADDR, bin_map[1].crc);
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen read BLD hw crc info function.
+This function will check crc results from register.
+
+return:
+	n.a.
+*******************************************************/
+static void nvt_read_bld_hw_crc(void)
+{
+	uint8_t buf[8] = {0};
+	uint32_t g_crc = 0, r_crc = 0;
+
+	/* CRC Flag */
+	nvt_set_page(ts->mmap->BLD_ILM_DLM_CRC_ADDR);
+	buf[0] = ts->mmap->BLD_ILM_DLM_CRC_ADDR & 0x7F;
+	buf[1] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 2);
+	NVT_ERR("crc_done = %d, ilm_crc_flag = %d, dlm_crc_flag = %d\n",
+			(buf[1] >> 2) & 0x01, (buf[1] >> 0) & 0x01, (buf[1] >> 1) & 0x01);
+
+	/* ILM CRC */
+	nvt_set_page(ts->mmap->G_ILM_CHECKSUM_ADDR);
+	buf[0] = ts->mmap->G_ILM_CHECKSUM_ADDR & 0x7F;
+	buf[1] = 0x00;
+	buf[2] = 0x00;
+	buf[3] = 0x00;
+	buf[4] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 5);
+	g_crc = buf[1] | (buf[2] << 8) | (buf[3] << 16) | (buf[4] << 24);
+
+	nvt_set_page(ts->mmap->R_ILM_CHECKSUM_ADDR);
+	buf[0] = ts->mmap->R_ILM_CHECKSUM_ADDR & 0x7F;
+	buf[1] = 0x00;
+	buf[2] = 0x00;
+	buf[3] = 0x00;
+	buf[4] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 5);
+	r_crc = buf[1] | (buf[2] << 8) | (buf[3] << 16) | (buf[4] << 24);
+
+	NVT_ERR("ilm: bin crc = 0x%08X, golden = 0x%08X, result = 0x%08X\n",
+			bin_map[0].crc, g_crc, r_crc);
+
+	/* DLM CRC */
+	nvt_set_page(ts->mmap->G_DLM_CHECKSUM_ADDR);
+	buf[0] = ts->mmap->G_DLM_CHECKSUM_ADDR & 0x7F;
+	buf[1] = 0x00;
+	buf[2] = 0x00;
+	buf[3] = 0x00;
+	buf[4] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 5);
+	g_crc = buf[1] | (buf[2] << 8) | (buf[3] << 16) | (buf[4] << 24);
+
+	nvt_set_page(ts->mmap->R_DLM_CHECKSUM_ADDR);
+	buf[0] = ts->mmap->R_DLM_CHECKSUM_ADDR & 0x7F;
+	buf[1] = 0x00;
+	buf[2] = 0x00;
+	buf[3] = 0x00;
+	buf[4] = 0x00;
+	CTP_SPI_READ(ts->client, buf, 5);
+	r_crc = buf[1] | (buf[2] << 8) | (buf[3] << 16) | (buf[4] << 24);
+
+	NVT_ERR("dlm: bin crc = 0x%08X, golden = 0x%08X, result = 0x%08X\n",
+			bin_map[1].crc, g_crc, r_crc);
+
+	return;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen Download_Firmware with HW CRC
+function. It's complete download firmware flow.
+
+return:
+	Executive outcomes. 0---succeed. else---fail.
+*******************************************************/
+static int32_t nvt_download_firmware_hw_crc(void)
+{
+	uint8_t retry = 0;
+	int32_t ret = 0;
+
+	start = ktime_get();
+
+	while (1) {
+		/* bootloader reset to reset MCU */
+		nvt_bootloader_reset();
+
+		/* set ilm & dlm reg bank */
+		nvt_set_bld_hw_crc();
+
+		/* Start to write firmware process */
+		if (cascade_2nd_header_info) {
+			/* for cascade */
+			nvt_tx_auto_copy_mode();
+
+			ret = nvt_write_firmware(fw_entry->data, fw_entry->size);
+			if (ret) {
+				NVT_ERR("Write_Firmware failed. (%d)\n", ret);
+				goto fail;
+			}
+
+			ret = nvt_check_spi_dma_tx_info();
+			if (ret) {
+				NVT_ERR("spi dma tx info failed. (%d)\n", ret);
+				goto fail;
+			}
+		} else {
+			ret = nvt_write_firmware(fw_entry->data, fw_entry->size);
+			if (ret) {
+				NVT_ERR("Write_Firmware failed. (%d)\n", ret);
+				goto fail;
+			}
+		}
+
+		/* enable hw bld crc function */
+		nvt_bld_crc_enable();
+
+		/* clear fw reset status & enable fw crc check */
+		nvt_fw_crc_enable();
+
+		/* Set Boot Ready Bit */
+		nvt_boot_ready();
+
+		ret = nvt_check_fw_reset_state(RESET_STATE_INIT);
+		if (ret) {
+			NVT_ERR("nvt_check_fw_reset_state failed. (%d)\n", ret);
+			goto fail;
+		} else {
+			break;
+		}
+
+fail:
+		retry++;
+		if(unlikely(retry > 2)) {
+			NVT_ERR("error, retry=%d\n", retry);
+			nvt_read_bld_hw_crc();
+			break;
+		}
+	}
+
+	end = ktime_get();
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen Download_Firmware function. It's
+complete download firmware flow.
+
+return:
+	n.a.
+*******************************************************/
+static int32_t nvt_download_firmware(void)
+{
+	uint8_t retry = 0;
+	int32_t ret = 0;
+
+	start = ktime_get();
+
+	while (1) {
+		/*
+		 * Send eng reset cmd before download FW
+		 * Keep TP_RESX low when send eng reset cmd
+		 */
+#if NVT_TOUCH_SUPPORT_HW_RST
+		gpio_set_value(ts->reset_gpio, 0);
+		mdelay(1);	//wait 1ms
+#endif
+		nvt_eng_reset();
+#if NVT_TOUCH_SUPPORT_HW_RST
+		gpio_set_value(ts->reset_gpio, 1);
+		mdelay(10);	//wait tRT2BRST after TP_RST
+#endif
+		nvt_bootloader_reset();
+
+		/* clear fw reset status */
+		nvt_write_addr(ts->mmap->EVENT_BUF_ADDR | EVENT_MAP_RESET_COMPLETE, 0x00);
+
+		/* Start to write firmware process */
+		ret = nvt_write_firmware(fw_entry->data, fw_entry->size);
+		if (ret) {
+			NVT_ERR("Write_Firmware failed. (%d)\n", ret);
+			goto fail;
+		}
+
+		/* Set Boot Ready Bit */
+		nvt_boot_ready();
+
+		ret = nvt_check_fw_reset_state(RESET_STATE_INIT);
+		if (ret) {
+			NVT_ERR("nvt_check_fw_reset_state failed. (%d)\n", ret);
+			goto fail;
+		}
+
+		/* check fw checksum result */
+		ret = nvt_check_fw_checksum();
+		if (ret) {
+			NVT_ERR("firmware checksum not match, retry=%d\n", retry);
+			goto fail;
+		} else {
+			break;
+		}
+
+fail:
+		retry++;
+		if(unlikely(retry > 2)) {
+			NVT_ERR("error, retry=%d\n", retry);
+			break;
+		}
+	}
+
+	end = ktime_get();
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen update firmware main function.
+
+return:
+	n.a.
+*******************************************************/
+int32_t nvt_update_firmware(const char *firmware_name)
+{
+	int32_t ret = 0;
+
+	// request bin file in "/etc/firmware"
+	ret = update_firmware_request(firmware_name);
+	if (ret) {
+		NVT_ERR("update_firmware_request failed. (%d)\n", ret);
+		goto request_firmware_fail;
+	}
+
+	/* initial buffer and variable */
+	ret = nvt_download_init();
+	if (ret) {
+		NVT_ERR("Download Init failed. (%d)\n", ret);
+		goto download_fail;
+	}
+
+	/* download firmware process */
+	if (ts->hw_crc)
+		ret = nvt_download_firmware_hw_crc();
+	else
+		ret = nvt_download_firmware();
+	if (ret) {
+		NVT_ERR("Download Firmware failed. (%d)\n", ret);
+		goto download_fail;
+	}
+
+	NVT_LOG("Update firmware success! <%ld us>\n",
+			(long) ktime_us_delta(end, start));
+
+	/* Get FW Info */
+	ret = nvt_get_fw_info();
+	if (ret) {
+		NVT_ERR("nvt_get_fw_info failed. (%d)\n", ret);
+	}
+
+download_fail:
+	if (!IS_ERR_OR_NULL(bin_map)) {
+		kfree(bin_map);
+		bin_map = NULL;
+	}
+
+	update_firmware_release();
+request_firmware_fail:
+
+	return ret;
+}
+
+/*******************************************************
+Description:
+	Novatek touchscreen update firmware when booting
+	function.
+
+return:
+	n.a.
+*******************************************************/
+void Boot_Update_Firmware(struct work_struct *work)
+{
+	mutex_lock(&ts->lock);
+	nvt_update_firmware(ts->fw_name);
+	nvt_get_fw_info();
+	mutex_unlock(&ts->lock);
+}
+#endif /* BOOT_UPDATE_FIRMWARE */
diff --git a/drivers/input/touchscreen/nt36523/nt36xxx_mem_map.h b/drivers/input/touchscreen/nt36523/nt36xxx_mem_map.h
new file mode 100644
index 000000000000..3f4195d636a0
--- /dev/null
+++ b/drivers/input/touchscreen/nt36523/nt36xxx_mem_map.h
@@ -0,0 +1,390 @@
+/*
+ * Copyright (C) 2010 - 2018 Novatek, Inc.
+ * Copyright (C) 2021 XiaoMi, Inc.
+ *
+ * $Revision: 57674 $
+ * $Date: 2020-03-02 11:16:20 +0800 (週一, 02 三月 2020) $
+ *
+ * This program is free software; you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation; either version 2 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful, but WITHOUT
+ * ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
+ * FITNESS FOR A PARTICULAR PURPOSE.  See the GNU General Public License for
+ * more details.
+ *
+ */
+
+#define CHIP_VER_TRIM_ADDR 0x3F004
+#define CHIP_VER_TRIM_OLD_ADDR 0x1F64E
+
+struct nvt_ts_mem_map {
+	uint32_t EVENT_BUF_ADDR;
+	uint32_t RAW_PIPE0_ADDR;
+	uint32_t RAW_PIPE1_ADDR;
+	uint32_t BASELINE_ADDR;
+	uint32_t BASELINE_BTN_ADDR;
+	uint32_t DIFF_PIPE0_ADDR;
+	uint32_t DIFF_PIPE1_ADDR;
+	uint32_t RAW_BTN_PIPE0_ADDR;
+	uint32_t RAW_BTN_PIPE1_ADDR;
+	uint32_t DIFF_BTN_PIPE0_ADDR;
+	uint32_t DIFF_BTN_PIPE1_ADDR;
+	uint32_t PEN_2D_BL_TIP_X_ADDR;
+	uint32_t PEN_2D_BL_TIP_Y_ADDR;
+	uint32_t PEN_2D_BL_RING_X_ADDR;
+	uint32_t PEN_2D_BL_RING_Y_ADDR;
+	uint32_t PEN_2D_DIFF_TIP_X_ADDR;
+	uint32_t PEN_2D_DIFF_TIP_Y_ADDR;
+	uint32_t PEN_2D_DIFF_RING_X_ADDR;
+	uint32_t PEN_2D_DIFF_RING_Y_ADDR;
+	uint32_t PEN_2D_RAW_TIP_X_ADDR;
+	uint32_t PEN_2D_RAW_TIP_Y_ADDR;
+	uint32_t PEN_2D_RAW_RING_X_ADDR;
+	uint32_t PEN_2D_RAW_RING_Y_ADDR;
+	uint32_t PEN_1D_DIFF_TIP_X_ADDR;
+	uint32_t PEN_1D_DIFF_TIP_Y_ADDR;
+	uint32_t PEN_1D_DIFF_RING_X_ADDR;
+	uint32_t PEN_1D_DIFF_RING_Y_ADDR;
+	uint32_t READ_FLASH_CHECKSUM_ADDR;
+	uint32_t RW_FLASH_DATA_ADDR;
+	/* Phase 2 Host Download */
+	uint32_t BOOT_RDY_ADDR;
+	uint32_t POR_CD_ADDR;
+	uint32_t TX_AUTO_COPY_EN;
+	uint32_t SPI_DMA_TX_INFO;
+	/* BLD CRC */
+	uint32_t BLD_LENGTH_ADDR;
+	uint32_t ILM_LENGTH_ADDR;
+	uint32_t DLM_LENGTH_ADDR;
+	uint32_t BLD_DES_ADDR;
+	uint32_t ILM_DES_ADDR;
+	uint32_t DLM_DES_ADDR;
+	uint32_t G_ILM_CHECKSUM_ADDR;
+	uint32_t G_DLM_CHECKSUM_ADDR;
+	uint32_t R_ILM_CHECKSUM_ADDR;
+	uint32_t R_DLM_CHECKSUM_ADDR;
+	uint32_t BLD_CRC_EN_ADDR;
+	uint32_t DMA_CRC_EN_ADDR;
+	uint32_t BLD_ILM_DLM_CRC_ADDR;
+	uint32_t DMA_CRC_FLAG_ADDR;
+	uint32_t FW_HISTORY_ADDR;
+};
+
+struct nvt_ts_hw_info {
+	uint8_t carrier_system;
+	uint8_t hw_crc;
+};
+
+static const struct nvt_ts_mem_map NT36523_memory_map = {
+	.EVENT_BUF_ADDR           = 0x2FE00,
+	.RAW_PIPE0_ADDR           = 0x30FA0,
+	.RAW_PIPE1_ADDR           = 0x30FA0,
+	.BASELINE_ADDR            = 0x36510,
+	.BASELINE_BTN_ADDR        = 0,
+	.DIFF_PIPE0_ADDR          = 0x373E8,
+	.DIFF_PIPE1_ADDR          = 0x38068,
+	.RAW_BTN_PIPE0_ADDR       = 0,
+	.RAW_BTN_PIPE1_ADDR       = 0,
+	.DIFF_BTN_PIPE0_ADDR      = 0,
+	.DIFF_BTN_PIPE1_ADDR      = 0,
+	.PEN_2D_BL_TIP_X_ADDR     = 0x2988A,
+	.PEN_2D_BL_TIP_Y_ADDR     = 0x29A1A,
+	.PEN_2D_BL_RING_X_ADDR    = 0x29BAA,
+	.PEN_2D_BL_RING_Y_ADDR    = 0x29D3A,
+	.PEN_2D_DIFF_TIP_X_ADDR   = 0x29ECA,
+	.PEN_2D_DIFF_TIP_Y_ADDR   = 0x2A05A,
+	.PEN_2D_DIFF_RING_X_ADDR  = 0x2A1EA,
+	.PEN_2D_DIFF_RING_Y_ADDR  = 0x2A37A,
+	.PEN_2D_RAW_TIP_X_ADDR    = 0x2A50A,
+	.PEN_2D_RAW_TIP_Y_ADDR    = 0x2A69A,
+	.PEN_2D_RAW_RING_X_ADDR   = 0x2A82A,
+	.PEN_2D_RAW_RING_Y_ADDR   = 0x2A9BA,
+	.PEN_1D_DIFF_TIP_X_ADDR   = 0x2AB4A,
+	.PEN_1D_DIFF_TIP_Y_ADDR   = 0x2ABAE,
+	.PEN_1D_DIFF_RING_X_ADDR  = 0x2AC12,
+	.PEN_1D_DIFF_RING_Y_ADDR  = 0x2AC76,
+	.READ_FLASH_CHECKSUM_ADDR = 0x24000,
+	.RW_FLASH_DATA_ADDR       = 0x24002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x3F10D,
+	.TX_AUTO_COPY_EN          = 0x3F7E8,
+	.SPI_DMA_TX_INFO          = 0x3F7F1,
+	/* BLD CRC */
+	.BLD_LENGTH_ADDR          = 0x3F138,	//0x3F138 ~ 0x3F13A	(3 bytes)
+	.ILM_LENGTH_ADDR          = 0x3F118,	//0x3F118 ~ 0x3F11A	(3 bytes)
+	.DLM_LENGTH_ADDR          = 0x3F130,	//0x3F130 ~ 0x3F132	(3 bytes)
+	.BLD_DES_ADDR             = 0x3F114,	//0x3F114 ~ 0x3F116	(3 bytes)
+	.ILM_DES_ADDR             = 0x3F128,	//0x3F128 ~ 0x3F12A	(3 bytes)
+	.DLM_DES_ADDR             = 0x3F12C,	//0x3F12C ~ 0x3F12E	(3 bytes)
+	.G_ILM_CHECKSUM_ADDR      = 0x3F100,	//0x3F100 ~ 0x3F103	(4 bytes)
+	.G_DLM_CHECKSUM_ADDR      = 0x3F104,	//0x3F104 ~ 0x3F107	(4 bytes)
+	.R_ILM_CHECKSUM_ADDR      = 0x3F120,	//0x3F120 ~ 0x3F123 (4 bytes)
+	.R_DLM_CHECKSUM_ADDR      = 0x3F124,	//0x3F124 ~ 0x3F127 (4 bytes)
+	.BLD_CRC_EN_ADDR          = 0x3F30E,
+	.DMA_CRC_EN_ADDR          = 0x3F136,
+	.BLD_ILM_DLM_CRC_ADDR     = 0x3F133,
+	.DMA_CRC_FLAG_ADDR        = 0x3F134,
+	.FW_HISTORY_ADDR          = 0x38D54,
+};
+
+static const struct nvt_ts_mem_map NT36526_memory_map = {
+	.EVENT_BUF_ADDR           = 0x22D00,
+	.RAW_PIPE0_ADDR           = 0x24000,
+	.RAW_PIPE1_ADDR           = 0x24000,
+	.BASELINE_ADDR            = 0x21758,
+	.BASELINE_BTN_ADDR        = 0,
+	.DIFF_PIPE0_ADDR          = 0x20AB0,
+	.DIFF_PIPE1_ADDR          = 0x24AB0,
+	.RAW_BTN_PIPE0_ADDR       = 0,
+	.RAW_BTN_PIPE1_ADDR       = 0,
+	.DIFF_BTN_PIPE0_ADDR      = 0,
+	.DIFF_BTN_PIPE1_ADDR      = 0,
+	.READ_FLASH_CHECKSUM_ADDR = 0x24000,
+	.RW_FLASH_DATA_ADDR       = 0x24002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x3F10D,
+	/* BLD CRC */
+	.BLD_LENGTH_ADDR          = 0x3F138,	//0x3F138 ~ 0x3F13A	(3 bytes)
+	.ILM_LENGTH_ADDR          = 0x3F118,	//0x3F118 ~ 0x3F11A	(3 bytes)
+	.DLM_LENGTH_ADDR          = 0x3F130,	//0x3F130 ~ 0x3F132	(3 bytes)
+	.BLD_DES_ADDR             = 0x3F114,	//0x3F114 ~ 0x3F116	(3 bytes)
+	.ILM_DES_ADDR             = 0x3F128,	//0x3F128 ~ 0x3F12A	(3 bytes)
+	.DLM_DES_ADDR             = 0x3F12C,	//0x3F12C ~ 0x3F12E	(3 bytes)
+	.G_ILM_CHECKSUM_ADDR      = 0x3F100,	//0x3F100 ~ 0x3F103	(4 bytes)
+	.G_DLM_CHECKSUM_ADDR      = 0x3F104,	//0x3F104 ~ 0x3F107	(4 bytes)
+	.R_ILM_CHECKSUM_ADDR      = 0x3F120,	//0x3F120 ~ 0x3F123 (4 bytes)
+	.R_DLM_CHECKSUM_ADDR      = 0x3F124,	//0x3F124 ~ 0x3F127 (4 bytes)
+	.BLD_CRC_EN_ADDR          = 0x3F30E,
+	.DMA_CRC_EN_ADDR          = 0x3F136,
+	.BLD_ILM_DLM_CRC_ADDR     = 0x3F133,
+	.DMA_CRC_FLAG_ADDR        = 0x3F134,
+};
+
+
+static const struct nvt_ts_mem_map NT36675_memory_map = {
+	.EVENT_BUF_ADDR           = 0x22D00,
+	.RAW_PIPE0_ADDR           = 0x24000,
+	.RAW_PIPE1_ADDR           = 0x24000,
+	.BASELINE_ADDR            = 0x21B90,
+	.BASELINE_BTN_ADDR        = 0,
+	.DIFF_PIPE0_ADDR          = 0x20C60,
+	.DIFF_PIPE1_ADDR          = 0x24C60,
+	.RAW_BTN_PIPE0_ADDR       = 0,
+	.RAW_BTN_PIPE1_ADDR       = 0,
+	.DIFF_BTN_PIPE0_ADDR      = 0,
+	.DIFF_BTN_PIPE1_ADDR      = 0,
+	.READ_FLASH_CHECKSUM_ADDR = 0x24000,
+	.RW_FLASH_DATA_ADDR       = 0x24002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x3F10D,
+	/* BLD CRC */
+	.BLD_LENGTH_ADDR          = 0x3F138,	//0x3F138 ~ 0x3F13A	(3 bytes)
+	.ILM_LENGTH_ADDR          = 0x3F118,	//0x3F118 ~ 0x3F11A	(3 bytes)
+	.DLM_LENGTH_ADDR          = 0x3F130,	//0x3F130 ~ 0x3F132	(3 bytes)
+	.BLD_DES_ADDR             = 0x3F114,	//0x3F114 ~ 0x3F116	(3 bytes)
+	.ILM_DES_ADDR             = 0x3F128,	//0x3F128 ~ 0x3F12A	(3 bytes)
+	.DLM_DES_ADDR             = 0x3F12C,	//0x3F12C ~ 0x3F12E	(3 bytes)
+	.G_ILM_CHECKSUM_ADDR      = 0x3F100,	//0x3F100 ~ 0x3F103	(4 bytes)
+	.G_DLM_CHECKSUM_ADDR      = 0x3F104,	//0x3F104 ~ 0x3F107	(4 bytes)
+	.R_ILM_CHECKSUM_ADDR      = 0x3F120,	//0x3F120 ~ 0x3F123 (4 bytes)
+	.R_DLM_CHECKSUM_ADDR      = 0x3F124,	//0x3F124 ~ 0x3F127 (4 bytes)
+	.BLD_CRC_EN_ADDR          = 0x3F30E,
+	.DMA_CRC_EN_ADDR          = 0x3F136,
+	.BLD_ILM_DLM_CRC_ADDR     = 0x3F133,
+	.DMA_CRC_FLAG_ADDR        = 0x3F134,
+};
+
+
+static const struct nvt_ts_mem_map NT36672A_memory_map = {
+	.EVENT_BUF_ADDR           = 0x21C00,
+	.RAW_PIPE0_ADDR           = 0x20000,
+	.RAW_PIPE1_ADDR           = 0x23000,
+	.BASELINE_ADDR            = 0x20BFC,
+	.BASELINE_BTN_ADDR        = 0x23BFC,
+	.DIFF_PIPE0_ADDR          = 0x206DC,
+	.DIFF_PIPE1_ADDR          = 0x236DC,
+	.RAW_BTN_PIPE0_ADDR       = 0x20510,
+	.RAW_BTN_PIPE1_ADDR       = 0x23510,
+	.DIFF_BTN_PIPE0_ADDR      = 0x20BF0,
+	.DIFF_BTN_PIPE1_ADDR      = 0x23BF0,
+	.READ_FLASH_CHECKSUM_ADDR = 0x24000,
+	.RW_FLASH_DATA_ADDR       = 0x24002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x3F10D,
+	/* BLD CRC */
+	.BLD_LENGTH_ADDR          = 0x3F10E,	//0x3F10E ~ 0x3F10F	(2 bytes)
+	.ILM_LENGTH_ADDR          = 0x3F118,	//0x3F118 ~ 0x3F119	(2 bytes)
+	.DLM_LENGTH_ADDR          = 0x3F130,	//0x3F130 ~ 0x3F131	(2 bytes)
+	.BLD_DES_ADDR             = 0x3F114,	//0x3F114 ~ 0x3F116	(3 bytes)
+	.ILM_DES_ADDR             = 0x3F128,	//0x3F128 ~ 0x3F12A	(3 bytes)
+	.DLM_DES_ADDR             = 0x3F12C,	//0x3F12C ~ 0x3F12E	(3 bytes)
+	.G_ILM_CHECKSUM_ADDR      = 0x3F100,	//0x3F100 ~ 0x3F103	(4 bytes)
+	.G_DLM_CHECKSUM_ADDR      = 0x3F104,	//0x3F104 ~ 0x3F107	(4 bytes)
+	.R_ILM_CHECKSUM_ADDR      = 0x3F120,	//0x3F120 ~ 0x3F123 (4 bytes)
+	.R_DLM_CHECKSUM_ADDR      = 0x3F124,	//0x3F124 ~ 0x3F127 (4 bytes)
+	.BLD_CRC_EN_ADDR          = 0x3F30E,
+	.DMA_CRC_EN_ADDR          = 0x3F132,
+	.BLD_ILM_DLM_CRC_ADDR     = 0x3F133,
+	.DMA_CRC_FLAG_ADDR        = 0x3F134,
+};
+
+static const struct nvt_ts_mem_map NT36772_memory_map = {
+	.EVENT_BUF_ADDR           = 0x11E00,
+	.RAW_PIPE0_ADDR           = 0x10000,
+	.RAW_PIPE1_ADDR           = 0x12000,
+	.BASELINE_ADDR            = 0x10E70,
+	.BASELINE_BTN_ADDR        = 0x12E70,
+	.DIFF_PIPE0_ADDR          = 0x10830,
+	.DIFF_PIPE1_ADDR          = 0x12830,
+	.RAW_BTN_PIPE0_ADDR       = 0x10E60,
+	.RAW_BTN_PIPE1_ADDR       = 0x12E60,
+	.DIFF_BTN_PIPE0_ADDR      = 0x10E68,
+	.DIFF_BTN_PIPE1_ADDR      = 0x12E68,
+	.READ_FLASH_CHECKSUM_ADDR = 0x14000,
+	.RW_FLASH_DATA_ADDR       = 0x14002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x1F141,
+	.POR_CD_ADDR              = 0x1F61C,
+	/* BLD CRC */
+	.R_ILM_CHECKSUM_ADDR      = 0x1BF00,
+};
+
+static const struct nvt_ts_mem_map NT36525_memory_map = {
+	.EVENT_BUF_ADDR           = 0x11A00,
+	.RAW_PIPE0_ADDR           = 0x10000,
+	.RAW_PIPE1_ADDR           = 0x12000,
+	.BASELINE_ADDR            = 0x10B08,
+	.BASELINE_BTN_ADDR        = 0x12B08,
+	.DIFF_PIPE0_ADDR          = 0x1064C,
+	.DIFF_PIPE1_ADDR          = 0x1264C,
+	.RAW_BTN_PIPE0_ADDR       = 0x10634,
+	.RAW_BTN_PIPE1_ADDR       = 0x12634,
+	.DIFF_BTN_PIPE0_ADDR      = 0x10AFC,
+	.DIFF_BTN_PIPE1_ADDR      = 0x12AFC,
+	.READ_FLASH_CHECKSUM_ADDR = 0x14000,
+	.RW_FLASH_DATA_ADDR       = 0x14002,
+	/* Phase 2 Host Download */
+	.BOOT_RDY_ADDR            = 0x1F141,
+	.POR_CD_ADDR              = 0x1F61C,
+	/* BLD CRC */
+	.R_ILM_CHECKSUM_ADDR      = 0x1BF00,
+};
+
+static const struct nvt_ts_mem_map NT36676F_memory_map = {
+	.EVENT_BUF_ADDR           = 0x11A00,
+	.RAW_PIPE0_ADDR           = 0x10000,
+	.RAW_PIPE1_ADDR           = 0x12000,
+	.BASELINE_ADDR            = 0x10B08,
+	.BASELINE_BTN_ADDR        = 0x12B08,
+	.DIFF_PIPE0_ADDR          = 0x1064C,
+	.DIFF_PIPE1_ADDR          = 0x1264C,
+	.RAW_BTN_PIPE0_ADDR       = 0x10634,
+	.RAW_BTN_PIPE1_ADDR       = 0x12634,
+	.DIFF_BTN_PIPE0_ADDR      = 0x10AFC,
+	.DIFF_BTN_PIPE1_ADDR      = 0x12AFC,
+	.READ_FLASH_CHECKSUM_ADDR = 0x14000,
+	.RW_FLASH_DATA_ADDR       = 0x14002,
+};
+
+static struct nvt_ts_hw_info NT36523_hw_info = {
+	.carrier_system = 2,
+	.hw_crc         = 2,
+};
+
+static struct nvt_ts_hw_info NT36526_hw_info = {
+	.carrier_system = 2,
+	.hw_crc         = 2,
+};
+
+static struct nvt_ts_hw_info NT36675_hw_info = {
+	.carrier_system = 2,
+	.hw_crc         = 2,
+};
+
+static struct nvt_ts_hw_info NT36672A_hw_info = {
+	.carrier_system = 0,
+	.hw_crc         = 1,
+};
+
+static struct nvt_ts_hw_info NT36772_hw_info = {
+	.carrier_system = 0,
+	.hw_crc         = 0,
+};
+
+static struct nvt_ts_hw_info NT36525_hw_info = {
+	.carrier_system = 0,
+	.hw_crc         = 0,
+};
+
+static struct nvt_ts_hw_info NT36676F_hw_info = {
+	.carrier_system = 0,
+	.hw_crc         = 0,
+};
+
+#define NVT_ID_BYTE_MAX 6
+struct nvt_ts_trim_id_table {
+	uint8_t id[NVT_ID_BYTE_MAX];
+	uint8_t mask[NVT_ID_BYTE_MAX];
+	const struct nvt_ts_mem_map *mmap;
+	const struct nvt_ts_hw_info *hwinfo;
+};
+
+static const struct nvt_ts_trim_id_table trim_id_table[] = {
+	{.id = {0x20, 0xFF, 0xFF, 0x23, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36523_memory_map,  .hwinfo = &NT36523_hw_info},
+	{.id = {0x0C, 0xFF, 0xFF, 0x23, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36523_memory_map,  .hwinfo = &NT36523_hw_info},
+	{.id = {0x0B, 0xFF, 0xFF, 0x23, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36523_memory_map,  .hwinfo = &NT36523_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x23, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36523_memory_map,  .hwinfo = &NT36523_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x23, 0x65, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36523_memory_map,  .hwinfo = &NT36523_hw_info},
+	{.id = {0x0C, 0xFF, 0xFF, 0x72, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36675_memory_map,  .hwinfo = &NT36675_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x26, 0x65, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36526_memory_map,  .hwinfo = &NT36526_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x75, 0x66, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36675_memory_map,  .hwinfo = &NT36675_hw_info},
+	{.id = {0x0B, 0xFF, 0xFF, 0x72, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0B, 0xFF, 0xFF, 0x82, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0B, 0xFF, 0xFF, 0x25, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x72, 0x65, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x72, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x82, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x70, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0B, 0xFF, 0xFF, 0x70, 0x66, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x0A, 0xFF, 0xFF, 0x72, 0x67, 0x03}, .mask = {1, 0, 0, 1, 1, 1},
+		.mmap = &NT36672A_memory_map, .hwinfo = &NT36672A_hw_info},
+	{.id = {0x55, 0x00, 0xFF, 0x00, 0x00, 0x00}, .mask = {1, 1, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0x55, 0x72, 0xFF, 0x00, 0x00, 0x00}, .mask = {1, 1, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xAA, 0x00, 0xFF, 0x00, 0x00, 0x00}, .mask = {1, 1, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xAA, 0x72, 0xFF, 0x00, 0x00, 0x00}, .mask = {1, 1, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x72, 0x67, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x70, 0x66, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x70, 0x67, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x72, 0x66, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36772_memory_map,  .hwinfo = &NT36772_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x25, 0x65, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36525_memory_map,  .hwinfo = &NT36525_hw_info},
+	{.id = {0xFF, 0xFF, 0xFF, 0x76, 0x66, 0x03}, .mask = {0, 0, 0, 1, 1, 1},
+		.mmap = &NT36676F_memory_map, .hwinfo = &NT36676F_hw_info}
+};
-- 
Armbian

