diff --git a/CMakeLists.txt b/CMakeLists.txt index d6a67f8..3bfc8f7 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -31,6 +31,7 @@ list(APPEND SOURCES "${LV_PORT_PATH}/lv_port_display_espressif.c") list(APPEND SOURCES "lvgl_tft/ra8875.c") list(APPEND SOURCES "lvgl_tft/GC9A01.c") list(APPEND SOURCES "lvgl_tft/ili9163c.c") + list(APPEND SOURCES "lvgl_tft/pcd8544.c") if(CONFIG_LV_TFT_DISPLAY_PROTOCOL_SPI) list(APPEND SOURCES "lvgl_tft/disp_spi.c") diff --git a/README.md b/README.md index a664636..522c0e1 100644 --- a/README.md +++ b/README.md @@ -30,6 +30,7 @@ swap of RGB565 color on the LVGL configuration menuconfig (it's not handled auto | RA8875 | TFT | SPI | 16: RGB565 | Yes | | SH1107 | Monochrome | SPI | 1: 1byte per pixel | No | | SSD1306 | Monochrome | I2C | 1: 1byte per pixel | No | +| PCD8544 | Monochrome | SPI | 1: 1byte per pixel | No | | IL3820 | e-Paper | SPI | 1: 1byte per pixel | No | | UC8151D/ GoodDisplay GDEW0154M10 DES | e-Paper | SPI | 1: 1byte per pixel | No | | FitiPower JD79653A/ GoodDisplay GDEW0154M09 | e-Paper | SPI | 1: 1byte per pixel | No | diff --git a/lvgl_helpers.h b/lvgl_helpers.h index 439bd6b..5c5a17a 100644 --- a/lvgl_helpers.h +++ b/lvgl_helpers.h @@ -76,6 +76,8 @@ extern "C" { #define DISP_BUF_SIZE ((LV_VER_RES_MAX * LV_VER_RES_MAX) / 8) // 2888 bytes #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_ILI9163C #define DISP_BUF_SIZE (LV_HOR_RES_MAX * 40) +#elif defined (CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544) +#define DISP_BUF_SIZE (LV_HOR_RES_MAX * (LV_VER_RES_MAX / 8)) #else #error "No display controller selected" #endif diff --git a/lvgl_spi_conf.h b/lvgl_spi_conf.h index 240090d..cab94d7 100644 --- a/lvgl_spi_conf.h +++ b/lvgl_spi_conf.h @@ -64,16 +64,12 @@ extern "C" { #define ENABLE_TOUCH_INPUT CONFIG_LV_ENABLE_TOUCH -#if defined (CONFIG_LV_TFT_DISPLAY_SPI_HSPI) -#if defined (CONFIG_IDF_TARGET_ESP32C3) -#define TFT_SPI_HOST SPI2_HOST -#else -#define TFT_SPI_HOST HSPI_HOST -#endif -#elif defined (CONFIG_LV_TFT_DISPLAY_SPI_VSPI) -#define TFT_SPI_HOST VSPI_HOST -#elif defined (CONFIG_LV_TFT_DISPLAY_SPI_FSPI) -#define TFT_SPI_HOST FSPI_HOST +#if defined (CONFIG_LV_TFT_DISPLAY_SPI1_HOST) +#define TFT_SPI_HOST SPI1_HOST +#elif defined (CONFIG_LV_TFT_DISPLAY_SPI2_HOST) +#define TFT_SPI_HOST SPI2_HOST +#elif defined (CONFIG_LV_TFT_DISPLAY_SPI3_HOST) +#define TFT_SPI_HOST SPI3_HOST #endif #if defined (CONFIG_LV_TFT_DISPLAY_SPI_HALF_DUPLEX) @@ -166,6 +162,8 @@ extern "C" { #define SPI_TFT_CLOCK_SPEED_HZ (40 * 1000 * 1000) #elif defined(CONFIG_LV_TFT_DISPLAY_CONTROLLER_FT81X) #define SPI_TFT_CLOCK_SPEED_HZ (32*1000*1000) +#elif defined (CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544) +#define SPI_TFT_CLOCK_SPEED_HZ (4*1000*1000) #else #define SPI_TFT_CLOCK_SPEED_HZ (40*1000*1000) #endif diff --git a/lvgl_tft/Kconfig b/lvgl_tft/Kconfig index 140c173..b55f1f1 100644 --- a/lvgl_tft/Kconfig +++ b/lvgl_tft/Kconfig @@ -174,6 +174,10 @@ menu "LVGL TFT Display controller" help ILI9163C display controller. + config LV_TFT_DISPLAY_CONTROLLER_PCD8544 + bool + help + PCD8544 display controller (Nokia 3110/5110) # Display controller communication protocol # # This symbols define the communication protocol used by the @@ -340,6 +344,11 @@ menu "LVGL TFT Display controller" bool "ILI9163C" select LV_TFT_DISPLAY_CONTROLLER_ILI9163C select LV_TFT_DISPLAY_PROTOCOL_SPI + config LV_TFT_DISPLAY_USER_CONTROLLER_PCD8544 + bool "PCD8544" + select LV_TFT_DISPLAY_CONTROLLER_PCD8544 + select LV_TFT_DISPLAY_PROTOCOL_SPI + select LV_TFT_DISPLAY_MONOCHROME endchoice config CUSTOM_DISPLAY_BUFFER_SIZE @@ -460,18 +469,17 @@ menu "LVGL TFT Display controller" choice prompt "TFT SPI Bus." if LV_TFT_DISPLAY_PROTOCOL_SPI - default LV_TFT_DISPLAY_SPI_VSPI if LV_PREDEFINED_DISPLAY_TTGO && \ + default LV_TFT_DISPLAY_SPI3_HOST if LV_PREDEFINED_DISPLAY_TTGO && \ !IDF_TARGET_ESP32S2 - default LV_TFT_DISPLAY_SPI_FSPI if IDF_TARGET_ESP32S2 help Select the SPI Bus the TFT Display is attached to. - config LV_TFT_DISPLAY_SPI_HSPI - bool "HSPI" - config LV_TFT_DISPLAY_SPI_VSPI - bool "VSPI" if !IDF_TARGET_ESP32S2 - config LV_TFT_DISPLAY_SPI_FSPI - bool "FSPI" if IDF_TARGET_ESP32S2 + config LV_TFT_DISPLAY_SPI1_HOST + bool "SPI1_HOST" + config LV_TFT_DISPLAY_SPI2_HOST + bool "SPI2_HOST" + config LV_TFT_DISPLAY_SPI3_HOST + bool "SPI3_HOST" endchoice choice diff --git a/lvgl_tft/disp_driver.c b/lvgl_tft/disp_driver.c index ea1d493..be55086 100644 --- a/lvgl_tft/disp_driver.c +++ b/lvgl_tft/disp_driver.c @@ -43,6 +43,8 @@ void *disp_driver_init(lv_disp_drv_t *drv) uc8151d_init(); #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_ILI9163C ili9163c_init(); +#elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544 + pcd8544_init(); #endif return disp_backlight_init(); @@ -112,6 +114,8 @@ void disp_driver_flush(lv_disp_drv_t * drv, const lv_area_t * area, lv_color_t * uc8151d_lv_fb_flush(drv, area, color_map); #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_ILI9163C ili9163c_flush(drv, area, color_map); +#elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544 + pcd8544_flush(drv, area, color_map); #endif } @@ -127,6 +131,8 @@ void disp_driver_rounder(lv_disp_drv_t * disp_drv, lv_area_t * area) jd79653a_lv_rounder_cb(disp_drv, area); #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_UC8151D uc8151d_lv_rounder_cb(disp_drv, area); +#elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544 + pcd8544_rounder(disp_drv, area); #endif } @@ -143,5 +149,7 @@ void disp_driver_set_px(lv_disp_drv_t * disp_drv, uint8_t * buf, lv_coord_t buf_ jd79653a_lv_set_fb_cb(disp_drv, buf, buf_w, x, y, color, opa); #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_UC8151D uc8151d_lv_set_fb_cb(disp_drv, buf, buf_w, x, y, color, opa); +#elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544 + pcd8544_set_px_cb(disp_drv, buf, buf_w, x, y, color, opa); #endif } diff --git a/lvgl_tft/disp_driver.h b/lvgl_tft/disp_driver.h index a4a282b..7f43b46 100644 --- a/lvgl_tft/disp_driver.h +++ b/lvgl_tft/disp_driver.h @@ -52,6 +52,8 @@ extern "C" { #include "uc8151d.h" #elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_ILI9163C #include "ili9163c.h" +#elif defined CONFIG_LV_TFT_DISPLAY_CONTROLLER_PCD8544 +#include "pcd8544.h" #endif /********************* diff --git a/lvgl_tft/pcd8544.c b/lvgl_tft/pcd8544.c new file mode 100644 index 0000000..49d067e --- /dev/null +++ b/lvgl_tft/pcd8544.c @@ -0,0 +1,148 @@ +/** + * @file pcd8544.c + * + * Roughly based on: + * https://github.com/adafruit/Adafruit-PCD8544-Nokia-5110-LCD-library + * https://github.com/olikraus/u8g2 + */ + +#include "disp_spi.h" +#include "driver/gpio.h" + +#include +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" + +#include "pcd8544.h" + +#define TAG "lv_pcd8544" + +/********************** + * MACROS + **********************/ + +#define BIT_SET(a,b) ((a) |= (1U<<(b))) +#define BIT_CLEAR(a,b) ((a) &= ~(1U<<(b))) + +/********************** + * STATIC FUNCTIONS + **********************/ + +static void pcd8544_send_cmd(uint8_t cmd) +{ + disp_wait_for_pending_transactions(); + gpio_set_level(PCD8544_DC, 0); /*Command mode*/ + disp_spi_send_data(&cmd, 1); +} + +static void pcd8544_send_data(void * data, uint16_t length) +{ + disp_wait_for_pending_transactions(); + gpio_set_level(PCD8544_DC, 1); /*Data mode*/ + disp_spi_send_data(data, length); +} + +static void pcd8544_send_colors(void * data, uint16_t length) +{ + gpio_set_level(PCD8544_DC, 1); /*Data mode*/ + disp_spi_send_colors(data, length); +} + +/********************** + * GLOBAL FUNCTIONS + **********************/ + +void pcd8544_init(void){ + + // TODO: orientation + + // Initialize non-SPI GPIOs + gpio_pad_select_gpio(PCD8544_DC); + gpio_set_direction(PCD8544_DC, GPIO_MODE_OUTPUT); + gpio_pad_select_gpio(PCD8544_RST); + gpio_set_direction(PCD8544_RST, GPIO_MODE_OUTPUT); + + // Reset the display + gpio_set_level(PCD8544_RST, 0); + vTaskDelay(100 / portTICK_RATE_MS); + gpio_set_level(PCD8544_RST, 1); + vTaskDelay(100 / portTICK_RATE_MS); + + pcd8544_send_cmd(0x21); /* activate chip (PD=0), horizontal increment (V=0), enter extended command set (H=1) */ + pcd8544_send_cmd(0x06); /* temp. control: b10 = 2 */ + pcd8544_send_cmd(0x13); /* bias system 1:48 */ + pcd8544_send_cmd(0xc0); /* medium Vop = Contrast 0x40 = 64 */ + + pcd8544_send_cmd(0x20); /* activate chip (PD=0), horizontal increment (V=0), enter extended command set (H=0) */ + pcd8544_send_cmd(0x0c); /* display mode normal */ +} + +void pcd8544_set_contrast (uint8_t contrast){ + if (contrast > 0x7f){ + contrast = 0x7f; + } + pcd8544_send_cmd(0x21); /* activate chip (PD=0), horizontal increment (V=0), enter extended command set (H=1) */ + pcd8544_send_cmd(0x80 | contrast); /* medium Vop = Contrast */ +} + +void pcd8544_rounder(lv_disp_drv_t * disp_drv, lv_area_t *area){ + uint8_t hor_max = disp_drv->hor_res; + uint8_t ver_max = disp_drv->ver_res; + + area->x1 = 0; + area->y1 = 0; + area->x2 = hor_max - 1; + area->y2 = ver_max - 1; +} + +void pcd8544_set_px_cb(lv_disp_drv_t * disp_drv, uint8_t * buf, lv_coord_t buf_w, lv_coord_t x, lv_coord_t y, + lv_color_t color, lv_opa_t opa){ + + uint8_t set = (color.full == 0) && (LV_OPA_TRANSP != opa); + + uint16_t byte_index = x + (( y>>3 ) * buf_w); + uint8_t bit_index = y & 0x7; + + if (set) { + BIT_SET(buf[byte_index], bit_index); + } else { + BIT_CLEAR(buf[byte_index], bit_index); + } +} + +void pcd8544_flush(lv_disp_drv_t * disp_drv, const lv_area_t * area, lv_color_t * color_map){ + + pcd8544_send_cmd(0x20); /* activate chip (PD=0), horizontal increment (V=0), enter extended command set (H=0) */ + + uint8_t * buf = (uint8_t *) color_map; + + // Check if the whole frame buffer can be sent in a single SPI transaction + + if ((area->x1 == 0) && (area->y1 == 0) && (area->x2 == (disp_drv->hor_res - 1)) && (area->y2 == (disp_drv->ver_res - 1))){ + + // send complete frame buffer at once. + // NOTE: disp_spi_send_colors triggers lv_disp_flush_ready + + pcd8544_send_cmd(0x40); /* set Y address */ + pcd8544_send_cmd(0x80); /* set X address */ + pcd8544_send_colors(buf, disp_drv->hor_res * disp_drv->ver_res / 8); + + } else { + + // send horizontal tiles + + uint16_t bank_start = area->y1 / 8; + uint16_t bank_end = area->y2 / 8; + + uint16_t bank; + uint16_t cols_to_update = area->x2 - area->x1 + 1; + for (bank = bank_start ; bank <= bank_end ; bank++ ){ + pcd8544_send_cmd(0x40 | bank ); /* set Y address */ + pcd8544_send_cmd(0x80 | area->x1 ); /* set X address */ + uint16_t offset = bank * disp_drv->hor_res + area->x1; + pcd8544_send_data(&buf[offset], cols_to_update); + } + + lv_disp_flush_ready(disp_drv); + } +} diff --git a/lvgl_tft/pcd8544.h b/lvgl_tft/pcd8544.h new file mode 100644 index 0000000..24fcc71 --- /dev/null +++ b/lvgl_tft/pcd8544.h @@ -0,0 +1,57 @@ + +/** + * @file pcd8544.h + * + */ + +#ifndef PCD8544_H +#define PCD8544_H + +#ifdef __cplusplus +extern "C" { +#endif + +/********************* + * INCLUDES + *********************/ +#include + +#ifdef LV_LVGL_H_INCLUDE_SIMPLE +#include "lvgl.h" +#else +#include "lvgl/lvgl.h" +#endif + +/********************* + * DEFINES + *********************/ + +#define PCD8544_DC CONFIG_LV_DISP_PIN_DC +#define PCD8544_RST CONFIG_LV_DISP_PIN_RST +#define PCD8544_BCKL CONFIG_LV_DISP_PIN_BCKL + +/********************** + * TYPEDEFS + **********************/ + +/********************** + * GLOBAL PROTOTYPES + **********************/ + +void pcd8544_init(void); +void pcd8544_flush(lv_disp_drv_t * drv, const lv_area_t * area, lv_color_t * color_map); +void pcd8544_rounder(lv_disp_drv_t * disp_drv, lv_area_t *area); +void pcd8544_set_px_cb(lv_disp_drv_t * disp_drv, uint8_t * buf, lv_coord_t buf_w, lv_coord_t x, lv_coord_t y, + lv_color_t color, lv_opa_t opa); +void pcd8544_set_contrast(uint8_t contrast); + +/********************** + * MACROS + **********************/ + + +#ifdef __cplusplus +} /* extern "C" */ +#endif + +#endif /*PCD8544_H*/ diff --git a/lvgl_tft/st7789.c b/lvgl_tft/st7789.c index ba2889a..9794b01 100644 --- a/lvgl_tft/st7789.c +++ b/lvgl_tft/st7789.c @@ -28,12 +28,11 @@ typedef struct { * STATIC PROTOTYPES **********************/ static void st7789_set_orientation(lv_disp_drv_t *drv, uint8_t orientation); - static void st7789_send_cmd(lv_disp_drv_t * drv, uint8_t cmd); static void st7789_send_data(lv_disp_drv_t * drv, void *data, uint16_t length); static void st7789_send_color(lv_disp_drv_t * drv, void *data, uint16_t length); - static void st7789_reset(lv_disp_drv_t * drv); + /********************** * STATIC VARIABLES **********************/ diff --git a/lvgl_touch/ft6x36.c b/lvgl_touch/ft6x36.c index b968d43..4bc5e1d 100644 --- a/lvgl_touch/ft6x36.c +++ b/lvgl_touch/ft6x36.c @@ -1,162 +1,162 @@ -/* -* 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. -*/ - -#ifdef LV_LVGL_H_INCLUDE_SIMPLE -#include -#else -#include -#endif - -#include "ft6x36.h" -#include "lvgl_i2c/i2c_manager.h" - -#define TAG "FT6X36" -#define FT6X36_TOUCH_QUEUE_ELEMENTS 1 - -static ft6x36_status_t ft6x36_status; -/* Set during initialization */ -static uint8_t current_dev_addr; -/* -1 coordinates to designate it was never touched */ -static ft6x36_touch_t touch_inputs = { -1, -1, LV_INDEV_STATE_REL }; - -#if CONFIG_LV_FT6X36_COORDINATES_QUEUE -QueueHandle_t ft6x36_touch_queue_handle; -#endif - -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); -} - -/** - * @brief Read the FT6x36 gesture ID. Initialize first! - * @param dev_addr: I2C FT6x36 Slave address. - * @retval The gesture ID or 0x00 in case of failure - */ -uint8_t ft6x36_get_gesture_id() { - if (!ft6x36_status.inited) { - LV_LOG_ERROR("Init first!"); - return 0x00; - } - uint8_t data_buf; - esp_err_t ret; - if ((ret = ft6x06_i2c_read8(current_dev_addr, FT6X36_GEST_ID_REG, &data_buf) != ESP_OK)) - LV_LOG_ERROR("Error reading from device: %s", esp_err_to_name(ret)); - return data_buf; -} - -/** - * @brief Initialize for FT6x36 communication via I2C - * @param dev_addr: Device address on communication Bus (I2C slave address of FT6X36). - * @retval None - */ -void ft6x06_init(uint16_t dev_addr) { - - ft6x36_status.inited = true; - current_dev_addr = dev_addr; - uint8_t data_buf; - esp_err_t ret; - LV_LOG_INFO("Found touch panel controller"); - if ((ret = ft6x06_i2c_read8(dev_addr, FT6X36_PANEL_ID_REG, &data_buf) != ESP_OK)) - LV_LOG_ERROR("Error reading from device: %s", - esp_err_to_name(ret)); // Only show error the first time - LV_LOG_INFO("\tDevice ID: 0x%02x", data_buf); - - ft6x06_i2c_read8(dev_addr, FT6X36_CHIPSELECT_REG, &data_buf); - LV_LOG_INFO("\tChip ID: 0x%02x", data_buf); - - ft6x06_i2c_read8(dev_addr, FT6X36_DEV_MODE_REG, &data_buf); - LV_LOG_INFO("\tDevice mode: 0x%02x", data_buf); - - ft6x06_i2c_read8(dev_addr, FT6X36_FIRMWARE_ID_REG, &data_buf); - LV_LOG_INFO("\tFirmware ID: 0x%02x", data_buf); - - ft6x06_i2c_read8(dev_addr, FT6X36_RELEASECODE_REG, &data_buf); - LV_LOG_INFO("\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 ) - { - LV_LOG_ERROR("\tError creating touch input FreeRTOS queue" ); - return; - } - xQueueSend( ft6x36_touch_queue_handle, &touch_inputs, 0 ); -#endif -} - -/** - * @brief Get the touch screen X and Y positions values. Ignores multi touch - * @param drv: - * @param data: Store data here - * @retval Always false - */ -bool ft6x36_read(lv_indev_drv_t *drv, lv_indev_data_t *data) { - if (!ft6x36_status.inited) { - LV_LOG_ERROR("Init first!"); - return 0x00; - } - uint8_t data_buf[5]; // 1 byte status, 2 bytes X, 2 bytes Y - - 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) { - LV_LOG_ERROR("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; - } - - 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 = 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 - touch_inputs.last_x = LV_HOR_RES - touch_inputs.last_x; -#endif -#if CONFIG_LV_FT6X36_INVERT_Y - touch_inputs.last_y = LV_VER_RES - touch_inputs.last_y; -#endif - data->point.x = touch_inputs.last_x; - data->point.y = touch_inputs.last_y; - data->state = touch_inputs.current_state; - LV_LOG_INFO("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; -} +/* +* 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. +*/ + +#ifdef LV_LVGL_H_INCLUDE_SIMPLE +#include +#else +#include +#endif + +#include "ft6x36.h" +#include "lvgl_i2c/i2c_manager.h" + +#define TAG "FT6X36" +#define FT6X36_TOUCH_QUEUE_ELEMENTS 1 + +static ft6x36_status_t ft6x36_status; +/* Set during initialization */ +static uint8_t current_dev_addr; +/* -1 coordinates to designate it was never touched */ +static ft6x36_touch_t touch_inputs = { -1, -1, LV_INDEV_STATE_REL }; + +#if CONFIG_LV_FT6X36_COORDINATES_QUEUE +QueueHandle_t ft6x36_touch_queue_handle; +#endif + +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); +} + +/** + * @brief Read the FT6x36 gesture ID. Initialize first! + * @param dev_addr: I2C FT6x36 Slave address. + * @retval The gesture ID or 0x00 in case of failure + */ +uint8_t ft6x36_get_gesture_id() { + if (!ft6x36_status.inited) { + LV_LOG_ERROR("Init first!"); + return 0x00; + } + uint8_t data_buf; + esp_err_t ret; + if ((ret = ft6x06_i2c_read8(current_dev_addr, FT6X36_GEST_ID_REG, &data_buf) != ESP_OK)) + LV_LOG_ERROR("Error reading from device: %s", esp_err_to_name(ret)); + return data_buf; +} + +/** + * @brief Initialize for FT6x36 communication via I2C + * @param dev_addr: Device address on communication Bus (I2C slave address of FT6X36). + * @retval None + */ +void ft6x06_init(uint16_t dev_addr) { + + ft6x36_status.inited = true; + current_dev_addr = dev_addr; + uint8_t data_buf; + esp_err_t ret; + LV_LOG_INFO("Found touch panel controller"); + if ((ret = ft6x06_i2c_read8(dev_addr, FT6X36_PANEL_ID_REG, &data_buf) != ESP_OK)) + LV_LOG_ERROR("Error reading from device: %s", + esp_err_to_name(ret)); // Only show error the first time + LV_LOG_INFO("\tDevice ID: 0x%02x", data_buf); + + ft6x06_i2c_read8(dev_addr, FT6X36_CHIPSELECT_REG, &data_buf); + LV_LOG_INFO("\tChip ID: 0x%02x", data_buf); + + ft6x06_i2c_read8(dev_addr, FT6X36_DEV_MODE_REG, &data_buf); + LV_LOG_INFO("\tDevice mode: 0x%02x", data_buf); + + ft6x06_i2c_read8(dev_addr, FT6X36_FIRMWARE_ID_REG, &data_buf); + LV_LOG_INFO("\tFirmware ID: 0x%02x", data_buf); + + ft6x06_i2c_read8(dev_addr, FT6X36_RELEASECODE_REG, &data_buf); + LV_LOG_INFO("\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 ) + { + LV_LOG_ERROR("\tError creating touch input FreeRTOS queue" ); + return; + } + xQueueSend( ft6x36_touch_queue_handle, &touch_inputs, 0 ); +#endif +} + +/** + * @brief Get the touch screen X and Y positions values. Ignores multi touch + * @param drv: + * @param data: Store data here + * @retval Always false + */ +bool ft6x36_read(lv_indev_drv_t *drv, lv_indev_data_t *data) { + if (!ft6x36_status.inited) { + LV_LOG_ERROR("Init first!"); + return 0x00; + } + uint8_t data_buf[5]; // 1 byte status, 2 bytes X, 2 bytes Y + + 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) { + LV_LOG_ERROR("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; + } + + 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 = 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 + touch_inputs.last_x = LV_HOR_RES - touch_inputs.last_x; +#endif +#if CONFIG_LV_FT6X36_INVERT_Y + touch_inputs.last_y = LV_VER_RES - touch_inputs.last_y; +#endif + data->point.x = touch_inputs.last_x; + data->point.y = touch_inputs.last_y; + data->state = touch_inputs.current_state; + LV_LOG_INFO("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; +}