Marge branch 'master' into lvgl_7.11.0_idf_5.0

This commit is contained in:
Luc Appelman 2023-05-17 10:17:09 +02:00
commit a73c429954
62 changed files with 2427 additions and 1270 deletions

View file

@ -1,28 +1,29 @@
menu "LVGL Touch controller"
config LV_TOUCH_CONTROLLER
int
default 0 if LV_TOUCH_CONTROLLER_NONE
default 1 if LV_TOUCH_CONTROLLER_XPT2046
default 2 if LV_TOUCH_CONTROLLER_FT6X06
default 3 if LV_TOUCH_CONTROLLER_STMPE610
int
default 0 if LV_TOUCH_CONTROLLER_NONE
default 1 if LV_TOUCH_CONTROLLER_XPT2046
default 2 if LV_TOUCH_CONTROLLER_FT6X06
default 3 if LV_TOUCH_CONTROLLER_STMPE610
default 4 if LV_TOUCH_CONTROLLER_ADCRAW
default 5 if LV_TOUCH_CONTROLLER_FT81X
default 6 if LV_TOUCH_CONTROLLER_RA8875
default 7 if LV_TOUCH_CONTROLLER_GT911
choice
prompt "Select a touch panel controller model."
default LV_TOUCH_CONTROLLER_NONE
help
Select the controller for your touch panel.
prompt "Select a touch panel controller model."
default LV_TOUCH_CONTROLLER_NONE
help
Select the controller for your touch panel.
config LV_TOUCH_CONTROLLER_NONE
bool "None"
config LV_TOUCH_CONTROLLER_XPT2046
config LV_TOUCH_CONTROLLER_NONE
bool "None"
config LV_TOUCH_CONTROLLER_XPT2046
select LV_TOUCH_DRIVER_PROTOCOL_SPI
bool "XPT2046"
config LV_TOUCH_CONTROLLER_FT6X06
select LV_TOUCH_DRIVER_PROTOCOL_I2C
config LV_TOUCH_CONTROLLER_FT6X06
select LV_I2C_TOUCH
bool "FT6X06"
config LV_TOUCH_CONTROLLER_STMPE610
select LV_TOUCH_DRIVER_PROTOCOL_SPI
@ -36,14 +37,17 @@ menu "LVGL Touch controller"
config LV_TOUCH_CONTROLLER_RA8875
select LV_TOUCH_DRIVER_DISPLAY
bool "RA8875"
config LV_TOUCH_CONTROLLER_GT911
select LV_I2C_TOUCH
bool "GT911"
endchoice
config LV_TOUCH_DRIVER_PROTOCOL_SPI
bool
help
Touch controller protocol SPI
config LV_TOUCH_DRIVER_PROTOCOL_I2C
config LV_I2C_TOUCH
bool
help
Touch controller protocol I2C
@ -57,48 +61,29 @@ menu "LVGL Touch controller"
bool
help
Touch controller uses same interface/device as display
(Note: Display must be initialized before touch)
choice
prompt "Touch I2C port"
depends on LV_TOUCH_DRIVER_PROTOCOL_I2C
default LV_TOUCH_I2C_PORT_0
help
Select the I2C port used by the touch controller.
(Note: Display must be initialized before touch)
config LV_TOUCH_I2C_PORT_0
bool "I2C PORT 0"
config LV_TOUCH_I2C_PORT_1
bool "I2C PORT 1"
endchoice
choice
prompt "Touch Controller SPI Bus."
depends on LV_TOUCH_DRIVER_PROTOCOL_SPI
default LV_TOUCH_CONTROLLER_SPI_VSPI if !IDF_TARGET_ESP32S2
default LV_TOUCH_CONTROLLER_SPI_FSPI if IDF_TARGET_ESP32S2
default LV_TOUCH_CONTROLLER_SPI2_HOST
help
Select the SPI Bus the TFT Display is attached to.
config LV_TOUCH_CONTROLLER_SPI_HSPI
bool "HSPI"
config LV_TOUCH_CONTROLLER_SPI_VSPI
bool "VSPI" if !IDF_TARGET_ESP32S2
config LV_TOUCH_CONTROLLER_SPI_FSPI
bool "FSPI" if IDF_TARGET_ESP32S2
Select the SPI Bus the touch controller is attached to.
config LV_TOUCH_CONTROLLER_SPI2_HOST
bool "SPI2_HOST"
config LV_TOUCH_CONTROLLER_SPI3_HOST
bool "SPI3_HOST"
endchoice
menu "Touchpanel (XPT2046) Pin Assignments"
depends on LV_TOUCH_CONTROLLER_XPT2046
config LV_TOUCH_SPI_MISO
int
prompt "GPIO for MISO (Master In Slave Out)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 35 if LV_PREDEFINED_PINS_38V1
default 19
help
@ -107,8 +92,6 @@ menu "LVGL Touch controller"
config LV_TOUCH_SPI_MOSI
int
prompt "GPIO for MOSI (Master Out Slave In)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 32 if LV_PREDEFINED_PINS_38V1
default 23
@ -117,9 +100,7 @@ menu "LVGL Touch controller"
config LV_TOUCH_SPI_CLK
int "GPIO for CLK (SCK / Serial Clock)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 26 if LV_PREDEFINED_PINS_38V1
default 18
help
@ -127,9 +108,7 @@ menu "LVGL Touch controller"
config LV_TOUCH_SPI_CS
int "GPIO for CS (Slave Select)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 33 if LV_PREDEFINED_PINS_38V1
default 5
help
@ -137,15 +116,13 @@ menu "LVGL Touch controller"
config LV_TOUCH_PIN_IRQ
int "GPIO for IRQ (Interrupt Request)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 27 if LV_PREDEFINED_PINS_38V4
default 25
help
Configure the touchpanel IRQ pin here.
endmenu
menu "Touchpanel Configuration (XPT2046)"
depends on LV_TOUCH_CONTROLLER_XPT2046
@ -172,11 +149,11 @@ menu "LVGL Touch controller"
prompt "Maximum Y coordinate value."
default 4095 if LV_PREDEFINED_PINS_38V4
default 1900
config LV_TOUCH_XY_SWAP
bool
prompt "Swap XY."
default y
config LV_TOUCH_XY_SWAP
bool
prompt "Swap XY."
default y
config LV_TOUCH_INVERT_X
bool
@ -203,36 +180,13 @@ menu "LVGL Touch controller"
endchoice
endmenu
menu "Touchpanel (FT6X06) Pin Assignments"
depends on LV_TOUCH_CONTROLLER_FT6X06
config LV_TOUCH_I2C_SDA
int
prompt "GPIO for SDA (I2C)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 21
help
Configure the I2C touchpanel SDA pin here.
config LV_TOUCH_I2C_SCL
int "GPIO for clock signal SCL (I2C)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 22
help
Configure the I2C touchpanel SCL pin here.
endmenu
menu "Touchpanel Configuration (FT6X06)"
depends on LV_TOUCH_CONTROLLER_FT6X06
config LV_FT6X36_SWAPXY
bool
prompt "Swap X with Y coordinate."
default y
config LV_FT6X36_SWAPXY
bool
prompt "Swap X with Y coordinate."
default n
config LV_FT6X36_INVERT_X
bool
@ -242,19 +196,24 @@ menu "LVGL Touch controller"
config LV_FT6X36_INVERT_Y
bool
prompt "Invert Y coordinate value."
default y
default n
config LV_FT6X36_COORDINATES_QUEUE
bool
prompt "Send coordinates to FreeRTOS queue."
default n
help
Receive from the FreeRTOS queue using the handle 'ft6x36_touch_queue_handle'.
endmenu
menu "Touchpanel (STMPE610) Pin Assignments"
depends on LV_TOUCH_CONTROLLER_STMPE610
config LV_TOUCH_SPI_MISO
int
prompt "GPIO for MISO (Master In Slave Out)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 35 if LV_PREDEFINED_PINS_38V1
default 19 if LV_PREDEFINED_DISPLAY_ADA_FEATHERWING
default 19
@ -263,10 +222,9 @@ menu "LVGL Touch controller"
Configure the touchpanel MISO pin here.
config LV_TOUCH_SPI_MOSI
# TODO Fix default for ESP32C3
int
prompt "GPIO for MOSI (Master Out Slave In)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 32 if LV_PREDEFINED_PINS_38V1
default 18 if LV_PREDEFINED_DISPLAY_ADA_FEATHERWING
@ -277,8 +235,6 @@ menu "LVGL Touch controller"
config LV_TOUCH_SPI_CLK
int "GPIO for CLK (SCK / Serial Clock)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 26 if LV_PREDEFINED_PINS_38V1
default 5 if LV_PREDEFINED_DISPLAY_ADA_FEATHERWING
@ -288,9 +244,6 @@ menu "LVGL Touch controller"
config LV_TOUCH_SPI_CS
int "GPIO for CS (Slave Select)"
range 0 39 if IDF_TARGET_ESP32
range 0 43 if IDF_TARGET_ESP32S2
default 33 if LV_PREDEFINED_PINS_38V1
default 32 if LV_PREDEFINED_DISPLAY_ADA_FEATHERWING
default 5
@ -320,11 +273,11 @@ menu "LVGL Touch controller"
int
prompt "Maximum Y coordinate value."
default 3800
config LV_TOUCH_XY_SWAP
bool
prompt "Swap XY."
default n
bool
prompt "Swap XY."
default n
config LV_TOUCH_INVERT_X
bool
@ -336,7 +289,7 @@ menu "LVGL Touch controller"
prompt "Invert Y coordinate value."
default y
endmenu
menu "Touchpanel (ADCRAW) Pin Assignments"
depends on LV_TOUCH_CONTROLLER_ADCRAW
@ -357,7 +310,7 @@ menu "LVGL Touch controller"
help
Configure the touchpanel Y- pin. Must be ADC input.
config LV_TOUCHSCREEN_RESISTIVE_PIN_XL
int
prompt "GPIO X-"
@ -423,25 +376,25 @@ menu "LVGL Touch controller"
config LV_TOUCH_X_MIN
int
prompt "Minimum X coordinate ADC value"
range 0 1023
range 0 1023
default 0
config LV_TOUCH_Y_MIN
int
prompt "Minimum Y coordinate ADC value"
range 0 1023
range 0 1023
default 0
config LV_TOUCH_X_MAX
int
prompt "Maximum X coordinate ADC value"
range 0 1023
range 0 1023
default 1023
config LV_TOUCH_Y_MAX
int
prompt "Maximum Y coordinate ADC value"
range 0 1023
range 0 1023
default 1023
config LV_TOUCH_XY_SWAP
@ -462,13 +415,13 @@ menu "LVGL Touch controller"
config LV_TOUCH_RA8875_SAMPLE_TIME
int
prompt "TP Sample Time Adjusting"
range 0 7
range 0 7
default 0
config LV_TOUCH_RA8875_ADC_CLOCK
int
prompt "ADC Clock Setting"
range 0 7
range 0 7
default 0
config LV_TOUCH_RA8875_WAKEUP_ENABLE
@ -488,4 +441,57 @@ menu "LVGL Touch controller"
endmenu
menu "Touchpanel Configuration (GT911)"
depends on LV_TOUCH_CONTROLLER_GT911
config LV_GT911_SWAPXY
bool
prompt "Swap X with Y coordinate."
default y
config LV_GT911_INVERT_X
bool
prompt "Invert X coordinate value."
default n
config LV_GT911_INVERT_Y
bool
prompt "Invert Y coordinate value."
default y
endmenu
choice
prompt "Select an I2C port for the touch panel"
default LV_I2C_TOUCH_PORT_0
depends on LV_I2C_TOUCH
config LV_I2C_TOUCH_PORT_0
bool
prompt "I2C port 0"
help
I2C is shared peripheral managed by I2C Manager. In order to configure I2C Manager (pinout, etc.) see menu
Component config->I2C Port Settings.
config LV_I2C_TOUCH_PORT_1
bool
prompt "I2C port 1"
help
I2C is shared peripheral managed by I2C Manager. In order to configure I2C Manager (pinout, etc.) see menu
Component config->I2C Port Settings.
endchoice
config LV_I2C
bool
default y if LV_I2C_TOUCH
config LV_I2C_TOUCH_PORT
int
default 1 if LV_I2C_TOUCH_PORT_1
default 0
endmenu

View file

@ -1,55 +1,45 @@
/*
* Copyright © 2020 Wolfgang Christl
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include <esp_log.h>
#include <driver/i2c.h>
#ifdef LV_LVGL_H_INCLUDE_SIMPLE
#include <lvgl.h>
#else
#include <lvgl/lvgl.h>
#endif
#include "ft6x36.h"
#include "tp_i2c.h"
#include "../lvgl_i2c_conf.h"
#include "lvgl_i2c/i2c_manager.h"
#define TAG "FT6X36"
#define FT6X36_TOUCH_QUEUE_ELEMENTS 1
ft6x36_status_t ft6x36_status;
uint8_t current_dev_addr; // set during init
static ft6x36_status_t ft6x36_status;
static uint8_t current_dev_addr; // set during init
static ft6x36_touch_t touch_inputs = { -1, -1, LV_INDEV_STATE_REL }; // -1 coordinates to designate it was never touched
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
QueueHandle_t ft6x36_touch_queue_handle;
#endif
esp_err_t ft6x06_i2c_read8(uint8_t slave_addr, uint8_t register_addr, uint8_t *data_buf) {
i2c_cmd_handle_t i2c_cmd = i2c_cmd_link_create();
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (slave_addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_write_byte(i2c_cmd, register_addr, I2C_MASTER_ACK);
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (slave_addr << 1) | I2C_MASTER_READ, true);
i2c_master_read_byte(i2c_cmd, data_buf, I2C_MASTER_NACK);
i2c_master_stop(i2c_cmd);
esp_err_t ret = i2c_master_cmd_begin(TOUCH_I2C_PORT, i2c_cmd, 1000 / portTICK_PERIOD_MS);
i2c_cmd_link_delete(i2c_cmd);
return ret;
static esp_err_t ft6x06_i2c_read8(uint8_t slave_addr, uint8_t register_addr, uint8_t *data_buf) {
return lvgl_i2c_read(CONFIG_LV_I2C_TOUCH_PORT, slave_addr, register_addr, data_buf, 1);
}
/**
@ -75,42 +65,38 @@ uint8_t ft6x36_get_gesture_id() {
* @retval None
*/
void ft6x06_init(uint16_t dev_addr) {
if (!ft6x36_status.inited) {
/* I2C master is initialized before calling this function */
#if 0
esp_err_t code = i2c_master_init();
#else
esp_err_t code = ESP_OK;
#endif
ft6x36_status.inited = true;
current_dev_addr = dev_addr;
uint8_t data_buf;
esp_err_t ret;
ESP_LOGI(TAG, "Found touch panel controller");
if ((ret = ft6x06_i2c_read8(dev_addr, FT6X36_PANEL_ID_REG, &data_buf) != ESP_OK))
ESP_LOGE(TAG, "Error reading from device: %s",
esp_err_to_name(ret)); // Only show error the first time
ESP_LOGI(TAG, "\tDevice ID: 0x%02x", data_buf);
if (code != ESP_OK) {
ft6x36_status.inited = false;
ESP_LOGE(TAG, "Error during I2C init %s", esp_err_to_name(code));
} else {
ft6x36_status.inited = true;
current_dev_addr = dev_addr;
uint8_t data_buf;
esp_err_t ret;
ESP_LOGI(TAG, "Found touch panel controller");
if ((ret = ft6x06_i2c_read8(dev_addr, FT6X36_PANEL_ID_REG, &data_buf) != ESP_OK))
ESP_LOGE(TAG, "Error reading from device: %s",
esp_err_to_name(ret)); // Only show error the first time
ESP_LOGI(TAG, "\tDevice ID: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_CHIPSELECT_REG, &data_buf);
ESP_LOGI(TAG, "\tChip ID: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_CHIPSELECT_REG, &data_buf);
ESP_LOGI(TAG, "\tChip ID: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_DEV_MODE_REG, &data_buf);
ESP_LOGI(TAG, "\tDevice mode: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_DEV_MODE_REG, &data_buf);
ESP_LOGI(TAG, "\tDevice mode: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_FIRMWARE_ID_REG, &data_buf);
ESP_LOGI(TAG, "\tFirmware ID: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_FIRMWARE_ID_REG, &data_buf);
ESP_LOGI(TAG, "\tFirmware ID: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_RELEASECODE_REG, &data_buf);
ESP_LOGI(TAG, "\tRelease code: 0x%02x", data_buf);
ft6x06_i2c_read8(dev_addr, FT6X36_RELEASECODE_REG, &data_buf);
ESP_LOGI(TAG, "\tRelease code: 0x%02x", data_buf);
}
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
ft6x36_touch_queue_handle = xQueueCreate( FT6X36_TOUCH_QUEUE_ELEMENTS, sizeof( ft6x36_touch_t ) );
if( ft6x36_touch_queue_handle == NULL )
{
ESP_LOGE( TAG, "\tError creating touch input FreeRTOS queue" );
return;
}
xQueueSend( ft6x36_touch_queue_handle, &touch_inputs, 0 );
#endif
}
/**
@ -120,82 +106,55 @@ void ft6x06_init(uint16_t dev_addr) {
* @retval Always false
*/
bool ft6x36_read(lv_indev_drv_t *drv, lv_indev_data_t *data) {
uint8_t data_xy[4]; // 2 bytes X | 2 bytes Y
uint8_t touch_pnt_cnt; // Number of detected touch points
static int16_t last_x = 0; // 12bit pixel value
static int16_t last_y = 0; // 12bit pixel value
ft6x06_i2c_read8(current_dev_addr, FT6X36_TD_STAT_REG, &touch_pnt_cnt);
if (touch_pnt_cnt != 1) { // ignore no touch & multi touch
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_REL;
return false;
if (!ft6x36_status.inited) {
ESP_LOGE(TAG, "Init first!");
return 0x00;
}
uint8_t data_buf[5]; // 1 byte status, 2 bytes X, 2 bytes Y
// Read X value
i2c_cmd_handle_t i2c_cmd = i2c_cmd_link_create();
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (current_dev_addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_write_byte(i2c_cmd, FT6X36_P1_XH_REG, I2C_MASTER_ACK);
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (current_dev_addr << 1) | I2C_MASTER_READ, true);
i2c_master_read_byte(i2c_cmd, &data_xy[0], I2C_MASTER_ACK); // reads FT6X36_P1_XH_REG
i2c_master_read_byte(i2c_cmd, &data_xy[1], I2C_MASTER_NACK); // reads FT6X36_P1_XL_REG
i2c_master_stop(i2c_cmd);
esp_err_t ret = i2c_master_cmd_begin(TOUCH_I2C_PORT, i2c_cmd, 1000 / portTICK_PERIOD_MS);
i2c_cmd_link_delete(i2c_cmd);
esp_err_t ret = lvgl_i2c_read(CONFIG_LV_I2C_TOUCH_PORT, current_dev_addr, FT6X36_TD_STAT_REG, &data_buf[0], 5);
if (ret != ESP_OK) {
ESP_LOGE(TAG, "Error getting X coordinates: %s", esp_err_to_name(ret));
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_REL; // no touch detected
ESP_LOGE(TAG, "Error talking to touch IC: %s", esp_err_to_name(ret));
}
uint8_t touch_pnt_cnt = data_buf[0]; // Number of detected touch points
if (ret != ESP_OK || touch_pnt_cnt != 1) { // ignore no touch & multi touch
if ( touch_inputs.current_state != LV_INDEV_STATE_REL)
{
touch_inputs.current_state = LV_INDEV_STATE_REL;
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
xQueueOverwrite( ft6x36_touch_queue_handle, &touch_inputs );
#endif
}
data->point.x = touch_inputs.last_x;
data->point.y = touch_inputs.last_y;
data->state = touch_inputs.current_state;
return false;
}
// Read Y value
i2c_cmd = i2c_cmd_link_create();
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (current_dev_addr << 1) | I2C_MASTER_WRITE, true);
i2c_master_write_byte(i2c_cmd, FT6X36_P1_YH_REG, I2C_MASTER_ACK);
i2c_master_start(i2c_cmd);
i2c_master_write_byte(i2c_cmd, (current_dev_addr << 1) | I2C_MASTER_READ, true);
i2c_master_read_byte(i2c_cmd, &data_xy[2], I2C_MASTER_ACK); // reads FT6X36_P1_YH_REG
i2c_master_read_byte(i2c_cmd, &data_xy[3], I2C_MASTER_NACK); // reads FT6X36_P1_YL_REG
i2c_master_stop(i2c_cmd);
ret = i2c_master_cmd_begin(TOUCH_I2C_PORT, i2c_cmd, 1000 / portTICK_PERIOD_MS);
i2c_cmd_link_delete(i2c_cmd);
if (ret != ESP_OK) {
ESP_LOGE(TAG, "Error getting Y coordinates: %s", esp_err_to_name(ret));
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_REL; // no touch detected
return false;
}
last_x = ((data_xy[0] & FT6X36_MSB_MASK) << 8) | (data_xy[1] & FT6X36_LSB_MASK);
last_y = ((data_xy[2] & FT6X36_MSB_MASK) << 8) | (data_xy[3] & FT6X36_LSB_MASK);
touch_inputs.current_state = LV_INDEV_STATE_PR;
touch_inputs.last_x = ((data_buf[1] & FT6X36_MSB_MASK) << 8) | (data_buf[2] & FT6X36_LSB_MASK);
touch_inputs.last_y = ((data_buf[3] & FT6X36_MSB_MASK) << 8) | (data_buf[4] & FT6X36_LSB_MASK);
#if CONFIG_LV_FT6X36_SWAPXY
int16_t swap_buf = last_x;
last_x = last_y;
last_y = swap_buf;
int16_t swap_buf = touch_inputs.last_x;
touch_inputs.last_x = touch_inputs.last_y;
touch_inputs.last_y = swap_buf;
#endif
#if CONFIG_LV_FT6X36_INVERT_X
last_x = LV_HOR_RES - last_x;
touch_inputs.last_x = LV_HOR_RES - touch_inputs.last_x;
#endif
#if CONFIG_LV_FT6X36_INVERT_Y
last_y = LV_VER_RES - last_y;
touch_inputs.last_y = LV_VER_RES - touch_inputs.last_y;
#endif
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_PR;
ESP_LOGV(TAG, "X=%u Y=%u", data->point.x, data->point.y);
data->point.x = touch_inputs.last_x;
data->point.y = touch_inputs.last_y;
data->state = touch_inputs.current_state;
ESP_LOGD(TAG, "X=%u Y=%u", data->point.x, data->point.y);
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
xQueueOverwrite( ft6x36_touch_queue_handle, &touch_inputs );
#endif
return false;
}

View file

@ -2,20 +2,20 @@
/*
* Copyright © 2020 Wolfgang Christl
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
@ -23,6 +23,10 @@
#include <stdint.h>
#include <stdbool.h>
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
#include "freertos/FreeRTOS.h"
#include "freertos/queue.h"
#endif
#ifdef LV_LVGL_H_INCLUDE_SIMPLE
#include "lvgl.h"
#else
@ -145,6 +149,16 @@ typedef struct {
bool inited;
} ft6x36_status_t;
typedef struct
{
int16_t last_x;
int16_t last_y;
lv_indev_state_t current_state;
} ft6x36_touch_t;
#if CONFIG_LV_FT6X36_COORDINATES_QUEUE
extern QueueHandle_t ft6x36_touch_queue_handle;
#endif
/**
* @brief Initialize for FT6x36 communication via I2C
* @param dev_addr: Device address on communication Bus (I2C slave address of FT6X36).

144
lvgl_touch/gt911.c Normal file
View file

@ -0,0 +1,144 @@
/*
* Copyright © 2021 Sturnus Inc.
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include <esp_log.h>
#ifdef LV_LVGL_H_INCLUDE_SIMPLE
#include <lvgl.h>
#else
#include <lvgl/lvgl.h>
#endif
#include "gt911.h"
#include "lvgl_i2c/i2c_manager.h"
#define TAG "GT911"
gt911_status_t gt911_status;
//TODO: handle multibyte read and refactor to just one read transaction
esp_err_t gt911_i2c_read(uint8_t slave_addr, uint16_t register_addr, uint8_t *data_buf, uint8_t len) {
return lvgl_i2c_read(CONFIG_LV_I2C_TOUCH_PORT, slave_addr, register_addr | I2C_REG_16, data_buf, len);
}
esp_err_t gt911_i2c_write8(uint8_t slave_addr, uint16_t register_addr, uint8_t data) {
uint8_t buffer = data;
return lvgl_i2c_write(CONFIG_LV_I2C_TOUCH_PORT, slave_addr, register_addr | I2C_REG_16, &buffer, 1);
}
/**
* @brief Initialize for GT911 communication via I2C
* @param dev_addr: Device address on communication Bus (I2C slave address of GT911).
* @retval None
*/
void gt911_init(uint8_t dev_addr) {
if (!gt911_status.inited) {
gt911_status.i2c_dev_addr = dev_addr;
uint8_t data_buf;
esp_err_t ret;
ESP_LOGI(TAG, "Checking for GT911 Touch Controller");
if ((ret = gt911_i2c_read(dev_addr, GT911_PRODUCT_ID1, &data_buf, 1) != ESP_OK)) {
ESP_LOGE(TAG, "Error reading from device: %s",
esp_err_to_name(ret)); // Only show error the first time
return;
}
// Read 4 bytes for Product ID in ASCII
for (int i = 0; i < GT911_PRODUCT_ID_LEN; i++) {
gt911_i2c_read(dev_addr, (GT911_PRODUCT_ID1 + i), (uint8_t *)&(gt911_status.product_id[i]), 1);
}
ESP_LOGI(TAG, "\tProduct ID: %s", gt911_status.product_id);
gt911_i2c_read(dev_addr, GT911_VENDOR_ID, &data_buf, 1);
ESP_LOGI(TAG, "\tVendor ID: 0x%02x", data_buf);
gt911_i2c_read(dev_addr, GT911_X_COORD_RES_L, &data_buf, 1);
gt911_status.max_x_coord = data_buf;
gt911_i2c_read(dev_addr, GT911_X_COORD_RES_H, &data_buf, 1);
gt911_status.max_x_coord |= ((uint16_t)data_buf << 8);
ESP_LOGI(TAG, "\tX Resolution: %d", gt911_status.max_x_coord);
gt911_i2c_read(dev_addr, GT911_Y_COORD_RES_L, &data_buf, 1);
gt911_status.max_y_coord = data_buf;
gt911_i2c_read(dev_addr, GT911_Y_COORD_RES_H, &data_buf, 1);
gt911_status.max_y_coord |= ((uint16_t)data_buf << 8);
ESP_LOGI(TAG, "\tY Resolution: %d", gt911_status.max_y_coord);
gt911_status.inited = true;
}
}
/**
* @brief Get the touch screen X and Y positions values. Ignores multi touch
* @param drv:
* @param data: Store data here
* @retval Always false
*/
bool gt911_read(lv_indev_drv_t *drv, lv_indev_data_t *data) {
uint8_t touch_pnt_cnt; // Number of detected touch points
static int16_t last_x = 0; // 12bit pixel value
static int16_t last_y = 0; // 12bit pixel value
uint8_t data_buf;
uint8_t status_reg;
gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_STATUS_REG, &status_reg, 1);
// ESP_LOGI(TAG, "\tstatus: 0x%02x", status_reg);
touch_pnt_cnt = status_reg & 0x0F;
if ((status_reg & 0x80) || (touch_pnt_cnt < 6)) {
//Reset Status Reg Value
gt911_i2c_write8(gt911_status.i2c_dev_addr, GT911_STATUS_REG, 0x00);
}
if (touch_pnt_cnt != 1) { // ignore no touch & multi touch
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_REL;
return false;
}
// gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_TRACK_ID1, &data_buf, 1);
// ESP_LOGI(TAG, "\ttrack_id: %d", data_buf);
gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_PT1_X_COORD_L, &data_buf, 1);
last_x = data_buf;
gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_PT1_X_COORD_H, &data_buf, 1);
last_x |= ((uint16_t)data_buf << 8);
gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_PT1_Y_COORD_L, &data_buf, 1);
last_y = data_buf;
gt911_i2c_read(gt911_status.i2c_dev_addr, GT911_PT1_Y_COORD_H, &data_buf, 1);
last_y |= ((uint16_t)data_buf << 8);
#if CONFIG_LV_GT911_INVERT_X
last_x = gt911_status.max_x_coord - last_x;
#endif
#if CONFIG_LV_GT911_INVERT_Y
last_y = gt911_status.max_y_coord - last_y;
#endif
#if CONFIG_LV_GT911_SWAPXY
int16_t swap_buf = last_x;
last_x = last_y;
last_y = swap_buf;
#endif
data->point.x = last_x;
data->point.y = last_y;
data->state = LV_INDEV_STATE_PR;
ESP_LOGI(TAG, "X=%u Y=%u", data->point.x, data->point.y);
ESP_LOGV(TAG, "X=%u Y=%u", data->point.x, data->point.y);
return false;
}

94
lvgl_touch/gt911.h Normal file
View file

@ -0,0 +1,94 @@
#ifndef __GT911_H
/*
* Copyright © 2021 Sturnus Inc.
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#define __GT911_H
#include <stdint.h>
#include <stdbool.h>
#ifdef LV_LVGL_H_INCLUDE_SIMPLE
#include "lvgl.h"
#else
#include "lvgl/lvgl.h"
#endif
#ifdef __cplusplus
extern "C" {
#endif
#define GT911_I2C_SLAVE_ADDR 0x5D
#define GT911_PRODUCT_ID_LEN 4
/* Register Map of GT911 */
#define GT911_PRODUCT_ID1 0x8140
#define GT911_PRODUCT_ID2 0x8141
#define GT911_PRODUCT_ID3 0x8142
#define GT911_PRODUCT_ID4 0x8143
#define GT911_FIRMWARE_VER_L 0x8144
#define GT911_FIRMWARE_VER_H 0x8145
#define GT911_X_COORD_RES_L 0x8146
#define GT911_X_COORD_RES_H 0x8147
#define GT911_Y_COORD_RES_L 0x8148
#define GT911_Y_COORD_RES_H 0x8149
#define GT911_VENDOR_ID 0x814A
#define GT911_STATUS_REG 0x814E
#define GT911_STATUS_REG_BUF 0x80
#define GT911_STATUS_REG_LARGE 0x40
#define GT911_STATUS_REG_PROX_VALID 0x20
#define GT911_STATUS_REG_HAVEKEY 0x10
#define GT911_STATUS_REG_PT_MASK 0x0F
#define GT911_TRACK_ID1 0x814F
#define GT911_PT1_X_COORD_L 0x8150
#define GT911_PT1_X_COORD_H 0x8151
#define GT911_PT1_Y_COORD_L 0x8152
#define GT911_PT1_Y_COORD_H 0x8153
#define GT911_PT1_X_SIZE_L 0x8154
#define GT911_PT1_X_SIZE_H 0x8155
typedef struct {
bool inited;
char product_id[GT911_PRODUCT_ID_LEN];
uint16_t max_x_coord;
uint16_t max_y_coord;
uint8_t i2c_dev_addr;
} gt911_status_t;
/**
* @brief Initialize for GT911 communication via I2C
* @param dev_addr: Device address on communication Bus (I2C slave address of GT911).
* @retval None
*/
void gt911_init(uint8_t dev_addr);
/**
* @brief Get the touch screen X and Y positions values. Ignores multi touch
* @param drv:
* @param data: Store data here
* @retval Always false
*/
bool gt911_read(lv_indev_drv_t *drv, lv_indev_data_t *data);
#ifdef __cplusplus
}
#endif
#endif /* __GT911_H */

View file

@ -4,7 +4,6 @@
#include "touch_driver.h"
#include "tp_spi.h"
#include "tp_i2c.h"
void touch_driver_init(void)
@ -21,10 +20,16 @@ void touch_driver_init(void)
/* nothing to do */
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_RA8875)
ra8875_touch_init();
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_GT911)
gt911_init(GT911_I2C_SLAVE_ADDR);
#endif
}
#if LVGL_VERSION_MAJOR >= 8
void touch_driver_read(lv_indev_drv_t *drv, lv_indev_data_t *data)
#else
bool touch_driver_read(lv_indev_drv_t *drv, lv_indev_data_t *data)
#endif
{
bool res = false;
@ -40,8 +45,14 @@ bool touch_driver_read(lv_indev_drv_t *drv, lv_indev_data_t *data)
res = FT81x_read(drv, data);
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_RA8875)
res = ra8875_touch_read(drv, data);
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_GT911)
res = gt911_read(drv, data);
#endif
#if LVGL_VERSION_MAJOR >= 8
data->continue_reading = res;
#else
return res;
#endif
}

View file

@ -32,6 +32,8 @@ extern "C" {
#include "FT81x.h"
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_RA8875)
#include "ra8875_touch.h"
#elif defined (CONFIG_LV_TOUCH_CONTROLLER_GT911)
#include "gt911.h"
#endif
/*********************
@ -42,7 +44,12 @@ extern "C" {
* GLOBAL PROTOTYPES
**********************/
void touch_driver_init(void);
#if LVGL_VERSION_MAJOR >= 8
void touch_driver_read(lv_indev_drv_t *drv, lv_indev_data_t *data);
#else
bool touch_driver_read(lv_indev_drv_t *drv, lv_indev_data_t *data);
#endif
#ifdef __cplusplus
} /* extern "C" */

View file

@ -1,43 +0,0 @@
/*
* Copyright © 2020 Wolfgang Christl
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#include <driver/i2c.h>
#include <esp_log.h>
#define I2C_MASTER_FREQ_HZ 100000 /* 100kHz*/
#define I2C_MASTER_TX_BUF_DISABLE 0 /* I2C master doesn't need buffer */
#define I2C_MASTER_RX_BUF_DISABLE 0 /* I2C master doesn't need buffer */
/**
* @brief ESP32 I2C init as master
* @ret ESP32 error code
*/
esp_err_t i2c_master_init(void) {
int i2c_master_port = I2C_NUM_0;
i2c_config_t conf;
conf.mode = I2C_MODE_MASTER;
conf.sda_io_num = CONFIG_LV_TOUCH_I2C_SDA;
conf.sda_pullup_en = GPIO_PULLUP_ENABLE;
conf.scl_io_num = CONFIG_LV_TOUCH_I2C_SCL;
conf.scl_pullup_en = GPIO_PULLUP_ENABLE;
conf.master.clk_speed = I2C_MASTER_FREQ_HZ;
i2c_param_config(i2c_master_port, &conf);
return i2c_driver_install(i2c_master_port, conf.mode, I2C_MASTER_RX_BUF_DISABLE, I2C_MASTER_TX_BUF_DISABLE, 0);
}

View file

@ -1,36 +0,0 @@
/*
* Copyright © 2020 Wolfgang Christl
* Permission is hereby granted, free of charge, to any person obtaining a copy of this
* software and associated documentation files (the Software), to deal in the Software
* without restriction, including without limitation the rights to use, copy, modify, merge,
* publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons
* to whom the Software is furnished to do so, subject to the following conditions:
*
* The above copyright notice and this permission notice shall be included in all copies or
* substantial portions of the Software.
*
* THE SOFTWARE IS PROVIDED AS IS, WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED,
* INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR
* PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE
* FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE,
* ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
* SOFTWARE.
*/
#ifndef __TS_H
#define __TS_H
#ifdef __cplusplus
extern "C" {
#endif
#include <stdint.h>
esp_err_t i2c_master_init(void);
#ifdef __cplusplus
}
#endif
#endif /* __TS_H */