Parcourir la source

Add lvgl adaptation of touch screen xpt2046 for BSP (#6114)

* lvgl adaptation to resistive touch screen xpt2046

* some bug

* canonical code

* canonical code

* fix

* Modify the calibration section

* Modify the calibration section

* fix
solar_li il y a 2 ans
Parent
commit
5b00165f6e

+ 7 - 1
bsp/stm32/stm32f407-atk-explorer/applications/lvgl/lv_port_indev.c

@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2022, RT-Thread Development Team
  *
  * SPDX-License-Identifier: Apache-2.0
  *
@@ -29,8 +29,14 @@ static void input_read(lv_indev_drv_t *indev_drv, lv_indev_data_t *data)
 void lv_port_indev_input(rt_int16_t x, rt_int16_t y, lv_indev_state_t state)
 {
     last_state = state;
+#ifdef BSP_USING_TOUCH_CAP
     last_x = LCD_W - y;
     last_y = x;
+#endif /* BSP_USING_TOUCH_CAP */
+#ifdef BSP_USING_TOUCH_RES
+    last_x = x;
+    last_y = y;
+#endif /* BSP_USING_TOUCH_RES */
 }
 
 void lv_port_indev_init(void)

+ 32 - 9
bsp/stm32/stm32f407-atk-explorer/board/Kconfig

@@ -47,15 +47,38 @@ menu "Onboard Peripheral Drivers"
                 bool "Enable lcd fill test"
                 default y
         endif
-
-    config BSP_USING_TOUCH
-        bool "Use LCD TOUCH"
-        select BSP_USING_I2C2
+        
+    menuconfig BSP_USING_TOUCH
+        bool "Use LCD TOUCH (Default Res)"
         default n
         if BSP_USING_TOUCH
-            config BSP_TOUCH_INT_PIN
-                int "Touch interrupt pin, PB1"
-                default 17
+            config BSP_USING_TOUCH_CAP
+                bool "Use LCD TOUCH Capacitance (i2c2)"
+                select BSP_USING_I2C2
+                default n
+                if BSP_USING_TOUCH_CAP
+                    config BSP_TOUCH_INT_PIN
+                        int "Touch interrupt pin, PB1"
+                        default 17
+                endif
+
+            config BSP_USING_TOUCH_RES
+                bool "Use LCD TOUCH Resistance (sspi1)"
+                select RT_USING_TOUCH
+                select RT_TOUCH_PIN_IRQ
+                select BSP_USING_SOFT_SPI
+                select BSP_USING_SOFT_SPI1
+                select BSP_USING_ONBOARD_LCD
+                default y
+                if BSP_USING_TOUCH_RES
+                    config BSP_XPT2046_CS_PIN
+                        string "pin name for the chip select pin"
+                        default "PC.13"
+
+                    config BSP_XPT2046_IRQ_PIN
+                        string "pin name for the irq pin"
+                        default "PB.1"
+                endif
         endif
 
     config BSP_USING_LVGL
@@ -374,7 +397,7 @@ menu "On-chip Peripheral Drivers"
 
     menuconfig BSP_USING_I2C1
         bool "Enable I2C1 BUS (software simulation)"
-        default y
+        default n
         select RT_USING_I2C
         select RT_USING_I2C_BITOPS
         select RT_USING_PIN
@@ -391,7 +414,7 @@ menu "On-chip Peripheral Drivers"
 
     menuconfig BSP_USING_I2C2
         bool "Enable LCD Touch BUS (software simulation)"
-        default y
+        default n
         select RT_USING_I2C
         select RT_USING_I2C_BITOPS
         select RT_USING_PIN

+ 8 - 2
bsp/stm32/stm32f407-atk-explorer/board/SConscript

@@ -35,8 +35,14 @@ if GetDepend(['BSP_USING_SRAM']):
 if GetDepend(['BSP_USING_ONBOARD_LCD']):
     src += Glob('ports/drv_lcd.c')
 
-if GetDepend(['BSP_USING_TOUCH']):
-    src += Glob('ports/touch/*.c')
+if GetDepend(['BSP_USING_TOUCH_CAP']):
+    src += Glob('ports/touch/drv_touch_ft.c')
+    src += Glob('ports/touch/drv_touch.c')
+    path += [cwd + '/ports/touch']
+
+if GetDepend(['BSP_USING_TOUCH_RES']):
+    src += Glob('ports/touch/drv_touch_xpt.c')
+    src += Glob('ports/touch/drv_xpt2046_init.c')
     path += [cwd + '/ports/touch']
 
 startup_path_prefix = SDK_LIB

+ 65 - 9
bsp/stm32/stm32f407-atk-explorer/board/ports/drv_lcd.c

@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2022, RT-Thread Development Team
  *
  * SPDX-License-Identifier: Apache-2.0
  *
@@ -7,6 +7,7 @@
  * Date           Author       Notes
  * 2021-12-28     unknow       copy by STemwin
  * 2021-12-29     xiangxistu   port for lvgl <lcd_fill_array>
+ * 2022-6-26      solar        Improve the api required for resistive touch screen calibration
  */
 
 #include <board.h>
@@ -472,14 +473,69 @@ void LCD_Clear(uint32_t color)
     }
 }
 
+void LCD_DrawLine(const char *pixel, rt_uint16_t x1, rt_uint16_t y1, rt_uint16_t x2, rt_uint16_t y2)
+{
+    rt_uint16_t t;
+    int xerr = 0, yerr = 0, delta_x, delta_y, distance;
+    int incx, incy, uRow, uCol;
+    delta_x = x2 - x1; //计算坐标增量
+    delta_y = y2 - y1;
+    uRow = x1;
+    uCol = y1;
+
+    if (delta_x > 0)
+        incx = 1; //设置单步方向
+    else if (delta_x == 0)
+        incx = 0; //垂直线
+    else
+    {
+        incx = -1;
+        delta_x = -delta_x;
+    }
+
+    if (delta_y > 0)
+        incy = 1;
+    else if (delta_y == 0)
+        incy = 0; //水平线
+    else
+    {
+        incy = -1;
+        delta_y = -delta_y;
+    }
+
+    if (delta_x > delta_y)
+        distance = delta_x; //选取基本增量坐标轴
+    else
+        distance = delta_y;
+
+    for (t = 0; t <= distance + 1; t++) //画线输出
+    {
+        // LCD_DrawPoint(uRow, uCol); //画点
+        LCD_Fast_DrawPoint(pixel, uRow, uCol);
+        xerr += delta_x;
+        yerr += delta_y;
+
+        if (xerr > distance)
+        {
+            xerr -= distance;
+            uRow += incx;
+        }
+
+        if (yerr > distance)
+        {
+            yerr -= distance;
+            uCol += incy;
+        }
+    }
+}
 void LCD_HLine(const char *pixel, int x1, int x2, int y)
 {
-    int xsize = x2 - x1 + 1;
-    LCD_SetCursor(x1, y);
-    LCD_WriteRAM_Prepare();
-    uint16_t *p = (uint16_t *)pixel;
-    for (; xsize > 0; xsize--)
-        LCD->RAM = *p;
+    LCD_DrawLine(pixel, x1, y, x2, y);
+}
+
+void LCD_VLine(const char *pixel, int x, int y1, int y2)
+{
+    LCD_DrawLine(pixel, x, y1, x, y2);
 }
 
 void LCD_BlitLine(const char *pixel, int x, int y, rt_size_t size)
@@ -1788,7 +1844,7 @@ static rt_err_t drv_lcd_init(struct rt_device *device)
     }
     else if (lcddev.id == 0X1963)
     {
-        LCD_WR_REG(0xE2);  //Set PLL with OSC = 10MHz (hardware),	Multiplier N = 35, 250MHz < VCO < 800MHz = OSC*(N+1), VCO = 300MHz
+        LCD_WR_REG(0xE2);  //Set PLL with OSC = 10MHz (hardware),   Multiplier N = 35, 250MHz < VCO < 800MHz = OSC*(N+1), VCO = 300MHz
         LCD_WR_DATA(0x1D); //参数1
         LCD_WR_DATA(0x02); //参数2 Divider M = 2, PLL = 300/(M+1) = 100MHz
         LCD_WR_DATA(0x04); //参数3 Validate M and N values
@@ -1882,7 +1938,7 @@ struct rt_device_graphic_ops fsmc_lcd_ops =
         LCD_Fast_DrawPoint,
         LCD_ReadPoint,
         LCD_HLine,
-        RT_NULL,
+        LCD_VLine,
         LCD_BlitLine,
 };
 

+ 14 - 2
bsp/stm32/stm32f407-atk-explorer/board/ports/drv_lcd.h

@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2022, RT-Thread Development Team
  *
  * SPDX-License-Identifier: Apache-2.0
  *
@@ -13,9 +13,15 @@
 #include "rtdevice.h"
 #include <drv_common.h>
 
+#ifdef BSP_USING_TOUCH_CAP
 #define LCD_W 800
 #define LCD_H 480
+#endif // BSP_USING_TOUCH_CAP
 
+#ifdef BSP_USING_TOUCH_RES
+#define LCD_W 320
+#define LCD_H 480
+#endif // BSP_USING_TOUCH_RES
 
 //LCD重要参数集
 typedef struct
@@ -49,7 +55,13 @@ typedef struct
 #define D2U_L2R  6      //从下到上,从左到右
 #define D2U_R2L  7      //从下到上,从右到左
 
-#define DFT_SCAN_DIR  L2R_U2D  //默认的扫描方向
+#ifdef BSP_USING_TOUCH_CAP
+#define DFT_SCAN_DIR  L2R_U2D  //电容触摸屏默认的扫描方向
+#endif // BSP_USING_TOUCH_CAP
+
+#ifdef BSP_USING_TOUCH_RES
+#define DFT_SCAN_DIR  D2U_L2R  //电阻触摸屏默认的扫描方向
+#endif // BSP_USING_TOUCH_RES
 
 //LCD分辨率设置
 #define SSD_HOR_RESOLUTION      800     //LCD水平分辨率

+ 2 - 2
bsp/stm32/stm32f407-atk-explorer/board/ports/touch/drv_touch.c

@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2022, RT-Thread Development Team
  *
  * SPDX-License-Identifier: Apache-2.0
  *
@@ -10,7 +10,7 @@
 
 #include <rtconfig.h>
 
-#ifdef BSP_USING_TOUCH
+#ifdef BSP_USING_TOUCH_CAP
 #include "drv_touch.h"
 #include <string.h>
 

+ 2 - 2
bsp/stm32/stm32f407-atk-explorer/board/ports/touch/drv_touch_ft.c

@@ -1,5 +1,5 @@
 /*
- * Copyright (c) 2006-2021, RT-Thread Development Team
+ * Copyright (c) 2006-2022, RT-Thread Development Team
  *
  * SPDX-License-Identifier: Apache-2.0
  *
@@ -19,7 +19,7 @@
 #include <stdint.h>
 #include <string.h>
 
-#ifdef BSP_USING_TOUCH
+#ifdef BSP_USING_TOUCH_CAP
 
 #define DBG_ENABLE
 #define DBG_SECTION_NAME  "TOUCH.ft"

+ 266 - 0
bsp/stm32/stm32f407-atk-explorer/board/ports/touch/drv_touch_xpt.c

@@ -0,0 +1,266 @@
+/*
+ * Copyright (c) 2006-2022, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2022-6-27      solar        first version
+ */
+
+#include <drv_touch_xpt.h>
+#include <drv_soft_spi.h>
+#include <drv_spi.h>
+#include <drv_gpio.h>
+
+#define LOG_TAG "drv.xpt2046"
+#include <drv_log.h>
+
+#ifdef BSP_USING_TOUCH_RES
+
+static const rt_uint8_t xpt2046_tx_data[21] = {0xD0, 0, 0xD0, 0, 0xD0, 0, 0xD0, 0, 0xD0, 0, 0x90, 0, 0x90, 0, 0x90, 0, 0x90, 0, 0x90, 0, 0};
+
+/* Please calibrate the resistive touch screen before use, it is best to store the calibrated data */
+rt_err_t xpt2046_calibration(const char *lcd_name,const char *touch_name)
+{
+    /* Find the TFT LCD device */
+    rt_device_t lcd = rt_device_find(lcd_name);
+    if (lcd == RT_NULL)
+    {
+        LOG_E(LOG_TAG " cannot find lcd device named %s", lcd_name);
+        return -RT_ERROR;
+    }
+    if (rt_device_open(lcd, RT_DEVICE_OFLAG_RDWR) != RT_EOK)
+    {
+        LOG_E(LOG_TAG " cannot open lcd device named %s", lcd_name);
+        return 0;
+    }
+
+    /* Find the Touch device */
+    rt_xpt2046_t touch = (rt_xpt2046_t)rt_device_find(touch_name);
+    if (touch == RT_NULL)
+    {
+        LOG_E(LOG_TAG " cannot find touch device named %s", touch_name);
+        return -RT_ERROR;
+    }
+
+    /* Get TFT LCD screen information */
+    struct rt_device_graphic_info lcd_info;
+    rt_device_control(lcd, RTGRAPHIC_CTRL_GET_INFO, &lcd_info);
+
+    /* clear screen */
+    for (rt_uint32_t y = 0; y < lcd_info.height; ++y)
+    {
+        const uint32_t white = 0xFFFFFFFF;
+        rt_graphix_ops(lcd)->draw_hline((const char *)(&white), 0, lcd_info.width, y);
+    }
+    /* Set the information for the four points used for calibration */
+    rt_uint32_t cross_size = (lcd_info.width > lcd_info.height ? lcd_info.height : lcd_info.width) / 10;
+    rt_uint32_t x0 = cross_size;
+    rt_uint32_t y0 = cross_size;
+    rt_uint32_t x1 = lcd_info.width - cross_size;
+    rt_uint32_t y1 = cross_size;
+    rt_uint32_t x2 = lcd_info.width - cross_size;
+    rt_uint32_t y2 = lcd_info.height - cross_size;
+    rt_uint32_t x3 = cross_size;
+    rt_uint32_t y3 = lcd_info.height - cross_size;
+    const rt_uint32_t black = 0x0;
+    /* Upper left cross */
+    rt_graphix_ops(lcd)->draw_hline((const char *)(&black), 0, x0 + cross_size, y0);
+    rt_graphix_ops(lcd)->draw_vline((const char *)(&black), x0, 0, y0 + cross_size);
+
+    touch->min_raw_x = 0;
+    touch->min_raw_y = 0;
+    touch->max_raw_x = 4096;
+    touch->max_raw_y = 4096;
+    touch->parent.info.range_x = 4096;
+    touch->parent.info.range_y = 4096;
+
+    rt_uint16_t x_raw[4];
+    rt_uint16_t y_raw[4];
+    rt_uint8_t raw_idx = 0;
+    rt_memset(x_raw, 0, sizeof(x_raw));
+    rt_memset(y_raw, 0, sizeof(y_raw));
+    while (1)
+    {
+        struct rt_touch_data read_data;
+        rt_memset(&read_data, 0, sizeof(struct rt_touch_data));
+        if (rt_device_read((rt_device_t)touch, 0, &read_data, 1) == 1)
+        {
+            x_raw[raw_idx] = read_data.x_coordinate;
+            y_raw[raw_idx++] = read_data.y_coordinate;
+            LOG_I(" %d point capture", raw_idx - 1);
+            /* After processing a point, proceed to clear the screen */
+            for (rt_uint32_t y = 0; y < lcd_info.height; ++y)
+            {
+                const uint32_t white = 0xFFFFFFFF;
+                rt_graphix_ops(lcd)->draw_hline((const char *)(&white), 0, lcd_info.width, y);
+            }
+            rt_thread_mdelay(400);
+            if (raw_idx >= 4)
+            {
+                break;
+            }
+            switch (raw_idx)
+            {
+            case 1:
+                /* Upper right cross */
+                rt_graphix_ops(lcd)->draw_hline((const char *)(&black), x1 - cross_size, lcd_info.width, y1);
+                rt_graphix_ops(lcd)->draw_vline((const char *)(&black), x1, 0, y1 + cross_size);
+                break;
+            case 2:
+                /* lower right cross */
+                rt_graphix_ops(lcd)->draw_hline((const char *)(&black), x2 - cross_size, lcd_info.width, y2);
+                rt_graphix_ops(lcd)->draw_vline((const char *)(&black), x2, y2 - cross_size, lcd_info.height);
+                break;
+            case 3:
+                /* lower left cross */
+                rt_graphix_ops(lcd)->draw_hline((const char *)(&black), 0, x3 + cross_size, y3);
+                rt_graphix_ops(lcd)->draw_vline((const char *)(&black), x3, y3 - cross_size, lcd_info.height);
+                break;
+            default:
+                break;
+            }
+        }
+        rt_thread_mdelay(10);
+    }
+    rt_uint16_t min_x = (x_raw[0] + x_raw[3]) / 2;
+    rt_uint16_t max_x = (x_raw[1] + x_raw[2]) / 2;
+    rt_uint16_t min_y = (y_raw[0] + y_raw[1]) / 2;
+    rt_uint16_t max_y = (y_raw[2] + y_raw[3]) / 2;
+
+    rt_int32_t x_raw_cnt_per_pixel = (max_x - min_x) / (x1 - x0);
+    rt_int32_t y_raw_cnt_per_pixel = (max_y - min_y) / (y2 - y1);
+
+    min_x -= cross_size * x_raw_cnt_per_pixel;
+    max_x += cross_size * x_raw_cnt_per_pixel;
+    min_y -= cross_size * y_raw_cnt_per_pixel;
+    max_y += cross_size * y_raw_cnt_per_pixel;
+
+    touch->min_raw_x = min_x;
+    touch->min_raw_y = min_y;
+    touch->max_raw_x = max_x;
+    touch->max_raw_y = max_y;
+    touch->parent.info.range_x = lcd_info.width;
+    touch->parent.info.range_y = lcd_info.height;
+
+    LOG_I(" Calibration result, min_x:%d, min_y:%d, max_x:%d, max_y:%d", min_x, min_y, max_x, max_y);
+
+    rt_device_close(lcd);
+
+    return RT_EOK;
+}
+
+static rt_size_t xpt2046_touch_readpoint(struct rt_touch_device *touch, void *buf, rt_size_t touch_num)
+{
+    if (touch_num != 0)
+    {
+        struct rt_touch_data *result = (struct rt_touch_data *)buf;
+        rt_xpt2046_t dev = (rt_xpt2046_t)touch;
+#ifdef RT_TOUCH_PIN_IRQ
+        if (rt_pin_read(dev->parent.config.irq_pin.pin))
+        {
+            result->event = RT_TOUCH_EVENT_NONE;
+            return 0;
+        }
+#endif /* RT_TOUCH_PIN_IRQ */
+        rt_uint8_t rx_data[21];
+        rt_spi_transfer(dev->spi, xpt2046_tx_data, rx_data, 21);
+        rt_uint8_t x_count = 0;
+        rt_uint8_t y_count = 0;
+        rt_uint32_t x_cum = 0;
+        rt_uint32_t y_cum = 0;
+        for (rt_uint8_t i = 1; i < 11; i += 2)
+        {
+            rt_uint16_t temp = (rx_data[i] << 8 | rx_data[i + 1]) >> 4;
+            if (temp >= dev->min_raw_x && temp <= dev->max_raw_x)
+            {
+                ++x_count;
+                x_cum += temp;
+            }
+            temp = (rx_data[i + 10] << 8 | rx_data[i + 11]) >> 4;
+            if (temp >= dev->min_raw_y && temp <= dev->max_raw_y)
+            {
+                ++y_count;
+                y_cum += temp;
+            }
+        }
+        if (!x_count || !y_count)
+        {
+            result->event = RT_TOUCH_EVENT_NONE;
+            return 0;
+        }
+        result->event = RT_TOUCH_EVENT_DOWN;
+        result->x_coordinate = ((float)x_cum / x_count - dev->min_raw_x) / (dev->max_raw_x - dev->min_raw_x) * dev->parent.info.range_x;
+        result->y_coordinate = ((float)y_cum / y_count - dev->min_raw_y) / (dev->max_raw_y - dev->min_raw_y) * dev->parent.info.range_y;
+        return touch_num;
+    }
+    else
+    {
+        return 0;
+    }
+}
+
+static rt_err_t xpt2046_touch_control(struct rt_touch_device *touch, int cmd, void *arg)
+{
+    rt_err_t result = RT_EOK;
+    RT_ASSERT(touch != RT_NULL);
+
+    /* If necessary, please implement this control function yourself */
+
+    return result;
+}
+
+static struct rt_touch_ops xpt2046_ops =
+{
+    .touch_readpoint = xpt2046_touch_readpoint,
+    .touch_control = xpt2046_touch_control,
+};
+
+static int xpt2046_hw_init(void)
+{
+    rt_xpt2046_t dev_obj = rt_malloc(sizeof(struct rt_xpt2046));
+    if (dev_obj != RT_NULL)
+    {
+        rt_memset(dev_obj, 0x0, sizeof(struct rt_xpt2046));
+        dev_obj->min_raw_x = BSP_XPT2046_MIN_RAW_X;
+        dev_obj->min_raw_y = BSP_XPT2046_MIN_RAW_Y;
+        dev_obj->max_raw_x = BSP_XPT2046_MAX_RAW_X;
+        dev_obj->max_raw_y = BSP_XPT2046_MAX_RAW_Y;
+        /* spi mount and config is implemented by the user */
+        dev_obj->spi = RT_NULL;
+
+        dev_obj->parent.info.type = RT_TOUCH_TYPE_RESISTANCE;
+        dev_obj->parent.info.vendor = RT_TOUCH_VENDOR_UNKNOWN;
+        dev_obj->parent.info.point_num = 1;
+        dev_obj->parent.info.range_x = BSP_XPT2046_RANGE_X;
+        dev_obj->parent.info.range_y = BSP_XPT2046_RANGE_Y;
+#ifdef RT_TOUCH_PIN_IRQ
+        dev_obj->parent.config.irq_pin.pin = rt_pin_get(BSP_XPT2046_IRQ_PIN);
+        dev_obj->parent.config.irq_pin.mode = PIN_MODE_INPUT_PULLUP;
+#endif /* RT_TOUCH_PIN_IRQ */
+        dev_obj->parent.ops = &xpt2046_ops;
+
+        rt_uint8_t dev_num = 0;
+        char dev_name[RT_NAME_MAX];
+        do
+        {
+            rt_sprintf(dev_name, "xpt%d", dev_num++);
+            if (dev_num == 255)
+            {
+                rt_device_destroy((rt_device_t) & (dev_obj->parent));
+                return RT_NULL;
+            }
+        } while (rt_device_find(dev_name));
+        rt_hw_touch_register(&(dev_obj->parent), dev_name, RT_DEVICE_FLAG_INT_RX, RT_NULL);
+        return RT_EOK;
+    }
+    else
+    {
+        return -RT_ERROR;
+    }
+}
+
+INIT_DEVICE_EXPORT(xpt2046_hw_init);
+
+#endif /* BSP_USING_TOUCH_RES */

+ 44 - 0
bsp/stm32/stm32f407-atk-explorer/board/ports/touch/drv_touch_xpt.h

@@ -0,0 +1,44 @@
+/*
+ * Copyright (c) 2006-2022, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2022-6-27      solar        first version
+ */
+
+#ifndef __DRV_XPT2046_H__
+#define __DRV_XPT2046_H__
+
+#include <rtthread.h>
+#include <rtdevice.h>
+#include "touch.h"
+
+#ifdef BSP_USING_TOUCH_RES
+
+/* Related parameters of screen calibration, if the calibration is not performed
+ * after power on, please manually set the following macro definitions */
+#define BSP_XPT2046_MIN_RAW_X   100
+#define BSP_XPT2046_MIN_RAW_Y   100
+#define BSP_XPT2046_MAX_RAW_X   1950
+#define BSP_XPT2046_MAX_RAW_Y   1950
+#define BSP_XPT2046_RANGE_X     320
+#define BSP_XPT2046_RANGE_Y     480
+
+struct rt_xpt2046
+{
+    struct rt_touch_device parent;
+    struct rt_spi_device *spi;
+    rt_uint16_t min_raw_x;
+    rt_uint16_t min_raw_y;
+    rt_uint16_t max_raw_x;
+    rt_uint16_t max_raw_y;
+};
+typedef struct rt_xpt2046 *rt_xpt2046_t;
+
+rt_err_t xpt2046_calibration(const char *lcd_name,const char *touch_name);
+
+#endif /* BSP_USING_TOUCH_RES */
+
+#endif /* __DRV_XPT2046_H__ */

+ 136 - 0
bsp/stm32/stm32f407-atk-explorer/board/ports/touch/drv_xpt2046_init.c

@@ -0,0 +1,136 @@
+/*
+ * Copyright (c) 2006-2022, RT-Thread Development Team
+ *
+ * SPDX-License-Identifier: Apache-2.0
+ *
+ * Change Logs:
+ * Date           Author       Notes
+ * 2022-6-27      solar        first version
+ */
+
+#include <rtdevice.h>
+#include "drv_touch_xpt.h"
+#include "drv_soft_spi.h"
+
+#ifdef PKG_USING_GUIENGINE
+#include <rtgui/event.h>
+#include <rtgui/rtgui_server.h>
+#elif defined(PKG_USING_LITTLEVGL2RTT)
+#include <littlevgl2rtt.h>
+#elif defined(PKG_USING_LVGL)
+#include <lvgl.h>
+extern void lv_port_indev_input(rt_int16_t x, rt_int16_t y, lv_indev_state_t state);
+static rt_bool_t touch_down = RT_FALSE;
+#endif /* PKG_USING_GUIENGINE */
+
+#ifdef BSP_USING_TOUCH_RES
+
+/* If calibration is not required, please manually modify the contents of
+ * the drv_touch_xpt.h file,and set BSP_TOUCH_CALIBRATE to RT_FALSE */
+#define BSP_TOUCH_CALIBRATE RT_TRUE
+
+#define BSP_XPT2046_SPI_BUS "sspi1"
+#define TOUCH_DEVICE_NAME   "xpt0"
+#define TFTLCD_DEVICE_NAME  "lcd"
+
+void xpt2046_init_hw(void)
+{
+    /* Find the touch device */
+    rt_device_t touch = rt_device_find(TOUCH_DEVICE_NAME);
+    if (touch == RT_NULL)
+    {
+        rt_kprintf("can't find touch device:%s\n", TOUCH_DEVICE_NAME);
+        return;
+    }
+    if (rt_device_open(touch, RT_DEVICE_FLAG_INT_RX) != RT_EOK)
+    {
+        rt_kprintf("can't open touch device:%s\n", TOUCH_DEVICE_NAME);
+        return;
+    }
+
+    rt_uint8_t dev_num = 0;
+    char dev_name[RT_NAME_MAX];
+    do
+    {
+        rt_sprintf(dev_name, "%s%d", BSP_XPT2046_SPI_BUS, dev_num++);
+        if (dev_num == 255)
+        {
+            return;
+        }
+    } while (rt_device_find(dev_name));
+
+    /* Mount the spi device to the spi bus, here is the soft spi,
+     * if you use other spi, please modify the following */
+    rt_hw_soft_spi_device_attach(BSP_XPT2046_SPI_BUS, dev_name, BSP_XPT2046_CS_PIN);
+
+    /* configure spi device */
+    rt_xpt2046_t tc = (rt_xpt2046_t)touch;
+    tc->spi = (struct rt_spi_device *)rt_device_find(dev_name);
+    struct rt_spi_configuration spi_config;
+    spi_config.data_width = 8;
+    spi_config.mode = RT_SPI_MASTER | RT_SPI_MODE_0 | RT_SPI_MSB;
+    /* Max freq of XPT2046 is 2MHz */
+    spi_config.max_hz = 2000000;
+    rt_spi_configure(tc->spi, &spi_config);
+
+#if (BSP_TOUCH_CALIBRATE == RT_TRUE)
+    /* Calibrate touch */
+    xpt2046_calibration(TFTLCD_DEVICE_NAME,TOUCH_DEVICE_NAME);
+#endif /* BSP_TOUCH_CALIBRATE == RT_TRUE */
+
+    /* init the TFT LCD */
+    rt_device_t lcd = RT_NULL;
+
+    lcd = rt_device_find("lcd");
+    rt_device_init(lcd);
+}
+
+void xpt2046_entry(void *parameter)
+{
+    /* Find the touch device */
+    rt_device_t touch = rt_device_find(TOUCH_DEVICE_NAME);
+    if (touch == RT_NULL)
+    {
+        rt_kprintf("can't find touch device:%s\n", TOUCH_DEVICE_NAME);
+        return;
+    }
+#ifndef PKG_USING_LVGL
+    rt_device_t lcd = rt_device_find(TFTLCD_DEVICE_NAME);
+    if (lcd == RT_NULL)
+    {
+       rt_kprintf("can't find display device:%s\n", TFTLCD_DEVICE_NAME);
+       return;
+    }
+#endif /* PKG_USING_LVGL */
+    while (1)
+    {
+        /* Prepare variable to read out the touch data */
+        struct rt_touch_data read_data;
+        rt_memset(&read_data, 0, sizeof(struct rt_touch_data));
+        if (rt_device_read(touch, 0, &read_data, 1) == 1)
+        {
+#ifdef PKG_USING_LVGL
+            lv_port_indev_input(read_data.x_coordinate, read_data.y_coordinate,
+                                ((read_data.event = RT_TOUCH_EVENT_DOWN) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL));
+#else /* PKG_USING_LVGL */
+            const rt_uint32_t black = 0x0;
+            rt_graphix_ops(lcd)->set_pixel((const char *)(&black),
+                                        read_data.x_coordinate,
+                                         read_data.y_coordinate);
+#endif /* PKG_USING_LVGL */
+        }
+        rt_thread_mdelay(1);
+    }
+}
+
+static int touch_xpt2046_init(void)
+{
+    xpt2046_init_hw();
+    rt_thread_t tid = rt_thread_create("xpt2046", xpt2046_entry, RT_NULL, 1024, 8, 20);
+    RT_ASSERT(tid != RT_NULL);
+    rt_thread_startup(tid);
+    return RT_EOK;
+}
+INIT_COMPONENT_EXPORT(touch_xpt2046_init);
+
+#endif /* BSP_USING_TOUCH_RES */