From ac11c689f7f2214876806dc4a0ecb572eb031b6f Mon Sep 17 00:00:00 2001
From: BigTreeTech <38851044+bigtreetech@users.noreply.github.com>
Date: Sun, 9 May 2021 10:02:16 +0800
Subject: [PATCH] Capacitive Touch Screen (GT911) for SKR SE BX (#21843)

Co-authored-by: Msq001 <alansayyeah@gmail.com>
Co-authored-by: Scott Lahteine <github@thinkyhead.com>
---
 Marlin/Configuration.h                       |   2 +-
 Marlin/src/HAL/LPC1768/tft/xpt2046.cpp       |   2 +-
 Marlin/src/HAL/STM32/tft/gt911.cpp           | 202 +++++++++++++++++++
 Marlin/src/HAL/STM32/tft/gt911.h             | 120 +++++++++++
 Marlin/src/HAL/STM32/tft/xpt2046.cpp         |   2 +-
 Marlin/src/HAL/STM32F1/tft/xpt2046.cpp       |   2 +-
 Marlin/src/inc/Conditionals_LCD.h            |  27 ++-
 Marlin/src/inc/Conditionals_adv.h            |   4 +-
 Marlin/src/inc/SanityCheck.h                 |  18 +-
 Marlin/src/lcd/tft/touch.cpp                 |  25 ++-
 Marlin/src/lcd/tft/touch.h                   |  13 +-
 Marlin/src/lcd/tft/ui_1024x600.cpp           |  43 ++--
 Marlin/src/lcd/touch/touch_buttons.cpp       |  11 +-
 Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h |  16 +-
 14 files changed, 425 insertions(+), 62 deletions(-)
 create mode 100644 Marlin/src/HAL/STM32/tft/gt911.cpp
 create mode 100644 Marlin/src/HAL/STM32/tft/gt911.h

diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h
index e1f9a4be707..755b58fe152 100644
--- a/Marlin/Configuration.h
+++ b/Marlin/Configuration.h
@@ -2571,7 +2571,7 @@
 //#define DWIN_CREALITY_LCD
 
 //
-// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
+// Touch Screen Settings
 //
 //#define TOUCH_SCREEN
 #if ENABLED(TOUCH_SCREEN)
diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
index cf14405484f..9c1e158981d 100644
--- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
@@ -22,7 +22,7 @@
 
 #include "../../../inc/MarlinConfig.h"
 
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
 
 #include "xpt2046.h"
 #include <SPI.h>
diff --git a/Marlin/src/HAL/STM32/tft/gt911.cpp b/Marlin/src/HAL/STM32/tft/gt911.cpp
new file mode 100644
index 00000000000..f99fa46e194
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/gt911.cpp
@@ -0,0 +1,202 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
+
+#include "../../../inc/MarlinConfig.h"
+
+#if ENABLED(TFT_TOUCH_DEVICE_GT911)
+
+#include "gt911.h"
+#include "pinconfig.h"
+
+SW_IIC::SW_IIC(uint16_t sda, uint16_t scl) {
+  scl_pin = scl;
+  sda_pin = sda;
+}
+
+// Software I2C hardware io init
+void SW_IIC::init() {
+  OUT_WRITE(scl_pin, HIGH);
+  OUT_WRITE(sda_pin, HIGH);
+}
+
+// Software I2C start signal
+void SW_IIC::start() {
+  write_sda(HIGH); // SDA = 1
+  write_scl(HIGH); // SCL = 1
+  iic_delay(2);
+  write_sda(LOW); // SDA = 0
+  iic_delay(1);
+  write_scl(LOW); // SCL = 0  // keep SCL low, avoid false stop caused by level jump caused by SDA switching IN/OUT
+}
+
+// Software I2C stop signal
+void SW_IIC::stop() {
+  write_scl(LOW); // SCL = 0
+  iic_delay(2);
+  write_sda(LOW); // SDA = 0
+  iic_delay(2);
+  write_scl(HIGH); // SCL = 1
+  iic_delay(2);
+  write_sda(HIGH); // SDA = 1
+}
+
+// Software I2C sends ACK or NACK signal
+void SW_IIC::send_ack(bool ack) {
+  write_sda(ack ? LOW : HIGH); // SDA = !ack
+  iic_delay(2);
+  write_scl(HIGH); // SCL = 1
+  iic_delay(2);
+  write_scl(LOW); // SCL = 0
+}
+
+// Software I2C read ACK or NACK signal
+bool SW_IIC::read_ack() {
+  bool error = 0;
+  set_sda_in();
+
+  iic_delay(2);
+
+  write_scl(HIGH); // SCL = 1
+  error = read_sda();
+
+  iic_delay(2);
+
+  write_scl(LOW);  // SCL = 0
+
+  set_sda_out();
+  return error;
+}
+
+void SW_IIC::send_byte(uint8_t txd) {
+  LOOP_L_N(i, 8) {
+    write_sda(txd & 0x80); // write data bit
+    txd <<= 1;
+    iic_delay(1);
+    write_scl(HIGH); // SCL = 1
+    iic_delay(2);
+    write_scl(LOW); // SCL = 0
+    iic_delay(1);
+  }
+
+  read_ack();  // wait ack
+}
+
+uint8_t SW_IIC::read_byte(bool ack) {
+  uint8_t data = 0;
+
+  set_sda_in();
+  LOOP_L_N(i, 8) {
+    write_scl(HIGH); // SCL = 1
+    iic_delay(1);
+    data <<= 1;
+    if (read_sda()) data++;
+    write_scl(LOW); // SCL = 0
+    iic_delay(2);
+  }
+  set_sda_out();
+
+  send_ack(ack);
+
+  return data;
+}
+
+GT911_REG_MAP GT911::reg;
+SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN);
+
+void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) {
+  sw_iic.start();
+  sw_iic.send_byte(gt911_slave_address);  // Set IIC Slave address
+  LOOP_L_N(i, reg_len) {  // Set reg address
+    uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
+    sw_iic.send_byte(r);
+  }
+
+  LOOP_L_N(i, w_len) {  // Write data to reg
+    sw_iic.send_byte(w_data[i]);
+  }
+  sw_iic.stop();
+}
+
+void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) {
+  sw_iic.start();
+  sw_iic.send_byte(gt911_slave_address);  // Set IIC Slave address
+  LOOP_L_N(i, reg_len) {  // Set reg address
+    uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
+    sw_iic.send_byte(r);
+  }
+
+  sw_iic.start();
+  sw_iic.send_byte(gt911_slave_address + 1);  // Set read mode
+
+  LOOP_L_N(i, r_len) {
+    r_data[i] = sw_iic.read_byte(1);  // Read data from reg
+  }
+  sw_iic.stop();
+}
+
+void GT911::Init() {
+  OUT_WRITE(GT911_RST_PIN, LOW);
+  OUT_WRITE(GT911_INT_PIN, LOW);
+  delay(20);
+  WRITE(GT911_RST_PIN, HIGH);
+  SET_INPUT(GT911_INT_PIN);
+
+  sw_iic.init();
+
+  uint8_t clear_reg = 0x0000;
+  write_reg(0x814E, 2, &clear_reg, 2); // Reset to 0 for start
+}
+
+bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) {
+  read_reg(0x814E, 2, &reg.REG.status, 1);
+
+  if (reg.REG.status & 0x80) {
+    uint8_t clear_reg = 0x00;
+    write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start
+    read_reg(0x8150, 2, reg.map + 2, 8 * (reg.REG.status & 0x0F));
+
+    // First touch point
+    *x = ((reg.REG.point[0].xh & 0x0F) << 8) | reg.REG.point[0].xl;
+    *y = ((reg.REG.point[0].yh & 0x0F) << 8) | reg.REG.point[0].yl;
+    return true;
+  }
+  return false;
+}
+
+bool GT911::getPoint(int16_t *x, int16_t *y) {
+  static bool touched = 0;
+  static int16_t read_x = 0, read_y = 0;
+  static millis_t next_time = 0;
+
+  if (ELAPSED(millis(), next_time)) {
+    touched = getFirstTouchPoint(&read_x, &read_y);
+    next_time = millis() + 20;
+  }
+
+  *x = read_x;
+  *y = read_y;
+  return touched;
+}
+
+#endif // TFT_TOUCH_DEVICE_GT911
+#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
diff --git a/Marlin/src/HAL/STM32/tft/gt911.h b/Marlin/src/HAL/STM32/tft/gt911.h
new file mode 100644
index 00000000000..752a554d98e
--- /dev/null
+++ b/Marlin/src/HAL/STM32/tft/gt911.h
@@ -0,0 +1,120 @@
+/**
+ * Marlin 3D Printer Firmware
+ * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
+ *
+ * Based on Sprinter and grbl.
+ * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
+ *
+ * This program is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * This program is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with this program.  If not, see <https://www.gnu.org/licenses/>.
+ *
+ */
+#pragma once
+
+#include "../../../inc/MarlinConfig.h"
+
+#define GT911_SLAVE_ADDRESS   0xBA
+
+#if !PIN_EXISTS(GT911_RST)
+  #error "GT911_RST_PIN is not defined."
+#elif !PIN_EXISTS(GT911_INT)
+  #error "GT911_INT_PIN is not defined."
+#elif !PIN_EXISTS(GT911_SW_I2C_SCL)
+  #error "GT911_SW_I2C_SCL_PIN is not defined."
+#elif !PIN_EXISTS(GT911_SW_I2C_SDA)
+  #error "GT911_SW_I2C_SDA_PIN is not defined."
+#endif
+
+class SW_IIC {
+  private:
+    uint16_t scl_pin;
+    uint16_t sda_pin;
+    void write_scl(bool level)
+    {
+      WRITE(scl_pin, level);
+    }
+    void write_sda(bool level)
+    {
+      WRITE(sda_pin, level);
+    }
+    bool read_sda()
+    {
+      return READ(sda_pin);
+    }
+    void set_sda_out()
+    {
+      SET_OUTPUT(sda_pin);
+    }
+    void set_sda_in()
+    {
+      SET_INPUT_PULLUP(sda_pin);
+    }
+    static void iic_delay(uint8_t t)
+    {
+      delayMicroseconds(t);
+    }
+
+  public:
+    SW_IIC(uint16_t sda, uint16_t scl);
+    // setSCL/SDA have to be called before begin()
+    void setSCL(uint16_t scl)
+    {
+      scl_pin = scl;
+    };
+    void setSDA(uint16_t sda)
+    {
+      sda_pin = sda;
+    };
+    void init();                // Initialize the IO port of IIC
+    void start();               // Send IIC start signal
+    void stop();                // Send IIC stop signal
+    void send_byte(uint8_t txd); // IIC sends a byte
+    uint8_t read_byte(bool ack); // IIC reads a byte
+    void send_ack(bool ack);            // IIC sends ACK or NACK signal
+    bool read_ack();
+};
+
+typedef struct __attribute__((__packed__)) {
+  uint8_t xl;
+  uint8_t xh;
+  uint8_t yl;
+  uint8_t yh;
+  uint8_t sizel;
+  uint8_t sizeh;
+  uint8_t reserved;
+  uint8_t track_id;
+} GT911_POINT;
+
+typedef union __attribute__((__packed__)) {
+  uint8_t map[42];
+  struct {
+    uint8_t status;    // 0x814E
+    uint8_t track_id;  // 0x814F
+
+    GT911_POINT point[5]; // [0]:0x8150 - 0x8157 / [1]:0x8158 - 0x815F / [2]:0x8160 - 0x8167 / [3]:0x8168 - 0x816F / [4]:0x8170 - 0x8177
+ } REG;
+} GT911_REG_MAP;
+
+class GT911 {
+  private:
+    static const uint8_t gt911_slave_address = GT911_SLAVE_ADDRESS;
+    static GT911_REG_MAP reg;
+    static SW_IIC sw_iic;
+    static void write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len);
+    static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len);
+
+  public:
+    static void Init();
+    static bool getFirstTouchPoint(int16_t *x, int16_t *y);
+    static bool getPoint(int16_t *x, int16_t *y);
+};
diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
index 04294e669c5..dffeb6aaf72 100644
--- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp
@@ -23,7 +23,7 @@
 
 #include "../../../inc/MarlinConfig.h"
 
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
 
 #include "xpt2046.h"
 #include "pinconfig.h"
diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
index 98371c5ffb8..ac9ad072aa0 100644
--- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
+++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
@@ -22,7 +22,7 @@
 
 #include "../../../inc/MarlinConfig.h"
 
-#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
 
 #include "xpt2046.h"
 #include <SPI.h>
diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h
index afec2c2b44b..ed86c1bf659 100644
--- a/Marlin/src/inc/Conditionals_LCD.h
+++ b/Marlin/src/inc/Conditionals_LCD.h
@@ -1131,6 +1131,9 @@
   #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY)
   #define TFT_RES_1024x600
   #define TFT_INTERFACE_LTDC
+  #if ENABLED(TOUCH_SCREEN)
+    #define TFT_TOUCH_DEVICE_GT911
+  #endif
 #elif ENABLED(TFT_GENERIC)
   #define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y)
   #if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320)
@@ -1219,16 +1222,30 @@
   #define HAS_UI_1024x600 1
 #endif
 #if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272)
-  #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen
+  #define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7)   // Fewer lines with touch buttons onscreen
 #elif HAS_UI_1024x600
   #define LCD_HEIGHT TERN(TOUCH_SCREEN, 12, 13) // Fewer lines with touch buttons onscreen
 #endif
 
 // This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046'
-#if ENABLED(TOUCH_SCREEN) && !HAS_GRAPHICAL_TFT
-  #undef TOUCH_SCREEN
-  #if ENABLED(TFT_CLASSIC_UI)
-    #define HAS_TOUCH_BUTTONS 1
+#if ENABLED(TOUCH_SCREEN)
+  #if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046)
+    #define TFT_TOUCH_DEVICE_XPT2046          // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
+  #endif
+  #if ENABLED(TFT_TOUCH_DEVICE_GT911)         // GT911 Capacitive touch screen such as BIQU_BX_TFT70
+    #undef TOUCH_SCREEN_CALIBRATION
+    #undef TOUCH_CALIBRATION_AUTO_SAVE
+  #endif
+  #if !HAS_GRAPHICAL_TFT
+    #undef TOUCH_SCREEN
+    #if ENABLED(TFT_CLASSIC_UI)
+      #define HAS_TOUCH_BUTTONS 1
+      #if ENABLED(TFT_TOUCH_DEVICE_GT911)
+        #define HAS_CAP_TOUCH_BUTTONS 1
+      #else
+        #define HAS_RES_TOUCH_BUTTONS 1
+      #endif
+    #endif
   #endif
 #endif
 
diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h
index 19ab98fed3e..44ea34a490d 100644
--- a/Marlin/src/inc/Conditionals_adv.h
+++ b/Marlin/src/inc/Conditionals_adv.h
@@ -371,13 +371,13 @@
 #endif
 
 // Full Touch Screen needs 'tft/xpt2046'
-#if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI)
+#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI)
   #define HAS_TFT_XPT2046 1
 #endif
 
 // Touch Screen or "Touch Buttons" need XPT2046 pins
 // but they use different components
-#if EITHER(HAS_TFT_XPT2046, HAS_TOUCH_BUTTONS)
+#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
   #define NEED_TOUCH_PINS 1
 #endif
 
diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h
index 2cc90e0e8bc..bbd646a30d9 100644
--- a/Marlin/src/inc/SanityCheck.h
+++ b/Marlin/src/inc/SanityCheck.h
@@ -3180,21 +3180,11 @@ static_assert(   _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
 #endif
 
 /**
- * Touch Buttons
+ * Touch Screen Calibration
  */
-#if ENABLED(TOUCH_SCREEN) && DISABLED(TOUCH_SCREEN_CALIBRATION)
-  #ifndef TOUCH_CALIBRATION_X
-    #error "TOUCH_CALIBRATION_X must be defined with TOUCH_SCREEN."
-  #endif
-  #ifndef TOUCH_CALIBRATION_Y
-    #error "TOUCH_CALIBRATION_Y must be defined with TOUCH_SCREEN."
-  #endif
-  #ifndef TOUCH_OFFSET_X
-    #error "TOUCH_OFFSET_X must be defined with TOUCH_SCREEN."
-  #endif
-  #ifndef TOUCH_OFFSET_Y
-    #error "TOUCH_OFFSET_Y must be defined with TOUCH_SCREEN."
-  #endif
+#if ENABLED(TFT_TOUCH_DEVICE_XPT2046) && DISABLED(TOUCH_SCREEN_CALIBRATION) \
+    && (!defined(TOUCH_CALIBRATION_X) || !defined(TOUCH_CALIBRATION_Y) || !defined(TOUCH_OFFSET_X) || !defined(TOUCH_OFFSET_Y))
+  #error "TOUCH_CALIBRATION_[XY] and TOUCH_OFFSET_[XY] are required for resistive touch screens with TOUCH_SCREEN_CALIBRATION disabled."
 #endif
 
 /**
diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp
index 83a7ea78b72..3d4e0a40e1e 100644
--- a/Marlin/src/lcd/tft/touch.cpp
+++ b/Marlin/src/lcd/tft/touch.cpp
@@ -257,18 +257,23 @@ void Touch::hold(touch_control_t *control, millis_t delay) {
 }
 
 bool Touch::get_point(int16_t *x, int16_t *y) {
-  #if ENABLED(TOUCH_SCREEN_CALIBRATION)
-    bool is_touched = (touch_calibration.calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y));
+  #if ENABLED(TFT_TOUCH_DEVICE_XPT2046)
+    #if ENABLED(TOUCH_SCREEN_CALIBRATION)
+      bool is_touched = (touch_calibration.calibration.orientation == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y));
 
-    if (is_touched && touch_calibration.calibration.orientation != TOUCH_ORIENTATION_NONE) {
-      *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x;
-      *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y;
-    }
-  #else
-    bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y));
-    *x = uint16_t((uint32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X;
-    *y = uint16_t((uint32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y;
+      if (is_touched && touch_calibration.calibration.orientation != TOUCH_ORIENTATION_NONE) {
+        *x = int16_t((int32_t(*x) * touch_calibration.calibration.x) >> 16) + touch_calibration.calibration.offset_x;
+        *y = int16_t((int32_t(*y) * touch_calibration.calibration.y) >> 16) + touch_calibration.calibration.offset_y;
+      }
+    #else
+      bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getRawPoint(y, x) : io.getRawPoint(x, y));
+      *x = uint16_t((uint32_t(*x) * TOUCH_CALIBRATION_X) >> 16) + TOUCH_OFFSET_X;
+      *y = uint16_t((uint32_t(*y) * TOUCH_CALIBRATION_Y) >> 16) + TOUCH_OFFSET_Y;
+    #endif
+  #elif ENABLED(TFT_TOUCH_DEVICE_GT911)
+    bool is_touched = (TOUCH_ORIENTATION == TOUCH_PORTRAIT ? io.getPoint(y, x) : io.getPoint(x, y));
   #endif
+
   return is_touched;
 }
 Touch touch;
diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h
index 6726f031ff9..8d6001b8d89 100644
--- a/Marlin/src/lcd/tft/touch.h
+++ b/Marlin/src/lcd/tft/touch.h
@@ -30,8 +30,15 @@
   #include "../tft_io/touch_calibration.h"
 #endif
 
-#include HAL_PATH(../../HAL, tft/xpt2046.h)
-#define TOUCH_DRIVER XPT2046
+#if ENABLED(TFT_TOUCH_DEVICE_GT911)
+  #include HAL_PATH(../../HAL, tft/gt911.h)
+  #define TOUCH_DRIVER_CLASS GT911
+#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046)
+  #include HAL_PATH(../../HAL, tft/xpt2046.h)
+  #define TOUCH_DRIVER_CLASS XPT2046
+#else
+  #error "Unknown Touch Screen Type."
+#endif
 
 // Menu Navigation
 extern int8_t encoderTopLine, encoderLine, screen_items;
@@ -85,7 +92,7 @@ typedef struct __attribute__((__packed__)) {
 
 class Touch {
   private:
-    static TOUCH_DRIVER io;
+    static TOUCH_DRIVER_CLASS io;
     static int16_t x, y;
     static bool enabled;
 
diff --git a/Marlin/src/lcd/tft/ui_1024x600.cpp b/Marlin/src/lcd/tft/ui_1024x600.cpp
index c9c0aae05a5..3b12ab2b60a 100644
--- a/Marlin/src/lcd/tft/ui_1024x600.cpp
+++ b/Marlin/src/lcd/tft/ui_1024x600.cpp
@@ -48,9 +48,9 @@
 void MarlinUI::tft_idle() {
   #if ENABLED(TOUCH_SCREEN)
     if (draw_menu_navigation) {
-      add_control(104, TFT_HEIGHT - 34, PAGE_UP, imgPageUp, encoderTopLine > 0);
-      add_control(344, TFT_HEIGHT - 34, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items);
-      add_control(224, TFT_HEIGHT - 34, BACK, imgBack);
+      add_control(164, TFT_HEIGHT - 50, PAGE_UP, imgPageUp, encoderTopLine > 0);
+      add_control(796, TFT_HEIGHT - 50, PAGE_DOWN, imgPageDown, encoderTopLine + LCD_HEIGHT < screen_items);
+      add_control(480, TFT_HEIGHT - 50, BACK, imgBack);
       draw_menu_navigation = false;
     }
   #endif
@@ -60,6 +60,7 @@ void MarlinUI::tft_idle() {
 }
 
 #if ENABLED(SHOW_BOOTSCREEN)
+
   void MarlinUI::show_bootscreen() {
     tft.queue.reset();
 
@@ -81,9 +82,13 @@ void MarlinUI::tft_idle() {
     #endif
 
     tft.queue.sync();
-    safe_delay(BOOTSCREEN_TIMEOUT);
+  }
+
+  void MarlinUI::bootscreen_completion(const millis_t sofar) {
+    if ((BOOTSCREEN_TIMEOUT) > sofar) safe_delay((BOOTSCREEN_TIMEOUT) - sofar);
     clear_lcd();
   }
+
 #endif
 
 void MarlinUI::draw_kill_screen() {
@@ -289,7 +294,7 @@ void MarlinUI::draw_status_screen() {
   tft_string.set(i16tostr3rj(feedrate_percentage));
   tft_string.add('%');
   tft.add_text(36, 1, color , tft_string);
-  TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 96, 176, 100, 32));
+  TERN_(TOUCH_SCREEN, touch.add_control(FEEDRATE, 274, y, 100, 32));
 
   // flow rate
   tft.canvas(650, y, 100, 32);
@@ -299,10 +304,10 @@ void MarlinUI::draw_status_screen() {
   tft_string.set(i16tostr3rj(planner.flow_percentage[active_extruder]));
   tft_string.add('%');
   tft.add_text(36, 1, color , tft_string);
-  TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 284, 176, 100, 32, active_extruder));
+  TERN_(TOUCH_SCREEN, touch.add_control(FLOWRATE, 650, y, 100, 32, active_extruder));
 
   #if ENABLED(TOUCH_SCREEN)
-    add_control(404, y, menu_main, imgSettings);
+    add_control(900, y, menu_main, imgSettings);
     TERN_(SDSUPPORT, add_control(12, y, menu_media, imgSD, !printingIsActive(), COLOR_CONTROL_ENABLED, card.isMounted() && printingIsActive() ? COLOR_BUSY : COLOR_CONTROL_DISABLED));
   #endif
 
@@ -375,8 +380,8 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val
   extern screenFunc_t _manual_move_func_ptr;
   if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) {
 
-    #define SLIDER_LENGTH 336
-    #define SLIDER_Y_POSITION 186
+    #define SLIDER_LENGTH 600
+    #define SLIDER_Y_POSITION 200
 
     tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16);
     tft.set_background(COLOR_BACKGROUND);
@@ -398,9 +403,9 @@ void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const val
 
 void TFT::draw_edit_screen_buttons() {
   #if ENABLED(TOUCH_SCREEN)
-    add_control(64, TFT_HEIGHT - 64, DECREASE, imgDecrease);
-    add_control(352, TFT_HEIGHT - 64, INCREASE, imgIncrease);
-    add_control(208, TFT_HEIGHT - 64, CLICK, imgConfirm);
+    add_control(164, TFT_HEIGHT - 64, DECREASE, imgDecrease);
+    add_control(796, TFT_HEIGHT - 64, INCREASE, imgIncrease);
+    add_control(480, TFT_HEIGHT - 64, CLICK, imgConfirm);
   #endif
 }
 
@@ -755,7 +760,7 @@ static void z_minus() { moveAxis(Z_AXIS, -1); }
     drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING));
     queue.inject_P(G28_STR);
     // Disable touch until home is done
-    TERN_(HAS_TFT_XPT2046, touch.disable());
+    TERN_(TOUCH_SCREEN, touch.disable());
     drawAxisValue(E_AXIS);
     drawAxisValue(X_AXIS);
     drawAxisValue(Y_AXIS);
@@ -804,14 +809,14 @@ static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage
     tft.add_image(0, 0, img, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY);
   }
 
-  TERN_(HAS_TFT_XPT2046, if (enabled) touch.add_control(BUTTON, x, y, width, height, data));
+  TERN_(TOUCH_SCREEN, if (enabled) touch.add_control(BUTTON, x, y, width, height, data));
 }
 
 void MarlinUI::move_axis_screen() {
   // Reset
   defer_status_screen(true);
   motionAxisState.blocked = false;
-  TERN_(HAS_TFT_XPT2046, touch.enable());
+  TERN_(TOUCH_SCREEN, touch.enable());
 
   ui.clear_lcd();
 
@@ -849,13 +854,13 @@ void MarlinUI::move_axis_screen() {
   motionAxisState.eNamePos.x = x;
   motionAxisState.eNamePos.y = y;
   drawCurESelection();
-  TERN_(HAS_TFT_XPT2046, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select));
+  TERN_(TOUCH_SCREEN, if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, BTN_HEIGHT, (intptr_t)e_select));
 
   x += BTN_WIDTH + spacing;
   drawBtn(x, y, "X-", (intptr_t)x_minus, imgLeft, X_BTN_COLOR, !busy);
 
   x += BTN_WIDTH + spacing; //imgHome is 64x64
-  TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy));
+  TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH / 2 - Images[imgHome].width / 2, y - (Images[imgHome].width - BTN_HEIGHT) / 2, BUTTON, (intptr_t)do_home, imgHome, !busy));
 
   x += BTN_WIDTH + spacing;
   uint16_t xplus_x = x;
@@ -904,13 +909,13 @@ void MarlinUI::move_axis_screen() {
   motionAxisState.stepValuePos.y = y;
   if (!busy) {
     drawCurStepValue();
-    TERN_(HAS_TFT_XPT2046, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size));
+    TERN_(TOUCH_SCREEN, touch.add_control(BUTTON, motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT, (intptr_t)step_size));
   }
 
   // aligned with x+
   drawBtn(xplus_x, TFT_HEIGHT - Y_MARGIN - BTN_HEIGHT, "off", (intptr_t)disable_steppers, imgCancel, COLOR_WHITE, !busy);
 
-  TERN_(HAS_TFT_XPT2046, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack));
+  TERN_(TOUCH_SCREEN, add_control(TFT_WIDTH - X_MARGIN - BTN_WIDTH, y, BACK, imgBack));
 }
 
 #endif // HAS_UI_480x320
diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp
index 975de58211f..c9476bd2bb0 100644
--- a/Marlin/src/lcd/touch/touch_buttons.cpp
+++ b/Marlin/src/lcd/touch/touch_buttons.cpp
@@ -24,8 +24,15 @@
 #include "touch_buttons.h"
 #include "../scaled_tft.h"
 
-#include HAL_PATH(../../HAL, tft/xpt2046.h)
-XPT2046 touchIO;
+#if ENABLED(TFT_TOUCH_DEVICE_GT911)
+  #include HAL_PATH(../../HAL, tft/gt911.h)
+  GT911 touchIO;
+#elif ENABLED(TFT_TOUCH_DEVICE_XPT2046)
+  #include HAL_PATH(../../HAL, tft/xpt2046.h)
+  XPT2046 touchIO;
+#else
+  #error "Unknown Touch Screen Type."
+#endif
 
 #if ENABLED(TOUCH_SCREEN_CALIBRATION)
   #include "../tft_io/touch_calibration.h"
diff --git a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h
index 320d04e0b17..c4349d182bf 100644
--- a/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h
+++ b/Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h
@@ -207,11 +207,21 @@
   #define LCD_B4_PIN                        PI4
   #define LCD_B3_PIN                        PG11
 
+  // GT911 Capacitive Touch Sensor
+  #if ENABLED(TFT_TOUCH_DEVICE_GT911)
+    #define GT911_RST_PIN                   PE4
+    #define GT911_INT_PIN                   PE3
+    #define GT911_SW_I2C_SCL_PIN            PE2
+    #define GT911_SW_I2C_SDA_PIN            PE6
+  #endif
+
 #endif
 
-#define BTN_EN1                             PH6
-#define BTN_EN2                             PH7
-#define BTN_ENC                             PH8
+#if IS_NEWPANEL
+  #define BTN_EN1                           PH6
+  #define BTN_EN2                           PH7
+  #define BTN_ENC                           PH8
+#endif
 
 #ifndef SDCARD_CONNECTION
   #define SDCARD_CONNECTION              ONBOARD