ESP32-S3 RGB接口驱动ST7701S显示 PCLK超过12MHz会画面倾斜问题

William_Zhang
Posts: 1
Joined: Mon Mar 13, 2023 9:13 am

ESP32-S3 RGB接口驱动ST7701S显示 PCLK超过12MHz会画面倾斜问题

Postby William_Zhang » Tue Mar 14, 2023 5:40 am

编程框架: idf-5.0
LVGL: V7.11

[基本信息]
基于idf-5.0框架的rgb_panel示例修改, 手里的显示屏驱动芯片为ST7701S, 接口RGB565, 分辨率800*480

[问题]
使用的防撕裂方式为两个信号量"sem_vsync_end, sem_gui_ready", 与idf示例相同, 双buf缓冲.
问题是"LCD_PIXEL_CLOCK_HZ"这个参数目前限制在了12MHz, 超过这个值后显示的画面会发生器偏移(右移),
但是rgb_panel的示例可以18MHz刷新, 并且查阅网上其他类似项目也可以在18MHz跑, 画面会流畅很多
请问我的跑不到18MHz是为什么? 是代码的问题还是显示屏的问题?

[初始化代码]

Code: Select all

/*
 * SPDX-FileCopyrightText: 2022 Espressif Systems (Shanghai) CO LTD
 *
 * SPDX-License-Identifier: CC0-1.0
 */

#include <stdio.h>
#include "sdkconfig.h"
#include "freertos/FreeRTOS.h"
#include "freertos/task.h"
#include "freertos/semphr.h"
#include "esp_timer.h"
#include "esp_lcd_panel_ops.h"
#include "esp_lcd_panel_rgb.h"
#include "driver/gpio.h"
#include "esp_err.h"
#include "esp_log.h"
#include "bsp_board.h"
#include "lvgl.h"
#include "rgb_lcd.h"
#include "my_spi.h"
#include "gt911.h"
#include "tca9554.h"

static const char *TAG = "rgb_lcd";

////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
//////////////////// Please update the following configuration according to your LCD spec //////////////////////////////
////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////
#define LCD_PIXEL_CLOCK_HZ     (12 * 1000 * 1000)
#define LCD_BK_LIGHT_ON_LEVEL  1
#define LCD_BK_LIGHT_OFF_LEVEL !LCD_BK_LIGHT_ON_LEVEL
#define LCD_PIN_NUM_BK_LIGHT       (-1)
#define LCD_PIN_NUM_HSYNC          GPIO_LCD_HSYNC
#define LCD_PIN_NUM_VSYNC          GPIO_LCD_VSYNC
#define LCD_PIN_NUM_DE             GPIO_LCD_DE
#define LCD_PIN_NUM_PCLK           GPIO_LCD_PCLK
#define LCD_PIN_NUM_DATA0          GPIO_LCD_D00 // B0
#define LCD_PIN_NUM_DATA1          GPIO_LCD_D01 // B1
#define LCD_PIN_NUM_DATA2          GPIO_LCD_D02 // B2
#define LCD_PIN_NUM_DATA3          GPIO_LCD_D03 // B3
#define LCD_PIN_NUM_DATA4          GPIO_LCD_D04 // B4
#define LCD_PIN_NUM_DATA5          GPIO_LCD_D05 // G0
#define LCD_PIN_NUM_DATA6          GPIO_LCD_D06 // G1
#define LCD_PIN_NUM_DATA7          GPIO_LCD_D07 // G2
#define LCD_PIN_NUM_DATA8          GPIO_LCD_D08 // G3
#define LCD_PIN_NUM_DATA9          GPIO_LCD_D09 // G4
#define LCD_PIN_NUM_DATA10         GPIO_LCD_D10 // G5
#define LCD_PIN_NUM_DATA11         GPIO_LCD_D11 // R0
#define LCD_PIN_NUM_DATA12         GPIO_LCD_D12 // R1
#define LCD_PIN_NUM_DATA13         GPIO_LCD_D13 // R2
#define LCD_PIN_NUM_DATA14         GPIO_LCD_D14 // R3
#define LCD_PIN_NUM_DATA15         GPIO_LCD_D15 // R4
#define LCD_PIN_NUM_DISP_EN        GPIO_LCD_DISP_EN

// The pixel number in horizontal and vertical
#define LCD_H_RES              480
#define LCD_V_RES              800
#define LCD_SCR_SIZE           (LCD_H_RES * LCD_V_RES)

static const uint32_t tick_inc_period_ms = 2;

// we use two semaphores to sync the VSYNC event and the LVGL task, to avoid potential tearing effect
#if CONFIG_EXAMPLE_AVOID_TEAR_EFFECT_WITH_SEM
SemaphoreHandle_t sem_vsync_end;
SemaphoreHandle_t sem_gui_ready;
#endif

static bool example_on_vsync_event(esp_lcd_panel_handle_t panel, const esp_lcd_rgb_panel_event_data_t *event_data, void *user_data)
{
    BaseType_t high_task_awoken = pdFALSE;
#if CONFIG_EXAMPLE_AVOID_TEAR_EFFECT_WITH_SEM
    if (xSemaphoreTakeFromISR(sem_gui_ready, &high_task_awoken) == pdTRUE) {
        xSemaphoreGiveFromISR(sem_vsync_end, &high_task_awoken);
    }
#endif
    return high_task_awoken == pdTRUE;
}

static IRAM_ATTR void lvgl_flush_cb(lv_disp_drv_t *drv, const lv_area_t *area, lv_color_t *color_map)
{
    esp_lcd_panel_handle_t panel_handle = (esp_lcd_panel_handle_t) drv->user_data;

    int offsetx1 = area->x1;
    int offsetx2 = area->x2;
    int offsety1 = area->y1;
    int offsety2 = area->y2;

#if CONFIG_EXAMPLE_AVOID_TEAR_EFFECT_WITH_SEM
    xSemaphoreGive(sem_gui_ready);
    xSemaphoreTake(sem_vsync_end, portMAX_DELAY);
#endif

    // pass the draw buffer to the driver
    esp_lcd_panel_draw_bitmap(panel_handle, offsetx1, offsety1, offsetx2 + 1, offsety2 + 1, color_map);
    lv_disp_flush_ready(drv);
}

static IRAM_ATTR bool lvgl_read_cb(lv_indev_drv_t * indev_drv, lv_indev_data_t * data)
{
    static uint8_t tp_num = 0;
    static uint16_t x = 0, y = 0;

    gt911_get_touch(&tp_num, &x, &y);

    if (0 == tp_num) {
        data->state = LV_INDEV_STATE_REL;
    } else {
        /* not swap xy */
        data->point.x = x;
        data->point.y = y;
        data->state = LV_INDEV_STATE_PR;

//        ESP_LOGI(TAG, "Touch (%d): [X-%d,Y-%d]", tp_num, x, y);
    }

    return false;
}

static void lvgl_increase_tick(void *arg)
{
    /* Tell LVGL how many milliseconds has elapsed */
    lv_tick_inc(tick_inc_period_ms);
}

static void lv_handler_task(void *pvparam)
{
    static TickType_t tick;

    tick = xTaskGetTickCount();

    while (1) {
        // The task running lv_timer_handler should have lower priority than that running `lv_tick_inc`
        lv_task_handler();
        // raise the task priority of LVGL and/or reduce the handler period can improve the performance
        vTaskDelayUntil(&tick, pdMS_TO_TICKS(10));
    }
}

esp_err_t rgb_lcd_init(void)
{
    static lv_disp_buf_t disp_buf; // contains internal graphic buffer(s) called draw buffer(s)
    static lv_disp_drv_t disp_drv; // contains callback functions

#if CONFIG_EXAMPLE_AVOID_TEAR_EFFECT_WITH_SEM
    ESP_LOGI(TAG, "Create 2 semaphores");
    sem_vsync_end = xSemaphoreCreateBinary();
    assert(sem_vsync_end);
    sem_gui_ready = xSemaphoreCreateBinary();
    assert(sem_gui_ready);
#endif

    ESP_LOGI(TAG, "SPI config parameters to rgb lcd.");
    lcd_on_sequence();
    vTaskDelay(pdMS_TO_TICKS(100));

#if LCD_PIN_NUM_BK_LIGHT >= 0
    ESP_LOGI(TAG, "Turn off LCD backlight");
    gpio_config_t bk_gpio_config = {
            .mode = GPIO_MODE_OUTPUT,
            .pin_bit_mask = 1ULL << LCD_PIN_NUM_BK_LIGHT
    };

    ESP_ERROR_CHECK(gpio_config(&bk_gpio_config));
#endif

    /* Init LCD config */
    ESP_LOGI(TAG, "Install RGB LCD panel driver");
    esp_lcd_panel_handle_t panel_handle = NULL;
    esp_lcd_rgb_panel_config_t panel_config = {
            .data_width = 16, // RGB565 in parallel mode, thus 16bit in width
            .psram_trans_align = 64,
#if CONFIG_EXAMPLE_USE_BOUNCE_BUFFER
            .bounce_buffer_size_px = 10 * EXAMPLE_LCD_H_RES,
#endif
            .clk_src = LCD_CLK_SRC_PLL240M,
            .disp_gpio_num = LCD_PIN_NUM_DISP_EN,
            .pclk_gpio_num = LCD_PIN_NUM_PCLK,
            .vsync_gpio_num = LCD_PIN_NUM_VSYNC,
            .hsync_gpio_num = LCD_PIN_NUM_HSYNC,
            .de_gpio_num = LCD_PIN_NUM_DE,
            .data_gpio_nums = {
                    LCD_PIN_NUM_DATA0,
                    LCD_PIN_NUM_DATA1,
                    LCD_PIN_NUM_DATA2,
                    LCD_PIN_NUM_DATA3,
                    LCD_PIN_NUM_DATA4,
                    LCD_PIN_NUM_DATA5,
                    LCD_PIN_NUM_DATA6,
                    LCD_PIN_NUM_DATA7,
                    LCD_PIN_NUM_DATA8,
                    LCD_PIN_NUM_DATA9,
                    LCD_PIN_NUM_DATA10,
                    LCD_PIN_NUM_DATA11,
                    LCD_PIN_NUM_DATA12,
                    LCD_PIN_NUM_DATA13,
                    LCD_PIN_NUM_DATA14,
                    LCD_PIN_NUM_DATA15,
            },
            .timings = {
                    .pclk_hz = LCD_PIXEL_CLOCK_HZ,
                    .h_res = LCD_H_RES,
                    .v_res = LCD_V_RES,
                    // The following parameters should refer to LCD spec
                    .hsync_back_porch = 40,
                    .hsync_front_porch = 80,
                    .hsync_pulse_width = 2,
                    .vsync_back_porch = 30,
                    .vsync_front_porch = 30,
                    .vsync_pulse_width = 2,
                    .flags.pclk_active_neg = true,
            },
            .flags.fb_in_psram = true, // allocate frame buffer in PSRAM
#if CONFIG_EXAMPLE_DOUBLE_FB
            .flags.double_fb = true,   // allocate double frame buffer
#endif // CONFIG_EXAMPLE_DOUBLE_FB
    };
    ESP_ERROR_CHECK(esp_lcd_new_rgb_panel(&panel_config, &panel_handle));

    ESP_LOGI(TAG, "Register event vsync callbacks");
    esp_lcd_rgb_panel_event_callbacks_t cbs = {
        .on_vsync = example_on_vsync_event,
    };
    ESP_ERROR_CHECK(esp_lcd_rgb_panel_register_event_callbacks(panel_handle, &cbs, &disp_drv));

    ESP_LOGI(TAG, "Initialize RGB LCD panel");
    ESP_ERROR_CHECK(esp_lcd_panel_reset(panel_handle));
    ESP_ERROR_CHECK(esp_lcd_panel_init(panel_handle));

    ESP_LOGI(TAG, "Initialize LVGL library");
    lv_init();
    void *buf1 = NULL;
    void *buf2 = NULL;
    uint32_t flush_size = (LCD_SCR_SIZE / 4);
#if CONFIG_EXAMPLE_DOUBLE_FB
    ESP_LOGI(TAG, "Use frame buffers as LVGL draw buffers");
    ESP_ERROR_CHECK(esp_lcd_rgb_panel_get_frame_buffer(panel_handle, 2, &buf1, &buf2));
    // initialize LVGL draw buffers
    lv_disp_buf_init(&disp_buf, buf1, buf2, EXAMPLE_LCD_H_RES * EXAMPLE_LCD_V_RES);
#else
    ESP_LOGI(TAG, "Allocate separate LVGL draw buffers from PSRAM");
    buf1 = heap_caps_malloc(flush_size * sizeof(lv_color_t), MALLOC_CAP_SPIRAM);
    assert(buf1);
    buf2 = heap_caps_malloc(flush_size * sizeof(lv_color_t), MALLOC_CAP_SPIRAM);
    assert(buf2);
    if (NULL == buf1 || NULL == buf2) {
        ESP_LOGE(TAG, "No free mem for allocating lvgl display buffer.");
        return ESP_ERR_NO_MEM;
    }
    // initialize LVGL draw buffers
    lv_disp_buf_init(&disp_buf, buf1, buf2, flush_size);
//    lv_disp_buf_init(&disp_buf, buf1, NULL, flush_size);
#endif // CONFIG_EXAMPLE_DOUBLE_FB

    ESP_LOGI(TAG, "Register display driver to LVGL");
    lv_disp_drv_init(&disp_drv);
    disp_drv.hor_res = LCD_H_RES;
    disp_drv.ver_res = LCD_V_RES;
    disp_drv.flush_cb = lvgl_flush_cb;
    disp_drv.buffer = &disp_buf; //disp_buf for lvgl 7.11.0
    disp_drv.user_data = panel_handle;

#if CONFIG_EXAMPLE_DOUBLE_FB
//    disp_drv.full_refresh = true; // the full_refresh mode can maintain the synchronization between the two frame buffers
#endif
    lv_disp_drv_register(&disp_drv);

    /* Init touchpad driver */
    ESP_LOGI(TAG, "Initialize gt911 touch pad driver.");
    ESP_ERROR_CHECK(gt911_init());

    ESP_LOGI(TAG, "Register input devcie and callback.");
    lv_indev_drv_t indev_drv;
    lv_indev_drv_init(&indev_drv);
    indev_drv.type = LV_INDEV_TYPE_POINTER;
    indev_drv.read_cb = lvgl_read_cb;
    lv_indev_drv_register(&indev_drv);

    ESP_LOGI(TAG, "Install LVGL tick timer");
    // Tick interface for LVGL (using esp_timer to generate 2ms periodic event)
    const esp_timer_create_args_t lvgl_tick_timer_args = {
            .callback = &lvgl_increase_tick,
            .name = "lvgl_tick",
            .arg = (void*)&tick_inc_period_ms,
            .dispatch_method = ESP_TIMER_TASK,
            .skip_unhandled_events = true,
    };
    esp_timer_handle_t lvgl_tick_timer = NULL;
    ESP_ERROR_CHECK(esp_timer_create(&lvgl_tick_timer_args, &lvgl_tick_timer));
    ESP_ERROR_CHECK(esp_timer_start_periodic(lvgl_tick_timer, tick_inc_period_ms * 1000));

    ESP_LOGI(TAG, "Create a task for 'lv_handler_task'.");
    if (pdPASS != xTaskCreatePinnedToCore (
            (TaskFunction_t)      lv_handler_task,
            (const char * const)     "LVGL Handler Task",
            (const uint32_t)     4 * 1024,
            (void * const)       NULL,
            (UBaseType_t)           (configMAX_PRIORITIES - 2),
            (TaskHandle_t * const)  NULL,
            (BaseType_t) tskNO_AFFINITY ))
    {
        return ESP_ERR_NO_MEM;
    } //FreeRTOS 任务优先级数字越小, 优先级越低

#if LCD_PIN_NUM_BK_LIGHT >= 0
    ESP_LOGI(TAG, "Turn on LCD backlight");
    gpio_set_level(LCD_PIN_NUM_BK_LIGHT, LCD_BK_LIGHT_ON_LEVEL);
#endif

    ESP_LOGI(TAG, "Display part is initialize OK now!");

    return ESP_OK;
}

/**
 * @brief LCD power on sequence
 * */
void lcd_on_sequence(void)
{
    //Hardware Reset: 1 -> 0 -> 1
    io_level.lcd_rst = 1;
    tca9554_write_output_pins(io_level.val);
    vTaskDelay(pdMS_TO_TICKS(5));
    io_level.lcd_rst = 0;
    tca9554_write_output_pins(io_level.val);
    vTaskDelay(pdMS_TO_TICKS(5));
    io_level.lcd_rst = 1;
    tca9554_write_output_pins(io_level.val);
    vTaskDelay(pdMS_TO_TICKS(120));

    spi_lcd_on_handler();
}

/**
 * @brief LCD power off sequence
 * */
void lcd_off_sequence(void)
{
    spi_lcd_off_handler();
    vTaskDelay(pdMS_TO_TICKS(10));

    io_level.lcd_rst = 0;
    tca9554_write_output_pins(io_level.val);
    vTaskDelay(pdMS_TO_TICKS(100));
}


ESP_Junru
Posts: 48
Joined: Tue Jul 12, 2022 6:26 am

Re: ESP32-S3 RGB接口驱动ST7701S显示 PCLK超过12MHz会画面倾斜问题

Postby ESP_Junru » Tue Mar 21, 2023 9:04 am

请打上120M PSRAM 补丁,具体方法看:https://github.com/espressif/esp-dev-ki ... rd/factory

ESP_Junru
Posts: 48
Joined: Tue Jul 12, 2022 6:26 am

Re: ESP32-S3 RGB接口驱动ST7701S显示 PCLK超过12MHz会画面倾斜问题

Postby ESP_Junru » Tue Mar 21, 2023 9:09 am

原因:
该问题通常是因为 RGB 需要连续数据输出,当 Flash 或其他应用程序禁用或抢占 PSRAM 带宽时,数据传输将无法跟上 RGB 的时钟速度,从而导致永久的屏幕漂移。

解决方法:
请先尝试文档中的方法优化工程的配置并尽量降低 PCLK,如果需要使用 Wifi 和连续写 Flash 的操作,请使用 "PSRAM XIP" + "RGB Bounce buffer" 的方法,开启步骤如下:

确认 IDF 版本为较新(> 2022.12.12)的 release/v5.0 及以上,因为旧版本不支持 "PSRAM XIP" 的功能
确认 PSRAM 配置里面是否能开启 SPIRAM_FETCH_INSTRUCTIONS 和 SPIRAM_RODATA 这两项(如果 rodata 段数据过大,会导致 PSRAM 内存不够)
确认内存(SRAM)是否有余量,大概需要占用 10 * screen_width * 4 字节
需要将 Data cache line size 设置为 64 Byte(可设置 Data cache line size 为 32KB 以节省内存)
如以上均符合条件,那么就可以参考文档修改 RGB 驱动(RGB 驱动里加上一行代码 .bounce_buffer_size_px = 10 * 屏幕宽度)
如操作 Wifi 仍存在屏幕漂移问题,可以尝试关闭 PSRAM 里 CONFIG_SPIRAM_TRY_ALLOCATE_WIFI_LWIP 一项(会占用较大 SRAM)
开启后带来的影响:

CPU 使用率升高
可能会造成中断看门狗复位
会造成较大内存开销

sifat105277
Posts: 1
Joined: Sun Apr 30, 2023 7:29 pm

Re: ESP32-S3 RGB接口驱动ST7701S显示 PCLK超过12MHz会画面倾斜问题

Postby sifat105277 » Sun Apr 30, 2023 7:42 pm

I need help. I do not understand how to draw a single pixel at a specific coordinate. Can you help me to share a demo code? my display support RGB+SPI interface. display driver is st7701s

Who is online

Users browsing this forum: No registered users and 43 guests