Optimize LVGL with HAL TFT IO (SPI and FSMC) (#18974)
This commit is contained in:
parent
3b9e0c3dde
commit
ff5c8d3570
@ -22,7 +22,7 @@
|
|||||||
|
|
||||||
#include "../../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_FSMC_TFT
|
#if HAS_FSMC_TFT || ENABLED(TFT_LVGL_UI_FSMC)
|
||||||
|
|
||||||
#include "tft_fsmc.h"
|
#include "tft_fsmc.h"
|
||||||
#include <libmaple/fsmc.h>
|
#include <libmaple/fsmc.h>
|
||||||
@ -224,6 +224,7 @@ void TFT_FSMC::Abort() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||||
|
#if defined(FSMC_DMA_DEV) && defined(FSMC_DMA_CHANNEL)
|
||||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease);
|
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | MemoryIncrease);
|
||||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Count);
|
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, Count);
|
||||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||||
@ -231,6 +232,7 @@ void TFT_FSMC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Cou
|
|||||||
|
|
||||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
|
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {};
|
||||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAS_FSMC_TFT
|
#endif // HAS_FSMC_TFT
|
||||||
|
@ -61,4 +61,11 @@ class TFT_FSMC {
|
|||||||
|
|
||||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); }
|
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_MODE, Data, Count); }
|
||||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); }
|
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_CIRC_MODE, &Data, Count); }
|
||||||
|
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||||
|
static uint16_t Data; Data = Color;
|
||||||
|
while (Count > 0) {
|
||||||
|
TransmitDMA(DMA_CIRC_MODE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||||
|
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
@ -22,7 +22,7 @@
|
|||||||
|
|
||||||
#include "../../../inc/MarlinConfig.h"
|
#include "../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_SPI_TFT
|
#if HAS_SPI_TFT || ENABLED(TFT_LVGL_UI_SPI)
|
||||||
|
|
||||||
#include "tft_spi.h"
|
#include "tft_spi.h"
|
||||||
|
|
||||||
@ -103,16 +103,21 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
|
|||||||
#if !PIN_EXISTS(TFT_MISO)
|
#if !PIN_EXISTS(TFT_MISO)
|
||||||
return 0;
|
return 0;
|
||||||
#else
|
#else
|
||||||
uint16_t d = 0;
|
uint8_t d = 0;
|
||||||
|
uint32_t data = 0;
|
||||||
|
SPIx.setClockDivider(SPI_CLOCK_DIV16);
|
||||||
DataTransferBegin(DATASIZE_8BIT);
|
DataTransferBegin(DATASIZE_8BIT);
|
||||||
WriteReg(Reg);
|
WriteReg(Reg);
|
||||||
|
|
||||||
SPI.read((uint8_t*)&d, 1); //dummy read
|
LOOP_L_N(i, 4) {
|
||||||
SPI.read((uint8_t*)&d, 1);
|
SPIx.read((uint8_t*)&d, 1);
|
||||||
|
data = (data << 8) | d;
|
||||||
|
}
|
||||||
|
|
||||||
DataTransferEnd();
|
DataTransferEnd();
|
||||||
|
SPIx.setClockDivider(SPI_CLOCK_MAX);
|
||||||
|
|
||||||
return d >> 7;
|
return data >> 7;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -62,4 +62,11 @@ public:
|
|||||||
|
|
||||||
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_MINC_ENABLE, Data, Count); }
|
||||||
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_MINC_DISABLE, &Data, Count); }
|
||||||
|
static void WriteMultiple(uint16_t Color, uint32_t Count) {
|
||||||
|
static uint16_t Data; Data = Color;
|
||||||
|
while (Count > 0) {
|
||||||
|
TransmitDMA(DMA_MINC_DISABLE, &Data, Count > 0xFFFF ? 0xFFFF : Count);
|
||||||
|
Count = Count > 0xFFFF ? Count - 0xFFFF : 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
};
|
};
|
||||||
|
@ -252,7 +252,7 @@
|
|||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Full Touch Screen needs 'tft/xpt2046'
|
// Full Touch Screen needs 'tft/xpt2046'
|
||||||
#if ENABLED(TOUCH_SCREEN)
|
#if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI)
|
||||||
#define HAS_TFT_XPT2046 1
|
#define HAS_TFT_XPT2046 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -54,112 +54,27 @@ TFT SPI_TFT;
|
|||||||
|
|
||||||
// use SPI1 for the spi tft.
|
// use SPI1 for the spi tft.
|
||||||
void TFT::spi_init(uint8_t spiRate) {
|
void TFT::spi_init(uint8_t spiRate) {
|
||||||
|
tftio.Init();
|
||||||
SPI_TFT_CS_H;
|
|
||||||
|
|
||||||
/**
|
|
||||||
* STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz
|
|
||||||
* STM32F1 has 3 SPI ports, SPI1 in APB2, SPI2/SPI3 in APB1
|
|
||||||
* so the minimum prescale of SPI1 is DIV4, SPI2/SPI3 is DIV2
|
|
||||||
*/
|
|
||||||
uint8_t clock;
|
|
||||||
switch (spiRate) {
|
|
||||||
case SPI_FULL_SPEED: clock = SPI_CLOCK_DIV4; break;
|
|
||||||
case SPI_HALF_SPEED: clock = SPI_CLOCK_DIV4; break;
|
|
||||||
case SPI_QUARTER_SPEED: clock = SPI_CLOCK_DIV8; break;
|
|
||||||
case SPI_EIGHTH_SPEED: clock = SPI_CLOCK_DIV16; break;
|
|
||||||
case SPI_SPEED_5: clock = SPI_CLOCK_DIV32; break;
|
|
||||||
case SPI_SPEED_6: clock = SPI_CLOCK_DIV64; break;
|
|
||||||
default: clock = SPI_CLOCK_DIV2; // Default from the SPI library
|
|
||||||
}
|
|
||||||
SPI.setModule(1);
|
|
||||||
SPI.begin();
|
|
||||||
SPI.setClockDivider(clock);
|
|
||||||
SPI.setBitOrder(MSBFIRST);
|
|
||||||
SPI.setDataMode(SPI_MODE0);
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t TFT::spi_Rec() {
|
|
||||||
uint8_t returnByte = SPI.transfer(ff);
|
|
||||||
return returnByte;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint8_t TFT::spi_read_write_byte(uint8_t data) {
|
|
||||||
uint8_t returnByte = SPI.transfer(data);
|
|
||||||
return returnByte;
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Receive a number of bytes from the SPI port to a buffer
|
|
||||||
*
|
|
||||||
* @param buf Pointer to starting address of buffer to write to.
|
|
||||||
* @param nbyte Number of bytes to receive.
|
|
||||||
* @return Nothing
|
|
||||||
*
|
|
||||||
* @details Uses DMA
|
|
||||||
*/
|
|
||||||
void TFT::spi_Read(uint8_t* buf, uint16_t nbyte) {SPI.dmaTransfer(0, const_cast<uint8_t*>(buf), nbyte);}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Send a single byte on SPI port
|
|
||||||
*
|
|
||||||
* @param b Byte to send
|
|
||||||
*
|
|
||||||
* @details
|
|
||||||
*/
|
|
||||||
void TFT::spi_Send(uint8_t b) {SPI.send(b);}
|
|
||||||
|
|
||||||
/**
|
|
||||||
* @brief Write token and then write from 512 byte buffer to SPI (for SD card)
|
|
||||||
*
|
|
||||||
* @param buf Pointer with buffer start address
|
|
||||||
* @return Nothing
|
|
||||||
*
|
|
||||||
* @details Use DMA
|
|
||||||
*/
|
|
||||||
void TFT::spi_SendBlock(uint8_t token, const uint8_t* buf) {
|
|
||||||
SPI.send(token);
|
|
||||||
SPI.dmaSend(const_cast<uint8_t*>(buf), 512);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TFT::LCD_WR_REG(uint8_t cmd) {
|
void TFT::LCD_WR_REG(uint8_t cmd) {
|
||||||
SPI_TFT_CS_L;
|
tftio.WriteReg(cmd);
|
||||||
SPI_TFT_DC_L;
|
|
||||||
spi_Send(cmd);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
}
|
}
|
||||||
void TFT::LCD_WR_DATA(uint8_t data) {
|
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
spi_Send(data);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
}
|
|
||||||
void TFT::LCD_WriteRAM_Prepare() {LCD_WR_REG(0X2C);}
|
|
||||||
void TFT::SetCursor(uint16_t x, uint16_t y) {
|
|
||||||
LCD_WR_REG(0x2A);
|
|
||||||
LCD_WR_DATA(x >> 8);
|
|
||||||
LCD_WR_DATA(x);
|
|
||||||
LCD_WR_DATA(x >> 8);
|
|
||||||
LCD_WR_DATA(x);
|
|
||||||
|
|
||||||
LCD_WR_REG(0x2B);
|
void TFT::LCD_WR_DATA(uint8_t data) {
|
||||||
LCD_WR_DATA(y >> 8);
|
tftio.WriteData(data);
|
||||||
LCD_WR_DATA(y);
|
|
||||||
LCD_WR_DATA(y >> 8);
|
|
||||||
LCD_WR_DATA(y);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TFT::SetPoint(uint16_t x, uint16_t y, uint16_t point) {
|
void TFT::SetPoint(uint16_t x, uint16_t y, uint16_t point) {
|
||||||
if ((x > 480) || (y > 320)) return;
|
if ((x > 480) || (y > 320)) return;
|
||||||
|
|
||||||
SetCursor(x, y);
|
SetWindows(x, y, 1, 1);
|
||||||
|
tftio.WriteMultiple(point, (uint16_t)1);
|
||||||
LCD_WriteRAM_Prepare();
|
|
||||||
LCD_WR_DATA((uint8_t)(point >> 8));
|
|
||||||
LCD_WR_DATA((uint8_t)point);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void TFT::SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height) {
|
void TFT::SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height) {
|
||||||
|
tftio.DataTransferBegin(DATASIZE_8BIT);
|
||||||
|
|
||||||
LCD_WR_REG(0x2A);
|
LCD_WR_REG(0x2A);
|
||||||
LCD_WR_DATA(x >> 8);
|
LCD_WR_DATA(x >> 8);
|
||||||
LCD_WR_DATA(x);
|
LCD_WR_DATA(x);
|
||||||
@ -171,6 +86,10 @@ void TFT::SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height) {
|
|||||||
LCD_WR_DATA(y);
|
LCD_WR_DATA(y);
|
||||||
LCD_WR_DATA((y + height - 1) >> 8);
|
LCD_WR_DATA((y + height - 1) >> 8);
|
||||||
LCD_WR_DATA(y + height - 1);
|
LCD_WR_DATA(y + height - 1);
|
||||||
|
|
||||||
|
LCD_WR_REG(0X2C);
|
||||||
|
|
||||||
|
tftio.DataTransferEnd();
|
||||||
}
|
}
|
||||||
|
|
||||||
void TFT::LCD_init() {
|
void TFT::LCD_init() {
|
||||||
@ -180,6 +99,8 @@ void TFT::LCD_init() {
|
|||||||
delay(150);
|
delay(150);
|
||||||
SPI_TFT_RST_H;
|
SPI_TFT_RST_H;
|
||||||
|
|
||||||
|
tftio.DataTransferBegin(DATASIZE_8BIT);
|
||||||
|
|
||||||
delay(120);
|
delay(120);
|
||||||
LCD_WR_REG(0x11);
|
LCD_WR_REG(0x11);
|
||||||
delay(120);
|
delay(120);
|
||||||
@ -251,6 +172,8 @@ void TFT::LCD_init() {
|
|||||||
delay(120); // Delay 120ms
|
delay(120); // Delay 120ms
|
||||||
LCD_WR_REG(0x29); // Display ON
|
LCD_WR_REG(0x29); // Display ON
|
||||||
|
|
||||||
|
tftio.DataTransferEnd();
|
||||||
|
|
||||||
LCD_clear(0x0000); //
|
LCD_clear(0x0000); //
|
||||||
LCD_Draw_Logo();
|
LCD_Draw_Logo();
|
||||||
SPI_TFT_BLK_H;
|
SPI_TFT_BLK_H;
|
||||||
@ -258,81 +181,18 @@ void TFT::LCD_init() {
|
|||||||
}
|
}
|
||||||
|
|
||||||
void TFT::LCD_clear(uint16_t color) {
|
void TFT::LCD_clear(uint16_t color) {
|
||||||
unsigned int i;
|
SetWindows(0, 0, (LCD_FULL_PIXEL_WIDTH) - 1, (LCD_FULL_PIXEL_HEIGHT) - 1);
|
||||||
uint8_t tbuf[960];
|
tftio.WriteMultiple(color, (uint32_t)(LCD_FULL_PIXEL_WIDTH) * (LCD_FULL_PIXEL_HEIGHT));
|
||||||
|
|
||||||
SetCursor(0, 0);
|
|
||||||
SetWindows(0, 0, 480 - 1, 320 - 1);
|
|
||||||
LCD_WriteRAM_Prepare();
|
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
for (i = 0; i < 960;) {
|
|
||||||
tbuf[i] = color >> 8;
|
|
||||||
tbuf[i + 1] = color;
|
|
||||||
i += 2;
|
|
||||||
}
|
|
||||||
for (i = 0; i < 320; i++) {
|
|
||||||
// for (m=0;m<480;m++)
|
|
||||||
// {
|
|
||||||
// LCD_WR_DATA(color>>8);
|
|
||||||
// LCD_WR_DATA(color);
|
|
||||||
SPI.dmaSend(tbuf, 960, true);
|
|
||||||
// SPI_TFT_CS_H;
|
|
||||||
// }
|
|
||||||
}
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
extern unsigned char bmp_public_buf[17 * 1024];
|
extern unsigned char bmp_public_buf[17 * 1024];
|
||||||
|
|
||||||
void TFT::LCD_Draw_Logo() {
|
void TFT::LCD_Draw_Logo() {
|
||||||
uint16_t i,y_off = 0;
|
SetWindows(0, 0, LCD_FULL_PIXEL_WIDTH, LCD_FULL_PIXEL_HEIGHT);
|
||||||
uint16_t *p_index;
|
for (uint16_t i = 0; i < (LCD_FULL_PIXEL_HEIGHT); i ++) {
|
||||||
uint16_t Color;
|
Pic_Logo_Read((uint8_t *)"", (uint8_t *)bmp_public_buf, (LCD_FULL_PIXEL_WIDTH) * 2);
|
||||||
|
tftio.WriteSequence((uint16_t *)bmp_public_buf, LCD_FULL_PIXEL_WIDTH);
|
||||||
#if 1
|
|
||||||
for (y_off = 0; y_off < 320; y_off ++) {
|
|
||||||
Pic_Logo_Read((uint8_t *)"", (uint8_t *)bmp_public_buf, 960);
|
|
||||||
|
|
||||||
SPI_TFT.spi_init(SPI_FULL_SPEED);
|
|
||||||
SetWindows(0, y_off, 480, 1);
|
|
||||||
LCD_WriteRAM_Prepare(); /* Prepare to write GRAM */
|
|
||||||
for (i = 0; i < 960;) {
|
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
|
||||||
Color = (*p_index >> 8);
|
|
||||||
*p_index = Color | ((*p_index & 0xFF) << 8);
|
|
||||||
i+=2;
|
|
||||||
}
|
}
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
SPI.dmaSend(bmp_public_buf,960,true);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
}
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
for (index = 0; index < 40; index ++) {
|
|
||||||
Pic_Logo_Read((uint8_t *)"", bmp_public_buf, 480*8*2);
|
|
||||||
i = 0;
|
|
||||||
SetCursor(0,0);
|
|
||||||
SetWindows(0, y_off * 8, 480, 8);
|
|
||||||
LCD_WriteRAM_Prepare(); /* Prepare to write GRAM */
|
|
||||||
for (i = 0; i < 480 * 8 * 2;) {
|
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
|
||||||
Color = (*p_index >> 8);
|
|
||||||
*p_index = Color | ((*p_index & 0xFF) << 8);
|
|
||||||
i += 2;
|
|
||||||
}
|
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
SPI.dmaSend(bmp_public_buf,480*8*2,true);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
|
|
||||||
y_off++;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
SetWindows(0, 0, 479, 319);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAS_TFT_LVGL_UI_SPI
|
#endif // HAS_TFT_LVGL_UI_SPI
|
||||||
|
@ -21,13 +21,13 @@
|
|||||||
*/
|
*/
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include "../../inc/MarlinConfigPre.h"
|
||||||
|
|
||||||
#define SPI_TFT_CS_H OUT_WRITE(SPI_TFT_CS_PIN, HIGH)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
#define SPI_TFT_CS_L OUT_WRITE(SPI_TFT_CS_PIN, LOW)
|
#include HAL_PATH(../../HAL, tft/tft_spi.h)
|
||||||
|
#elif ENABLED(TFT_LVGL_UI_FSMC)
|
||||||
#define SPI_TFT_DC_H OUT_WRITE(SPI_TFT_DC_PIN, HIGH)
|
#include HAL_PATH(../../HAL, tft/tft_fsmc.h)
|
||||||
#define SPI_TFT_DC_L OUT_WRITE(SPI_TFT_DC_PIN, LOW)
|
#endif
|
||||||
|
|
||||||
#define SPI_TFT_RST_H OUT_WRITE(SPI_TFT_RST_PIN, HIGH)
|
#define SPI_TFT_RST_H OUT_WRITE(SPI_TFT_RST_PIN, HIGH)
|
||||||
#define SPI_TFT_RST_L OUT_WRITE(SPI_TFT_RST_PIN, LOW)
|
#define SPI_TFT_RST_L OUT_WRITE(SPI_TFT_RST_PIN, LOW)
|
||||||
@ -37,20 +37,14 @@
|
|||||||
|
|
||||||
class TFT {
|
class TFT {
|
||||||
public:
|
public:
|
||||||
|
TFT_IO tftio;
|
||||||
void spi_init(uint8_t spiRate);
|
void spi_init(uint8_t spiRate);
|
||||||
uint8_t spi_Rec();
|
|
||||||
uint8_t spi_read_write_byte(uint8_t data);
|
|
||||||
void spi_Read(uint8_t* buf, uint16_t nbyte);
|
|
||||||
void spi_Send(uint8_t b);
|
|
||||||
void spi_SendBlock(uint8_t token, const uint8_t* buf);
|
|
||||||
void LCD_WR_REG(uint8_t cmd);
|
void LCD_WR_REG(uint8_t cmd);
|
||||||
void LCD_WR_DATA(uint8_t data);
|
void LCD_WR_DATA(uint8_t data);
|
||||||
void SetCursor(uint16_t x, uint16_t y);
|
|
||||||
void SetPoint(uint16_t x, uint16_t y, uint16_t point);
|
void SetPoint(uint16_t x, uint16_t y, uint16_t point);
|
||||||
void SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height);
|
void SetWindows(uint16_t x, uint16_t y, uint16_t with, uint16_t height);
|
||||||
void LCD_init();
|
void LCD_init();
|
||||||
void LCD_clear(uint16_t color);
|
void LCD_clear(uint16_t color);
|
||||||
void LCD_WriteRAM_Prepare();
|
|
||||||
void LCD_Draw_Logo();
|
void LCD_Draw_Logo();
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -51,6 +51,8 @@
|
|||||||
#endif
|
#endif
|
||||||
#include "../../../../gcode/gcode.h"
|
#include "../../../../gcode/gcode.h"
|
||||||
|
|
||||||
|
#include "pic_manager.h"
|
||||||
|
|
||||||
static lv_obj_t * scr;
|
static lv_obj_t * scr;
|
||||||
extern uint8_t sel_id;
|
extern uint8_t sel_id;
|
||||||
extern uint8_t once_flag;
|
extern uint8_t once_flag;
|
||||||
|
@ -500,14 +500,9 @@ char *creat_title_text() {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
//SERIAL_ECHOLNPAIR("gPicturePreviewStart: ", gPicturePreviewStart, " PREVIEW_LITTLE_PIC_SIZE: ", PREVIEW_LITTLE_PIC_SIZE);
|
|
||||||
|
|
||||||
card.setIndex((gPicturePreviewStart + To_pre_view) + size * row + 8);
|
card.setIndex((gPicturePreviewStart + To_pre_view) + size * row + 8);
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
SPI_TFT.spi_init(SPI_FULL_SPEED);
|
|
||||||
//SPI_TFT.SetCursor(0,0);
|
|
||||||
SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
||||||
SPI_TFT.LCD_WriteRAM_Prepare();
|
|
||||||
#else
|
#else
|
||||||
ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
||||||
LCD_WriteRAM_Prepare();
|
LCD_WriteRAM_Prepare();
|
||||||
@ -525,19 +520,11 @@ char *creat_title_text() {
|
|||||||
if (j >= 400) break;
|
if (j >= 400) break;
|
||||||
}
|
}
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
uint16_t Color, SpiColor;
|
for (i = 0; i < 400; i += 2) {
|
||||||
SpiColor = (LV_COLOR_BACKGROUND.full >> 8) | ((LV_COLOR_BACKGROUND.full & 0xFF) << 8);
|
|
||||||
for (i = 0; i < 400;) {
|
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
||||||
Color = (*p_index >> 8);
|
if (*p_index == 0x0000) *p_index = LV_COLOR_BACKGROUND.full;
|
||||||
*p_index = Color | ((*p_index & 0xFF) << 8);
|
|
||||||
i += 2;
|
|
||||||
if (*p_index == 0x0000) *p_index = SpiColor;
|
|
||||||
}
|
}
|
||||||
SPI_TFT_CS_L;
|
SPI_TFT.tftio.WriteSequence((uint16_t*)bmp_public_buf, 200);
|
||||||
SPI_TFT_DC_H;
|
|
||||||
SPI.dmaSend(bmp_public_buf, 400, true);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
#else
|
#else
|
||||||
for (i = 0; i < 400;) {
|
for (i = 0; i < 400;) {
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
||||||
@ -627,10 +614,7 @@ char *creat_title_text() {
|
|||||||
|
|
||||||
card.setIndex((PREVIEW_LITTLE_PIC_SIZE + To_pre_view) + size * row + 8);
|
card.setIndex((PREVIEW_LITTLE_PIC_SIZE + To_pre_view) + size * row + 8);
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
SPI_TFT.spi_init(SPI_FULL_SPEED);
|
|
||||||
//SPI_TFT.SetCursor(0,0);
|
|
||||||
SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
SPI_TFT.SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
||||||
SPI_TFT.LCD_WriteRAM_Prepare();
|
|
||||||
#else
|
#else
|
||||||
ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
ili9320_SetWindows(xpos_pixel, ypos_pixel + row, 200, 1);
|
||||||
LCD_WriteRAM_Prepare();
|
LCD_WriteRAM_Prepare();
|
||||||
@ -750,9 +734,6 @@ char *creat_title_text() {
|
|||||||
void Draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) {
|
void Draw_default_preview(int xpos_pixel, int ypos_pixel, uint8_t sel) {
|
||||||
int index;
|
int index;
|
||||||
int y_off = 0;
|
int y_off = 0;
|
||||||
int _y;
|
|
||||||
uint16_t *p_index;
|
|
||||||
int i;
|
|
||||||
|
|
||||||
for (index = 0; index < 10; index++) { // 200*200
|
for (index = 0; index < 10; index++) { // 200*200
|
||||||
#if HAS_BAK_VIEW_IN_FLASH
|
#if HAS_BAK_VIEW_IN_FLASH
|
||||||
@ -761,58 +742,24 @@ char *creat_title_text() {
|
|||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k
|
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
|
||||||
uint16_t Color;
|
|
||||||
for (i = 0; i < (DEFAULT_VIEW_MAX_SIZE / 10);) {
|
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
|
||||||
Color = (*p_index >> 8);
|
|
||||||
*p_index = Color | ((*p_index & 0xff) << 8);
|
|
||||||
i += 2;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k
|
default_view_Read(bmp_public_buf, DEFAULT_VIEW_MAX_SIZE / 10); // 20k
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
|
||||||
for (i = 0; i < (DEFAULT_VIEW_MAX_SIZE / 10);) {
|
|
||||||
p_index = (uint16_t *)(&bmp_public_buf[i]);
|
|
||||||
Color = (*p_index >> 8);
|
|
||||||
*p_index = Color | ((*p_index & 0xff) << 8);
|
|
||||||
i += 2;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
i = 0;
|
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
|
SPI_TFT.SetWindows(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200
|
||||||
//SPI_TFT.spi_init(SPI_FULL_SPEED);
|
SPI_TFT.tftio.WriteSequence((uint16_t*)(bmp_public_buf), DEFAULT_VIEW_MAX_SIZE / 20);
|
||||||
//SPI_TFT.SetWindows(xpos_pixel, y_off * 20+ypos_pixel, 200,20); //200*200
|
|
||||||
//SPI_TFT.LCD_WriteRAM_Prepare();
|
|
||||||
int j = 0;
|
|
||||||
for (_y = y_off * 20; _y < (y_off + 1) * 20; _y++) {
|
|
||||||
SPI_TFT.spi_init(SPI_FULL_SPEED);
|
|
||||||
SPI_TFT.SetWindows(xpos_pixel, y_off * 20 + ypos_pixel + j, 200, 1); // 200*200
|
|
||||||
SPI_TFT.LCD_WriteRAM_Prepare();
|
|
||||||
|
|
||||||
j++;
|
|
||||||
//memcpy(public_buf,&bmp_public_buf[i],400);
|
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
SPI.dmaSend(&bmp_public_buf[i], 400, true);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
|
|
||||||
i += 400;
|
|
||||||
if (i >= 8000) break;
|
|
||||||
}
|
|
||||||
#else
|
#else
|
||||||
int x_off = 0;
|
int x_off = 0;
|
||||||
uint16_t temp_p;
|
uint16_t temp_p;
|
||||||
|
int i = 0;
|
||||||
|
uint16_t *p_index;
|
||||||
ili9320_SetWindows(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200
|
ili9320_SetWindows(xpos_pixel, y_off * 20 + ypos_pixel, 200, 20); // 200*200
|
||||||
|
|
||||||
LCD_WriteRAM_Prepare();
|
LCD_WriteRAM_Prepare();
|
||||||
|
|
||||||
for (_y = y_off * 20; _y < (y_off + 1) * 20; _y++) {
|
for (int _y = y_off * 20; _y < (y_off + 1) * 20; _y++) {
|
||||||
for (x_off = 0; x_off < 200; x_off++) {
|
for (x_off = 0; x_off < 200; x_off++) {
|
||||||
if (sel == 1) {
|
if (sel == 1) {
|
||||||
temp_p = (uint16_t)(bmp_public_buf[i] | bmp_public_buf[i + 1] << 8);
|
temp_p = (uint16_t)(bmp_public_buf[i] | bmp_public_buf[i + 1] << 8);
|
||||||
|
@ -590,8 +590,6 @@ void disp_char_1624(uint16_t x, uint16_t y, uint8_t c, uint16_t charColor, uint1
|
|||||||
}
|
}
|
||||||
|
|
||||||
void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor) {
|
void disp_string(uint16_t x, uint16_t y, const char * string, uint16_t charColor, uint16_t bkColor) {
|
||||||
// Select TFT SPI so it can receive data
|
|
||||||
TERN_(TFT_LVGL_UI_SPI, SPI_TFT.spi_init(SPI_FULL_SPEED));
|
|
||||||
while (*string != '\0') {
|
while (*string != '\0') {
|
||||||
disp_char_1624(x, y, *string, charColor, bkColor);
|
disp_char_1624(x, y, *string, charColor, bkColor);
|
||||||
string++;
|
string++;
|
||||||
|
@ -22,249 +22,39 @@
|
|||||||
|
|
||||||
#include "../../../../inc/MarlinConfig.h"
|
#include "../../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_TFT_LVGL_UI
|
#if ENABLED(TFT_LVGL_UI_FSMC)
|
||||||
|
|
||||||
#if defined(ARDUINO_ARCH_STM32F1) && PIN_EXISTS(FSMC_CS) // FSMC on 100/144 pins SoCs
|
#include HAL_PATH(../../HAL, tft/tft_fsmc.h)
|
||||||
|
TFT_IO tftio;
|
||||||
|
|
||||||
#include <libmaple/fsmc.h>
|
void LCD_IO_Init(uint8_t cs, uint8_t rs);
|
||||||
#include <libmaple/gpio.h>
|
void LCD_IO_WriteData(uint16_t RegValue);
|
||||||
#include <libmaple/dma.h>
|
void LCD_IO_WriteReg(uint16_t Reg);
|
||||||
#include <boards.h>
|
#ifdef LCD_USE_DMA_FSMC
|
||||||
|
|
||||||
/* Timing configuration */
|
|
||||||
#define FSMC_ADDRESS_SETUP_TIME 15// AddressSetupTime
|
|
||||||
#define FSMC_DATA_SETUP_TIME 15// DataSetupTime
|
|
||||||
|
|
||||||
void LCD_IO_Init(uint8_t cs, uint8_t rs);
|
|
||||||
void LCD_IO_WriteData(uint16_t RegValue);
|
|
||||||
void LCD_IO_WriteReg(uint16_t Reg);
|
|
||||||
uint16_t LCD_IO_ReadData(uint16_t RegValue);
|
|
||||||
uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize);
|
|
||||||
uint16_t ILI9488_ReadRAM();
|
|
||||||
#ifdef LCD_USE_DMA_FSMC
|
|
||||||
void LCD_IO_WriteMultiple(uint16_t data, uint32_t count);
|
void LCD_IO_WriteMultiple(uint16_t data, uint32_t count);
|
||||||
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length);
|
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
void LCD_IO_Init(uint8_t cs, uint8_t rs) {
|
||||||
* FSMC LCD IO
|
tftio.Init();
|
||||||
*/
|
}
|
||||||
#define __ASM __asm
|
|
||||||
#define __STATIC_INLINE static inline
|
|
||||||
|
|
||||||
__attribute__((always_inline)) __STATIC_INLINE void __DSB() {__ASM volatile ("dsb 0xF" ::: "memory");}
|
void LCD_IO_WriteData(uint16_t RegValue) {
|
||||||
|
tftio.WriteData(RegValue);
|
||||||
|
}
|
||||||
|
|
||||||
#define FSMC_CS_NE1 PD7
|
void LCD_IO_WriteReg(uint16_t Reg) {
|
||||||
|
tftio.WriteReg(Reg);
|
||||||
#if ENABLED(STM32_XL_DENSITY)
|
}
|
||||||
#define FSMC_CS_NE2 PG9
|
|
||||||
#define FSMC_CS_NE3 PG10
|
|
||||||
#define FSMC_CS_NE4 PG12
|
|
||||||
|
|
||||||
#define FSMC_RS_A0 PF0
|
|
||||||
#define FSMC_RS_A1 PF1
|
|
||||||
#define FSMC_RS_A2 PF2
|
|
||||||
#define FSMC_RS_A3 PF3
|
|
||||||
#define FSMC_RS_A4 PF4
|
|
||||||
#define FSMC_RS_A5 PF5
|
|
||||||
#define FSMC_RS_A6 PF12
|
|
||||||
#define FSMC_RS_A7 PF13
|
|
||||||
#define FSMC_RS_A8 PF14
|
|
||||||
#define FSMC_RS_A9 PF15
|
|
||||||
#define FSMC_RS_A10 PG0
|
|
||||||
#define FSMC_RS_A11 PG1
|
|
||||||
#define FSMC_RS_A12 PG2
|
|
||||||
#define FSMC_RS_A13 PG3
|
|
||||||
#define FSMC_RS_A14 PG4
|
|
||||||
#define FSMC_RS_A15 PG5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#define FSMC_RS_A16 PD11
|
|
||||||
#define FSMC_RS_A17 PD12
|
|
||||||
#define FSMC_RS_A18 PD13
|
|
||||||
#define FSMC_RS_A19 PE3
|
|
||||||
#define FSMC_RS_A20 PE4
|
|
||||||
#define FSMC_RS_A21 PE5
|
|
||||||
#define FSMC_RS_A22 PE6
|
|
||||||
#define FSMC_RS_A23 PE2
|
|
||||||
|
|
||||||
#if ENABLED(STM32_XL_DENSITY)
|
|
||||||
#define FSMC_RS_A24 PG13
|
|
||||||
#define FSMC_RS_A25 PG14
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static uint8_t fsmcInit = 0;
|
|
||||||
|
|
||||||
typedef struct {
|
|
||||||
__IO uint16_t REG;
|
|
||||||
__IO uint16_t RAM;
|
|
||||||
} LCD_CONTROLLER_TypeDef;
|
|
||||||
|
|
||||||
LCD_CONTROLLER_TypeDef *LCD;
|
|
||||||
|
|
||||||
void LCD_IO_Init(uint8_t cs, uint8_t rs) {
|
|
||||||
uint32_t controllerAddress;
|
|
||||||
struct fsmc_nor_psram_reg_map* fsmcPsramRegion;
|
|
||||||
|
|
||||||
if (fsmcInit) return;
|
|
||||||
fsmcInit = 1;
|
|
||||||
|
|
||||||
switch (cs) {
|
|
||||||
case FSMC_CS_NE1: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION1; fsmcPsramRegion = FSMC_NOR_PSRAM1_BASE; break;
|
|
||||||
#if ENABLED(STM32_XL_DENSITY)
|
|
||||||
case FSMC_CS_NE2: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION2; fsmcPsramRegion = FSMC_NOR_PSRAM2_BASE; break;
|
|
||||||
case FSMC_CS_NE3: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION3; fsmcPsramRegion = FSMC_NOR_PSRAM3_BASE; break;
|
|
||||||
case FSMC_CS_NE4: controllerAddress = (uint32_t)FSMC_NOR_PSRAM_REGION4; fsmcPsramRegion = FSMC_NOR_PSRAM4_BASE; break;
|
|
||||||
#endif
|
|
||||||
default: return;
|
|
||||||
}
|
|
||||||
|
|
||||||
#define _ORADDR(N) controllerAddress |= (_BV32(N) - 2)
|
|
||||||
|
|
||||||
switch (rs) {
|
|
||||||
#if ENABLED(STM32_XL_DENSITY)
|
|
||||||
case FSMC_RS_A0: _ORADDR( 1); break;
|
|
||||||
case FSMC_RS_A1: _ORADDR( 2); break;
|
|
||||||
case FSMC_RS_A2: _ORADDR( 3); break;
|
|
||||||
case FSMC_RS_A3: _ORADDR( 4); break;
|
|
||||||
case FSMC_RS_A4: _ORADDR( 5); break;
|
|
||||||
case FSMC_RS_A5: _ORADDR( 6); break;
|
|
||||||
case FSMC_RS_A6: _ORADDR( 7); break;
|
|
||||||
case FSMC_RS_A7: _ORADDR( 8); break;
|
|
||||||
case FSMC_RS_A8: _ORADDR( 9); break;
|
|
||||||
case FSMC_RS_A9: _ORADDR(10); break;
|
|
||||||
case FSMC_RS_A10: _ORADDR(11); break;
|
|
||||||
case FSMC_RS_A11: _ORADDR(12); break;
|
|
||||||
case FSMC_RS_A12: _ORADDR(13); break;
|
|
||||||
case FSMC_RS_A13: _ORADDR(14); break;
|
|
||||||
case FSMC_RS_A14: _ORADDR(15); break;
|
|
||||||
case FSMC_RS_A15: _ORADDR(16); break;
|
|
||||||
#endif
|
|
||||||
case FSMC_RS_A16: _ORADDR(17); break;
|
|
||||||
case FSMC_RS_A17: _ORADDR(18); break;
|
|
||||||
case FSMC_RS_A18: _ORADDR(19); break;
|
|
||||||
case FSMC_RS_A19: _ORADDR(20); break;
|
|
||||||
case FSMC_RS_A20: _ORADDR(21); break;
|
|
||||||
case FSMC_RS_A21: _ORADDR(22); break;
|
|
||||||
case FSMC_RS_A22: _ORADDR(23); break;
|
|
||||||
case FSMC_RS_A23: _ORADDR(24); break;
|
|
||||||
#if ENABLED(STM32_XL_DENSITY)
|
|
||||||
case FSMC_RS_A24: _ORADDR(25); break;
|
|
||||||
case FSMC_RS_A25: _ORADDR(26); break;
|
|
||||||
#endif
|
|
||||||
default: return;
|
|
||||||
}
|
|
||||||
|
|
||||||
rcc_clk_enable(RCC_FSMC);
|
|
||||||
|
|
||||||
gpio_set_mode(GPIOD, 14, GPIO_AF_OUTPUT_PP); // FSMC_D00
|
|
||||||
gpio_set_mode(GPIOD, 15, GPIO_AF_OUTPUT_PP); // FSMC_D01
|
|
||||||
gpio_set_mode(GPIOD, 0, GPIO_AF_OUTPUT_PP);// FSMC_D02
|
|
||||||
gpio_set_mode(GPIOD, 1, GPIO_AF_OUTPUT_PP);// FSMC_D03
|
|
||||||
gpio_set_mode(GPIOE, 7, GPIO_AF_OUTPUT_PP);// FSMC_D04
|
|
||||||
gpio_set_mode(GPIOE, 8, GPIO_AF_OUTPUT_PP);// FSMC_D05
|
|
||||||
gpio_set_mode(GPIOE, 9, GPIO_AF_OUTPUT_PP);// FSMC_D06
|
|
||||||
gpio_set_mode(GPIOE, 10, GPIO_AF_OUTPUT_PP); // FSMC_D07
|
|
||||||
gpio_set_mode(GPIOE, 11, GPIO_AF_OUTPUT_PP); // FSMC_D08
|
|
||||||
gpio_set_mode(GPIOE, 12, GPIO_AF_OUTPUT_PP); // FSMC_D09
|
|
||||||
gpio_set_mode(GPIOE, 13, GPIO_AF_OUTPUT_PP); // FSMC_D10
|
|
||||||
gpio_set_mode(GPIOE, 14, GPIO_AF_OUTPUT_PP); // FSMC_D11
|
|
||||||
gpio_set_mode(GPIOE, 15, GPIO_AF_OUTPUT_PP); // FSMC_D12
|
|
||||||
gpio_set_mode(GPIOD, 8, GPIO_AF_OUTPUT_PP);// FSMC_D13
|
|
||||||
gpio_set_mode(GPIOD, 9, GPIO_AF_OUTPUT_PP);// FSMC_D14
|
|
||||||
gpio_set_mode(GPIOD, 10, GPIO_AF_OUTPUT_PP); // FSMC_D15
|
|
||||||
|
|
||||||
gpio_set_mode(GPIOD, 4, GPIO_AF_OUTPUT_PP);// FSMC_NOE
|
|
||||||
gpio_set_mode(GPIOD, 5, GPIO_AF_OUTPUT_PP);// FSMC_NWE
|
|
||||||
|
|
||||||
gpio_set_mode(PIN_MAP[cs].gpio_device, PIN_MAP[cs].gpio_bit, GPIO_AF_OUTPUT_PP); //FSMC_CS_NEx
|
|
||||||
gpio_set_mode(PIN_MAP[rs].gpio_device, PIN_MAP[rs].gpio_bit, GPIO_AF_OUTPUT_PP); //FSMC_RS_Ax
|
|
||||||
|
|
||||||
fsmcPsramRegion->BCR = FSMC_BCR_WREN | FSMC_BCR_MTYP_SRAM | FSMC_BCR_MWID_16BITS | FSMC_BCR_MBKEN;
|
|
||||||
fsmcPsramRegion->BTR = (FSMC_DATA_SETUP_TIME << 8) | FSMC_ADDRESS_SETUP_TIME;
|
|
||||||
|
|
||||||
afio_remap(AFIO_REMAP_FSMC_NADV);
|
|
||||||
|
|
||||||
LCD = (LCD_CONTROLLER_TypeDef*)controllerAddress;
|
|
||||||
}
|
|
||||||
|
|
||||||
void LCD_IO_WriteData(uint16_t RegValue) {
|
|
||||||
LCD->RAM = RegValue;
|
|
||||||
__DSB();
|
|
||||||
}
|
|
||||||
|
|
||||||
void LCD_IO_WriteReg(uint16_t Reg) {
|
|
||||||
LCD->REG = Reg;
|
|
||||||
__DSB();
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t LCD_IO_ReadData(uint16_t RegValue) {
|
|
||||||
LCD->REG = RegValue;
|
|
||||||
__DSB();
|
|
||||||
|
|
||||||
return LCD->RAM;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t ILI9488_ReadRAM() {
|
|
||||||
uint16_t data;
|
|
||||||
data = LCD->RAM;
|
|
||||||
return data;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint32_t LCD_IO_ReadData(uint16_t RegValue, uint8_t ReadSize) {
|
|
||||||
volatile uint32_t data;
|
|
||||||
LCD->REG = RegValue;
|
|
||||||
__DSB();
|
|
||||||
|
|
||||||
data = LCD->RAM; // dummy read
|
|
||||||
data = LCD->RAM & 0x00FF;
|
|
||||||
|
|
||||||
while (--ReadSize) {
|
|
||||||
data <<= 8;
|
|
||||||
data |= (LCD->RAM & 0x00FF);
|
|
||||||
}
|
|
||||||
return uint32_t(data);
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef LCD_USE_DMA_FSMC
|
|
||||||
|
|
||||||
|
#ifdef LCD_USE_DMA_FSMC
|
||||||
void LCD_IO_WriteMultiple(uint16_t color, uint32_t count) {
|
void LCD_IO_WriteMultiple(uint16_t color, uint32_t count) {
|
||||||
while (count > 0) {
|
tftio.WriteMultiple(color, count);
|
||||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, &color, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM);
|
|
||||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, count > 65535 ? 65535 : count);
|
|
||||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
|
|
||||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {}
|
|
||||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
|
|
||||||
count = count > 65535 ? count - 65535 : 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length) {
|
void LCD_IO_WriteSequence(uint16_t *data, uint16_t length) {
|
||||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | DMA_PINC_MODE);
|
tftio.WriteSequence(data, length);
|
||||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, length);
|
|
||||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
|
|
||||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {}
|
|
||||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
}
|
}
|
||||||
|
#endif // LCD_USE_DMA_FSMC
|
||||||
|
|
||||||
void LCD_IO_WriteSequence_Async(uint16_t *data, uint16_t length) {
|
|
||||||
dma_setup_transfer(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, data, DMA_SIZE_16BITS, &LCD->RAM, DMA_SIZE_16BITS, DMA_MEM_2_MEM | DMA_PINC_MODE);
|
|
||||||
dma_set_num_transfers(FSMC_DMA_DEV, FSMC_DMA_CHANNEL, length);
|
|
||||||
dma_clear_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
dma_enable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
}
|
|
||||||
|
|
||||||
void LCD_IO_WaitSequence_Async() {
|
|
||||||
while ((dma_get_isr_bits(FSMC_DMA_DEV, FSMC_DMA_CHANNEL) & 0x0A) == 0) {}
|
|
||||||
dma_disable(FSMC_DMA_DEV, FSMC_DMA_CHANNEL);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif // LCD_USE_DMA_FSMC
|
|
||||||
|
|
||||||
#endif // ARDUINO_ARCH_STM32F1 && FSMC_CS_PIN
|
|
||||||
#endif // HAS_TFT_LVGL_UI
|
#endif // HAS_TFT_LVGL_UI
|
||||||
|
@ -42,9 +42,8 @@
|
|||||||
|
|
||||||
#include "../../../../inc/MarlinConfig.h"
|
#include "../../../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_TOUCH_XPT2046
|
#include HAL_PATH(../../HAL, tft/xpt2046.h)
|
||||||
#include "../../../touch/xpt2046.h"
|
XPT2046 touch;
|
||||||
#endif
|
|
||||||
|
|
||||||
#if ENABLED(POWER_LOSS_RECOVERY)
|
#if ENABLED(POWER_LOSS_RECOVERY)
|
||||||
#include "../../../../feature/powerloss.h"
|
#include "../../../../feature/powerloss.h"
|
||||||
@ -121,13 +120,13 @@ void tft_set_cursor(uint16_t x, uint16_t y) {
|
|||||||
|
|
||||||
void LCD_WriteRAM_Prepare(void) {
|
void LCD_WriteRAM_Prepare(void) {
|
||||||
#if 0
|
#if 0
|
||||||
if ((DeviceCode == 0x9325) || (DeviceCode == 0x9328) || (DeviceCode == 0x8989)) {
|
switch (DeviceCode) {
|
||||||
|
case 0x9325: case 0x9328: case 0x8989: {
|
||||||
ClrCs
|
ClrCs
|
||||||
LCD->LCD_REG = R34;
|
LCD->LCD_REG = R34;
|
||||||
SetCs
|
SetCs
|
||||||
}
|
} break;
|
||||||
else {
|
default: LCD_WrtReg(0x002C);
|
||||||
LCD_WrtReg(0x002C);
|
|
||||||
}
|
}
|
||||||
#else
|
#else
|
||||||
LCD_IO_WriteReg(0x002C);
|
LCD_IO_WriteReg(0x002C);
|
||||||
@ -197,8 +196,8 @@ void ili9320_SetWindows(uint16_t StartX, uint16_t StartY, uint16_t width, uint16
|
|||||||
LCD_WriteReg(0x0053, yEnd);*/
|
LCD_WriteReg(0x0053, yEnd);*/
|
||||||
LCD_WriteReg(0x0050, StartY); // Specify the start/end positions of the window address in the horizontal direction by an address unit
|
LCD_WriteReg(0x0050, StartY); // Specify the start/end positions of the window address in the horizontal direction by an address unit
|
||||||
LCD_WriteReg(0x0051, yEnd); // Specify the start positions of the window address in the vertical direction by an address unit
|
LCD_WriteReg(0x0051, yEnd); // Specify the start positions of the window address in the vertical direction by an address unit
|
||||||
LCD_WriteReg(0x0052, 320 - xEnd);
|
LCD_WriteReg(0x0052, (LCD_FULL_PIXEL_HEIGHT) - xEnd);
|
||||||
LCD_WriteReg(0x0053, 320 - StartX - 1); // Specify the end positions of the window address in the vertical direction by an address unit
|
LCD_WriteReg(0x0053, (LCD_FULL_PIXEL_HEIGHT) - StartX - 1); // Specify the end positions of the window address in the vertical direction by an address unit
|
||||||
|
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
@ -268,28 +267,10 @@ void LCD_Clear(uint16_t Color) {
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
extern uint16_t ILI9488_ReadRAM();
|
#include HAL_PATH(../../HAL, tft/tft_fsmc.h)
|
||||||
|
extern TFT_IO tftio;
|
||||||
void init_tft() {
|
void init_tft() {
|
||||||
uint16_t i;
|
uint16_t i;
|
||||||
//************* Start Initial Sequence **********//
|
|
||||||
|
|
||||||
//start lcd pins and dma
|
|
||||||
#if PIN_EXISTS(LCD_BACKLIGHT)
|
|
||||||
OUT_WRITE(LCD_BACKLIGHT_PIN, DISABLED(DELAYED_BACKLIGHT_INIT)); // Illuminate after reset or right away
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if PIN_EXISTS(LCD_RESET)
|
|
||||||
// Perform a clean hardware reset with needed delays
|
|
||||||
OUT_WRITE(LCD_RESET_PIN, LOW);
|
|
||||||
_delay_ms(5);
|
|
||||||
WRITE(LCD_RESET_PIN, HIGH);
|
|
||||||
_delay_ms(5);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if PIN_EXISTS(LCD_BACKLIGHT) && ENABLED(DELAYED_BACKLIGHT_INIT)
|
|
||||||
WRITE(LCD_BACKLIGHT_PIN, HIGH);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
TERN_(HAS_LCD_CONTRAST, refresh_contrast());
|
TERN_(HAS_LCD_CONTRAST, refresh_contrast());
|
||||||
|
|
||||||
@ -303,12 +284,9 @@ void init_tft() {
|
|||||||
|
|
||||||
_delay_ms(5);
|
_delay_ms(5);
|
||||||
|
|
||||||
LCD_IO_WriteReg(0x00D3);
|
DeviceCode = tftio.GetID() & 0xFFFF;
|
||||||
DeviceCode = ILI9488_ReadRAM(); //dummy read
|
// Chitu and others
|
||||||
DeviceCode = ILI9488_ReadRAM();
|
if (DeviceCode == 0x8066) DeviceCode = 0x9488;
|
||||||
DeviceCode = ILI9488_ReadRAM();
|
|
||||||
DeviceCode <<= 8;
|
|
||||||
DeviceCode |= ILI9488_ReadRAM();
|
|
||||||
|
|
||||||
if (DeviceCode == 0x9488) {
|
if (DeviceCode == 0x9488) {
|
||||||
LCD_IO_WriteReg(0x00E0);
|
LCD_IO_WriteReg(0x00E0);
|
||||||
@ -436,7 +414,7 @@ void tft_lvgl_init() {
|
|||||||
|
|
||||||
//spi_flash_read_test();
|
//spi_flash_read_test();
|
||||||
|
|
||||||
TERN_(HAS_TOUCH_XPT2046, touch.init());
|
touch.Init();
|
||||||
|
|
||||||
lv_init();
|
lv_init();
|
||||||
|
|
||||||
@ -492,35 +470,14 @@ void tft_lvgl_init() {
|
|||||||
void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) {
|
void my_disp_flush(lv_disp_drv_t * disp, const lv_area_t * area, lv_color_t * color_p) {
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
#if ENABLED(TFT_LVGL_UI_SPI)
|
||||||
uint16_t i, width, height;
|
uint16_t i, width, height;
|
||||||
uint16_t clr_temp;
|
|
||||||
uint8_t tbuf[(LCD_FULL_PIXEL_WIDTH) * 2];
|
|
||||||
|
|
||||||
SPI_TFT.spi_init(SPI_FULL_SPEED);
|
|
||||||
|
|
||||||
width = area->x2 - area->x1 + 1;
|
width = area->x2 - area->x1 + 1;
|
||||||
height = area->y2 - area->y1 + 1;
|
height = area->y2 - area->y1 + 1;
|
||||||
|
|
||||||
for (int j = 0; j < height; j++) {
|
SPI_TFT.SetWindows((uint16_t)area->x1, (uint16_t)area->y1, width, height);
|
||||||
SPI_TFT.SetCursor(0, 0);
|
for (i = 0; i < height; i++) {
|
||||||
SPI_TFT.SetWindows((uint16_t)area->x1, (uint16_t)area->y1 + j, width, 1);
|
SPI_TFT.tftio.WriteSequence((uint16_t*)(color_p + width * i), width);
|
||||||
SPI_TFT.LCD_WriteRAM_Prepare();
|
|
||||||
|
|
||||||
for (i = 0; i < width * 2;) {
|
|
||||||
clr_temp = (uint16_t)(((uint16_t)color_p->ch.red << 11)
|
|
||||||
| ((uint16_t)color_p->ch.green << 5)
|
|
||||||
| ((uint16_t)color_p->ch.blue));
|
|
||||||
|
|
||||||
tbuf[i] = clr_temp >> 8;
|
|
||||||
tbuf[i + 1] = clr_temp;
|
|
||||||
i += 2;
|
|
||||||
color_p++;
|
|
||||||
}
|
}
|
||||||
SPI_TFT_CS_L;
|
|
||||||
SPI_TFT_DC_H;
|
|
||||||
SPI.dmaSend(tbuf, width * 2, true);
|
|
||||||
SPI_TFT_CS_H;
|
|
||||||
}
|
|
||||||
|
|
||||||
lv_disp_flush_ready(disp); /* Indicate you are ready with the flushing*/
|
lv_disp_flush_ready(disp); /* Indicate you are ready with the flushing*/
|
||||||
|
|
||||||
W25QXX.init(SPI_QUARTER_SPEED);
|
W25QXX.init(SPI_QUARTER_SPEED);
|
||||||
@ -556,174 +513,23 @@ unsigned int getTickDiff(unsigned int curTick, unsigned int lastTick) {
|
|||||||
return TICK_CYCLE * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick));
|
return TICK_CYCLE * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick));
|
||||||
}
|
}
|
||||||
|
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
static bool get_point(int16_t *x, int16_t *y) {
|
||||||
|
bool is_touched = touch.getRawPoint(x, y);
|
||||||
|
|
||||||
#ifndef USE_XPT2046
|
if (is_touched) {
|
||||||
#define USE_XPT2046 1
|
*x = int16_t((int32_t(*x) * XPT2046_X_CALIBRATION) >> 16) + XPT2046_X_OFFSET;
|
||||||
#define XPT2046_XY_SWAP 1
|
*y = int16_t((int32_t(*y) * XPT2046_Y_CALIBRATION) >> 16) + XPT2046_Y_OFFSET;
|
||||||
#define XPT2046_X_INV 1
|
}
|
||||||
#define XPT2046_Y_INV 0
|
|
||||||
|
#if ENABLED(GRAPHICAL_TFT_ROTATE_180)
|
||||||
|
x = (LCD_FULL_PIXEL_WIDTH) - x;
|
||||||
|
y = (LCD_FULL_PIXEL_HEIGHT) - y;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if USE_XPT2046
|
return is_touched;
|
||||||
#define XPT2046_HOR_RES 480
|
|
||||||
#define XPT2046_VER_RES 320
|
|
||||||
#define XPT2046_X_MIN 201
|
|
||||||
#define XPT2046_Y_MIN 164
|
|
||||||
#define XPT2046_X_MAX 3919
|
|
||||||
#define XPT2046_Y_MAX 3776
|
|
||||||
#define XPT2046_AVG 4
|
|
||||||
#define XPT2046_INV 1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#else
|
|
||||||
|
|
||||||
#ifndef USE_XPT2046
|
|
||||||
#define USE_XPT2046 1
|
|
||||||
#ifndef XPT2046_XY_SWAP
|
|
||||||
#define XPT2046_XY_SWAP 1
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_X_INV
|
|
||||||
#define XPT2046_X_INV 0
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_Y_INV
|
|
||||||
#define XPT2046_Y_INV 1
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if USE_XPT2046
|
|
||||||
#ifndef XPT2046_HOR_RES
|
|
||||||
#define XPT2046_HOR_RES 480
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_VER_RES
|
|
||||||
#define XPT2046_VER_RES 320
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_X_MIN
|
|
||||||
#define XPT2046_X_MIN 201
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_Y_MIN
|
|
||||||
#define XPT2046_Y_MIN 164
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_X_MAX
|
|
||||||
#define XPT2046_X_MAX 3919
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_Y_MAX
|
|
||||||
#define XPT2046_Y_MAX 3776
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_AVG
|
|
||||||
#define XPT2046_AVG 4
|
|
||||||
#endif
|
|
||||||
#ifndef XPT2046_INV
|
|
||||||
#define XPT2046_INV 0
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static void xpt2046_corr(uint16_t *x, uint16_t *y) {
|
|
||||||
#if XPT2046_XY_SWAP
|
|
||||||
int16_t swap_tmp;
|
|
||||||
swap_tmp = *x;
|
|
||||||
*x = *y;
|
|
||||||
*y = swap_tmp;
|
|
||||||
#endif
|
|
||||||
if ((*x) > XPT2046_X_MIN) (*x) -= XPT2046_X_MIN; else (*x) = 0;
|
|
||||||
if ((*y) > XPT2046_Y_MIN) (*y) -= XPT2046_Y_MIN; else (*y) = 0;
|
|
||||||
(*x) = uint32_t(uint32_t(*x) * XPT2046_HOR_RES) / (XPT2046_X_MAX - XPT2046_X_MIN);
|
|
||||||
(*y) = uint32_t(uint32_t(*y) * XPT2046_VER_RES) / (XPT2046_Y_MAX - XPT2046_Y_MIN);
|
|
||||||
#if XPT2046_X_INV
|
|
||||||
(*x) = XPT2046_HOR_RES - (*x);
|
|
||||||
#endif
|
|
||||||
#if XPT2046_Y_INV
|
|
||||||
(*y) = XPT2046_VER_RES - (*y);
|
|
||||||
#endif
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#define times 4
|
static int16_t last_x = 0, last_y = 0;
|
||||||
#define CHX 0x90
|
|
||||||
#define CHY 0xD0
|
|
||||||
|
|
||||||
int SPI2_ReadWrite2Bytes(void) {
|
|
||||||
#define SPI_READ_WRITE_BYTE(B) TERN(TFT_LVGL_UI_SPI, SPI_TFT.spi_read_write_byte, W25QXX.spi_flash_read_write_byte)(B)
|
|
||||||
const uint16_t t1 = SPI_READ_WRITE_BYTE(0xFF),
|
|
||||||
t2 = SPI_READ_WRITE_BYTE(0xFF);
|
|
||||||
return (((t1 << 8) | t2) >> 3) & 0x0FFF;
|
|
||||||
}
|
|
||||||
|
|
||||||
uint16_t x_addata[times], y_addata[times];
|
|
||||||
void XPT2046_Rd_Addata(uint16_t *X_Addata, uint16_t *Y_Addata) {
|
|
||||||
uint16_t i, j, k;
|
|
||||||
|
|
||||||
TERN(TFT_LVGL_UI_SPI, SPI_TFT.spi_init, W25QXX.init)(SPI_SPEED_6);
|
|
||||||
|
|
||||||
for (i = 0; i < times; i++) {
|
|
||||||
#if ENABLED(TFT_LVGL_UI_SPI)
|
|
||||||
OUT_WRITE(TOUCH_CS_PIN, LOW);
|
|
||||||
SPI_TFT.spi_read_write_byte(CHX);
|
|
||||||
y_addata[i] = SPI2_ReadWrite2Bytes();
|
|
||||||
WRITE(TOUCH_CS_PIN, HIGH);
|
|
||||||
|
|
||||||
OUT_WRITE(TOUCH_CS_PIN, LOW);
|
|
||||||
SPI_TFT.spi_read_write_byte(CHY);
|
|
||||||
x_addata[i] = SPI2_ReadWrite2Bytes();
|
|
||||||
WRITE(TOUCH_CS_PIN, HIGH);
|
|
||||||
#else // #if HAS_TOUCH_XPT2046
|
|
||||||
OUT_WRITE(TOUCH_CS_PIN, LOW);
|
|
||||||
W25QXX.spi_flash_read_write_byte(CHX);
|
|
||||||
y_addata[i] = SPI2_ReadWrite2Bytes();
|
|
||||||
WRITE(TOUCH_CS_PIN, HIGH);
|
|
||||||
|
|
||||||
OUT_WRITE(TOUCH_CS_PIN, LOW);
|
|
||||||
W25QXX.spi_flash_read_write_byte(CHY);
|
|
||||||
x_addata[i] = SPI2_ReadWrite2Bytes();
|
|
||||||
WRITE(TOUCH_CS_PIN, HIGH);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
}
|
|
||||||
TERN(TFT_LVGL_UI_SPI,,W25QXX.init(SPI_QUARTER_SPEED));
|
|
||||||
|
|
||||||
for (i = 0; i < times; i++)
|
|
||||||
for (j = i + 1; j < times; j++)
|
|
||||||
if (x_addata[j] > x_addata[i]) {
|
|
||||||
k = x_addata[j];
|
|
||||||
x_addata[j] = x_addata[i];
|
|
||||||
x_addata[i] = k;
|
|
||||||
}
|
|
||||||
if (x_addata[times / 2 - 1] - x_addata[times / 2] > 50) {
|
|
||||||
*X_Addata = *Y_Addata = 0;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
*X_Addata = (x_addata[times / 2 - 1] + x_addata[times / 2]) / 2;
|
|
||||||
|
|
||||||
for (i = 0; i < times; i++)
|
|
||||||
for (j = i + 1; j < times; j++)
|
|
||||||
if (y_addata[j] > y_addata[i]) {
|
|
||||||
k = y_addata[j];
|
|
||||||
y_addata[j] = y_addata[i];
|
|
||||||
y_addata[i] = k;
|
|
||||||
}
|
|
||||||
|
|
||||||
if (y_addata[times / 2 - 1] - y_addata[times / 2] > 50) {
|
|
||||||
*X_Addata = *Y_Addata = 0;
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
*Y_Addata = (y_addata[times / 2 - 1] + y_addata[times / 2]) / 2;
|
|
||||||
}
|
|
||||||
|
|
||||||
#define ADC_VALID_OFFSET 10
|
|
||||||
|
|
||||||
uint8_t TOUCH_PressValid(uint16_t _usX, uint16_t _usY) {
|
|
||||||
if ( (_usX <= ADC_VALID_OFFSET)
|
|
||||||
|| (_usY <= ADC_VALID_OFFSET)
|
|
||||||
|| (_usX >= 4095 - ADC_VALID_OFFSET)
|
|
||||||
|| (_usY >= 4095 - ADC_VALID_OFFSET)
|
|
||||||
) return 0;
|
|
||||||
return 1;
|
|
||||||
}
|
|
||||||
|
|
||||||
static lv_coord_t last_x = 0, last_y = 0;
|
|
||||||
bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) {
|
bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) {
|
||||||
uint32_t tmpTime, diffTime = 0;
|
uint32_t tmpTime, diffTime = 0;
|
||||||
|
|
||||||
@ -735,34 +541,24 @@ bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) {
|
|||||||
//touchpad_get_xy(&last_x, &last_y);
|
//touchpad_get_xy(&last_x, &last_y);
|
||||||
/*Save the pressed coordinates and the state*/
|
/*Save the pressed coordinates and the state*/
|
||||||
if (diffTime > 10) {
|
if (diffTime > 10) {
|
||||||
//use marlin touch code if enabled
|
if (get_point(&last_x, &last_y)) {
|
||||||
#if HAS_TOUCH_XPT2046
|
|
||||||
touch.getTouchPoint(reinterpret_cast<uint16_t&>(last_x), reinterpret_cast<uint16_t&>(last_y));
|
|
||||||
#else
|
|
||||||
XPT2046_Rd_Addata((uint16_t *)&last_x, (uint16_t *)&last_y);
|
|
||||||
#endif
|
|
||||||
if (TOUCH_PressValid(last_x, last_y)) {
|
|
||||||
|
|
||||||
data->state = LV_INDEV_STATE_PR;
|
data->state = LV_INDEV_STATE_PR;
|
||||||
|
|
||||||
/* Set the coordinates (if released use the last pressed coordinates) */
|
// Set the coordinates (if released use the last-pressed coordinates)
|
||||||
|
|
||||||
// SERIAL_ECHOLNPAIR("antes X: ", last_x, ", y: ", last_y);
|
|
||||||
xpt2046_corr((uint16_t *)&last_x, (uint16_t *)&last_y);
|
|
||||||
// SERIAL_ECHOLNPAIR("X: ", last_x, ", y: ", last_y);
|
|
||||||
data->point.x = last_x;
|
data->point.x = last_x;
|
||||||
data->point.y = last_y;
|
data->point.y = last_y;
|
||||||
|
|
||||||
last_x = 0;
|
last_x = last_y = 0;
|
||||||
last_y = 0;
|
|
||||||
}
|
}
|
||||||
else {
|
else
|
||||||
data->state = LV_INDEV_STATE_REL;
|
data->state = LV_INDEV_STATE_REL;
|
||||||
}
|
|
||||||
touch_time1 = tmpTime;
|
touch_time1 = tmpTime;
|
||||||
}
|
}
|
||||||
|
|
||||||
return false; /*Return `false` because we are not buffering and no more data to read*/
|
return false; // Return `false` since no data is buffering or left to read
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif // HAS_TFT_LVGL_UI
|
#endif // HAS_TFT_LVGL_UI
|
||||||
|
@ -164,7 +164,6 @@
|
|||||||
#define HAS_LANG_SELECT_SCREEN 1
|
#define HAS_LANG_SELECT_SCREEN 1
|
||||||
#define HAS_BAK_VIEW_IN_FLASH 0
|
#define HAS_BAK_VIEW_IN_FLASH 0
|
||||||
#define HAS_LOGO_IN_FLASH 0
|
#define HAS_LOGO_IN_FLASH 0
|
||||||
#define HAS_TOUCH_XPT2046 1
|
|
||||||
|
|
||||||
#define TOUCH_CS_PIN PB7 // SPI1_NSS
|
#define TOUCH_CS_PIN PB7 // SPI1_NSS
|
||||||
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
||||||
@ -183,6 +182,8 @@
|
|||||||
|
|
||||||
#define LCD_RESET_PIN PF11
|
#define LCD_RESET_PIN PF11
|
||||||
#define LCD_BACKLIGHT_PIN PD13
|
#define LCD_BACKLIGHT_PIN PD13
|
||||||
|
#define TFT_RESET_PIN PF11
|
||||||
|
#define TFT_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
|
#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
|
||||||
#define FSMC_CS_PIN PD7
|
#define FSMC_CS_PIN PD7
|
||||||
@ -197,24 +198,10 @@
|
|||||||
#define LCD_PIXEL_OFFSET_X 48
|
#define LCD_PIXEL_OFFSET_X 48
|
||||||
#define LCD_PIXEL_OFFSET_Y 48
|
#define LCD_PIXEL_OFFSET_Y 48
|
||||||
|
|
||||||
#define XPT2046_X_CALIBRATION -12316
|
#define XPT2046_X_CALIBRATION -17181
|
||||||
#define XPT2046_Y_CALIBRATION 8981
|
#define XPT2046_Y_CALIBRATION 11434
|
||||||
#define XPT2046_X_OFFSET 340
|
#define XPT2046_X_OFFSET 501
|
||||||
#define XPT2046_Y_OFFSET -20
|
#define XPT2046_Y_OFFSET -9
|
||||||
|
|
||||||
#define USE_XPT2046 1
|
|
||||||
#define XPT2046_XY_SWAP 0
|
|
||||||
#define XPT2046_X_INV 1
|
|
||||||
#define XPT2046_Y_INV 0
|
|
||||||
|
|
||||||
#define XPT2046_HOR_RES 480
|
|
||||||
#define XPT2046_VER_RES 320
|
|
||||||
#define XPT2046_X_MIN 140
|
|
||||||
#define XPT2046_Y_MIN 200
|
|
||||||
#define XPT2046_X_MAX 1900
|
|
||||||
#define XPT2046_Y_MAX 1900
|
|
||||||
#define XPT2046_AVG 4
|
|
||||||
#define XPT2046_INV 0
|
|
||||||
|
|
||||||
#elif ENABLED(TFT_480x320)
|
#elif ENABLED(TFT_480x320)
|
||||||
#define TFT_RESET_PIN PF11
|
#define TFT_RESET_PIN PF11
|
||||||
|
@ -198,7 +198,6 @@
|
|||||||
#define HAS_LANG_SELECT_SCREEN 0
|
#define HAS_LANG_SELECT_SCREEN 0
|
||||||
#define HAS_BAK_VIEW_IN_FLASH 0
|
#define HAS_BAK_VIEW_IN_FLASH 0
|
||||||
#define HAS_LOGO_IN_FLASH 0
|
#define HAS_LOGO_IN_FLASH 0
|
||||||
#define HAS_TOUCH_XPT2046 1
|
|
||||||
|
|
||||||
#define TOUCH_CS_PIN PB7 // SPI1_NSS
|
#define TOUCH_CS_PIN PB7 // SPI1_NSS
|
||||||
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
#define TOUCH_SCK_PIN PA5 // SPI1_SCK
|
||||||
@ -217,6 +216,8 @@
|
|||||||
|
|
||||||
#define LCD_RESET_PIN PF11
|
#define LCD_RESET_PIN PF11
|
||||||
#define LCD_BACKLIGHT_PIN PD13
|
#define LCD_BACKLIGHT_PIN PD13
|
||||||
|
#define TFT_RESET_PIN PF11
|
||||||
|
#define TFT_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
|
#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
|
||||||
#define FSMC_CS_PIN PD7
|
#define FSMC_CS_PIN PD7
|
||||||
@ -231,24 +232,10 @@
|
|||||||
#define LCD_PIXEL_OFFSET_X 48
|
#define LCD_PIXEL_OFFSET_X 48
|
||||||
#define LCD_PIXEL_OFFSET_Y 48
|
#define LCD_PIXEL_OFFSET_Y 48
|
||||||
|
|
||||||
#define XPT2046_X_CALIBRATION -12316
|
#define XPT2046_X_CALIBRATION -17181
|
||||||
#define XPT2046_Y_CALIBRATION 8981
|
#define XPT2046_Y_CALIBRATION 11434
|
||||||
#define XPT2046_X_OFFSET 340
|
#define XPT2046_X_OFFSET 501
|
||||||
#define XPT2046_Y_OFFSET -20
|
#define XPT2046_Y_OFFSET -9
|
||||||
|
|
||||||
#define USE_XPT2046 1
|
|
||||||
#define XPT2046_XY_SWAP 0
|
|
||||||
#define XPT2046_X_INV 1
|
|
||||||
#define XPT2046_Y_INV 0
|
|
||||||
|
|
||||||
#define XPT2046_HOR_RES 480
|
|
||||||
#define XPT2046_VER_RES 320
|
|
||||||
#define XPT2046_X_MIN 140
|
|
||||||
#define XPT2046_Y_MIN 200
|
|
||||||
#define XPT2046_X_MAX 1900
|
|
||||||
#define XPT2046_Y_MAX 1900
|
|
||||||
#define XPT2046_AVG 4
|
|
||||||
#define XPT2046_INV 0
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available
|
// SPI1(PA7)=LCD & SPI3(PB5)=STUFF, are not available
|
||||||
|
@ -177,6 +177,17 @@
|
|||||||
|
|
||||||
#define LCD_BACKLIGHT_PIN PD13
|
#define LCD_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
|
#define XPT2046_X_CALIBRATION 17880
|
||||||
|
#define XPT2046_Y_CALIBRATION -12234
|
||||||
|
#define XPT2046_X_OFFSET -45
|
||||||
|
#define XPT2046_Y_OFFSET 349
|
||||||
|
|
||||||
|
#define LCD_USE_DMA_FSMC // Use DMA transfers to send data to the TFT
|
||||||
|
#define FSMC_CS_PIN PD7
|
||||||
|
#define FSMC_RS_PIN PD11
|
||||||
|
#define FSMC_DMA_DEV DMA2
|
||||||
|
#define FSMC_DMA_CHANNEL DMA_CH5
|
||||||
|
|
||||||
#elif ENABLED(FSMC_GRAPHICAL_TFT)
|
#elif ENABLED(FSMC_GRAPHICAL_TFT)
|
||||||
|
|
||||||
#define DOGLCD_MOSI -1 // prevent redefine Conditionals_post.h
|
#define DOGLCD_MOSI -1 // prevent redefine Conditionals_post.h
|
||||||
|
@ -261,17 +261,30 @@
|
|||||||
#define BTN_EN2 PE11
|
#define BTN_EN2 PE11
|
||||||
#define BTN_ENC PE13
|
#define BTN_ENC PE13
|
||||||
|
|
||||||
#elif ENABLED(TFT_LITTLE_VGL_UI)
|
#define TFT_CS_PIN PD11
|
||||||
|
#define TFT_SCK_PIN PA5
|
||||||
|
#define TFT_MISO_PIN PA6
|
||||||
|
#define TFT_MOSI_PIN PA7
|
||||||
|
#define TFT_DC_PIN PD10
|
||||||
|
#define TFT_RST_PIN PC6
|
||||||
|
#define TFT_A0_PIN TFT_DC_PIN
|
||||||
|
|
||||||
#define FSMC_CS_PIN PD7 // NE4
|
#define TFT_RESET_PIN PC6
|
||||||
#define FSMC_RS_PIN PD11 // A0
|
#define TFT_BACKLIGHT_PIN PD13
|
||||||
|
|
||||||
#define TOUCH_CS_PIN PA7 // SPI2_NSS
|
#define XPT2046_X_CALIBRATION -17253
|
||||||
#define TOUCH_SCK_PIN PB13 // SPI2_SCK
|
#define XPT2046_Y_CALIBRATION 11579
|
||||||
#define TOUCH_MISO_PIN PB14 // SPI2_MISO
|
#define XPT2046_X_OFFSET 514
|
||||||
#define TOUCH_MOSI_PIN PB15 // SPI2_MOSI
|
#define XPT2046_Y_OFFSET -24
|
||||||
|
#define TOUCH_BUTTONS_HW_SPI
|
||||||
|
#define TOUCH_BUTTONS_HW_SPI_DEVICE 1
|
||||||
|
|
||||||
#define LCD_BACKLIGHT_PIN PD13
|
#ifndef LCD_FULL_PIXEL_WIDTH
|
||||||
|
#define LCD_FULL_PIXEL_WIDTH 480
|
||||||
|
#endif
|
||||||
|
#ifndef LCD_FULL_PIXEL_HEIGHT
|
||||||
|
#define LCD_FULL_PIXEL_HEIGHT 320
|
||||||
|
#endif
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
Loading…
Reference in New Issue
Block a user