Skip to content

Commit

Permalink
Minor cleanup (#2893)
Browse files Browse the repository at this point in the history
  • Loading branch information
digant73 committed Feb 20, 2024
1 parent 6de2f3a commit 7c430b3
Show file tree
Hide file tree
Showing 31 changed files with 116 additions and 107 deletions.
14 changes: 8 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -90,9 +90,9 @@ Only the TFTs listed below are currently supported. Trying to install the firmwa
MKS_TFT32L_V3.0
MKS_TFT35_V1.0

**MKS TFT with GigaDevice MCUs**
**MKS GD TFT**

MKS_GD_TFT28_V1_2_4
MKS_GD_TFT28_V1.2-4 (V1.2 and V1.4)

**WARNING:** BTT does not officially provide MKS TFT hardware support. MKS TFT is maintained by open source contributors and BTT does not bear any risk of MKS TFT hardware using this firmware.

Expand Down Expand Up @@ -255,11 +255,12 @@ For **MKS TFTs**:
1. The firmwares use the naming convention `MKS_TFT*_V*.*.*.x.bin`
2. Any binary file for an MKS firmware (e.g. `MKS_TFT28_V4.0.27.x.bin`) **MUST** be renamed to `MKSTFT*.bin` (e.g. `MKSTFT28.bin`, `MKSTFT35.bin` etc.) in order it can be recognized and installed by the TFT

For MKS TFTs **GigaDevice MCUs** (like the newest version of Genious Pro):
For **MKS GD TFTs**:

1. rename the right binary (e.g. `MKS_GD_TFT28_V1_2_4.27.x.bin`) in `mkstft28evo.bin`
2. create an empty `mkstft28.bin` file
3. create two empty directories `mks_font` and `mks_pic`
For MKS TFT28 mounting GD32 MCU (GigaDevice MCU) (like the newest version of Genious Pro), you need to:
1. Rename the right binary (e.g. `MKS_GD_TFT28_V1_2_4.27.x.bin`) to `MKSTFT28EVO.bin`
2. Create an empty file named `MKSTFT28.bin`
3. Create two empty directories named `MKS_FONT` and `MKS_PIC`

For example, for BTT TFT35 V3 select:

Expand Down Expand Up @@ -489,6 +490,7 @@ Please, see [Customization Guides](https://github.com/bigtreetech/BIGTREETECH-To
;MKS_TFT32_V1_4_NOBL
;MKS_TFT32L_V3_0
;MKS_TFT35_V1_0

;MKS_GD_TFT28_V1_2_4

[platformio]
Expand Down
8 changes: 4 additions & 4 deletions TFT/src/User/API/HW_Init.c
Original file line number Diff line number Diff line change
Expand Up @@ -7,7 +7,7 @@

void HW_GetClocksFreq(CLOCKS *clk)
{
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
RCU_GetClocksFreq(&clk->rccClocks);
#else
RCC_GetClocksFreq(&clk->rccClocks);
Expand All @@ -28,7 +28,7 @@ void HW_Init(void)
{
HW_GetClocksFreq(&mcuClocks);

#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
nvic_priority_group_set(NVIC_PRIGROUP_PRE2_SUB2);
#else
NVIC_PriorityGroupConfig(NVIC_PriorityGroup_2);
Expand All @@ -45,10 +45,10 @@ void HW_Init(void)
#endif

#if defined(MKS_TFT) && !defined(MKS_TFT35_V1_0) // not used by MKS_TFT35_V1_0
#if defined (GD32F3XX)
#ifdef GD32F3XX
rcu_periph_clock_enable(RCU_AF);
gpio_pin_remap_config(GPIO_USART1_REMAP, ENABLE);
#else
#else // if STM32F<xxx>
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
GPIO_PinRemapConfig(GPIO_Remap_USART2, ENABLE);
#endif
Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/API/Mainboard_FlowControl.c
Original file line number Diff line number Diff line change
Expand Up @@ -76,7 +76,7 @@ void loopBackEnd(void)
if (infoMachineSettings.onboardSD == ENABLED)
loopPrintFromOnboard();

// Buzzer handling
// buzzer handling
#ifdef BUZZER_PIN
loopBuzzer();
#endif
Expand Down
6 changes: 3 additions & 3 deletions TFT/src/User/Hal/HD44780.c
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ CIRCULAR_QUEUE *HD44780_queue = NULL;

void HD44780_DeConfig(void)
{
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
nvic_irq_disable(EXTI10_15_IRQn);
#else
NVIC_InitTypeDef NVIC_InitStructure;
Expand Down Expand Up @@ -49,7 +49,7 @@ void HD44780_Config(CIRCULAR_QUEUE *queue)
GPIO_InitSet(LCD_D4, MGPIO_MODE_IPD, 0);
GPIO_InitSet(LCD_RS, MGPIO_MODE_IPD, 0);

#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
gpio_exti_source_select(GPIO_EVENT_PORT_GPIOB, GPIO_EVENT_PIN_15);

exti_init(EXTI_15, EXTI_INTERRUPT, EXTI_TRIG_RISING);
Expand Down Expand Up @@ -86,7 +86,7 @@ void HD44780_Config(CIRCULAR_QUEUE *queue)
bool HD44780_writeData(void)
{
bool dataWritten = false;
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
if ((GPIO_ISTAT(GPIOB) & (1 << 15)) != 0)
{
uint8_t temp = ((GPIO_ISTAT(LCD_D7_PORT) & GPIO_PIN_6) >> 3 ) + // D7
Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/Hal/Knob_LED.c
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@ uint32_t frameTimeStamp = 0; // Frame unit need > 280us for WS2812
#define NEOPIXEL_T0H_US 0.35 // Neopixel code 0 high level hold time in us
#define NEOPIXEL_T1H_US 2.15 // Neopixel code 1 high level hold time in us

#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
#define NEOPIXEL_TIMER_CLOCK_ENABLE() rcu_periph_clock_enable(RCU_TIMER5)
#define NEOPIXEL_TIMER_CNT() TIMER_CNT(TIMER5)
#define NEOPIXEL_TIMER_PSC() TIMER_PSC(TIMER5)
Expand Down
8 changes: 4 additions & 4 deletions TFT/src/User/Hal/buzzer.c
Original file line number Diff line number Diff line change
Expand Up @@ -21,7 +21,7 @@ volatile uint32_t toggles = 0;

void TIM3_Config(void)
{
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
nvic_irq_enable(TIMER2_IRQn, 1U, 0U);

rcu_periph_clock_enable(RCU_TIMER2);
Expand All @@ -46,7 +46,7 @@ void TIM3_Config(void)
#endif
}

#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
void TIMER2_IRQHandler(void)
{
if ((TIMER_INTF(TIMER2) & TIMER_INTF_UPIF) != 0) // update interrupt flag
Expand Down Expand Up @@ -108,7 +108,7 @@ void Buzzer_TurnOn(const uint16_t frequency, const uint16_t duration)
void tone(const uint16_t frequency, const uint16_t duration)
{
if (frequency == 0 || duration == 0) return;
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
nvic_irq_disable(TIMER2_IRQn);
toggles = 2 * (frequency * duration / 1000); // must have an even value

Expand Down Expand Up @@ -147,7 +147,7 @@ void loopBuzzer(void)
else if (OS_GetTimeMs() > buzzerEndTime && toggles == 0)
{
buzzerEndTime = 0;
#if defined GD32F2XX || defined GD32F3XX
#if defined(GD32F2XX) || defined(GD32F3XX)
TIMER_CTL0(TIMER2) &= ~TIMER_CTL0_CEN;
#else
TIM3->CR1 &= ~TIM_CR1_CEN; // stop timer (for safety)
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Hal/gd32f30x/lcd.c
Original file line number Diff line number Diff line change
Expand Up @@ -59,8 +59,8 @@ void LCD_GPIO_Config(void)

void LCD_EXMC_Config(void)
{
exmc_norsram_parameter_struct EXMC_NORSRAMInitStructure;
exmc_norsram_timing_parameter_struct readWriteTiming,writeTiming; ;
exmc_norsram_parameter_struct EXMC_NORSRAMInitStructure;
exmc_norsram_timing_parameter_struct readWriteTiming,writeTiming;

/* EXMC configuration */
readWriteTiming.asyn_address_setuptime = 1U;
Expand Down
34 changes: 17 additions & 17 deletions TFT/src/User/Hal/gd32f30x/lcd.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,25 +20,25 @@

#else
#if defined(MKS_TFT)
/*
#define LCD_WR PB14
#define LCD_RS PD13
#define LCD_CS PC8
#define LCD_RD PD15
*/
// GPIO_SetLevel
#define LCD_CS_SET gpio_bit_set(GPIOC, GPIO_PIN_8 ) // Chip Select Port PC8 //片选端口
#define LCD_RS_SET gpio_bit_set(GPIOD, GPIO_PIN_13) // Data / command PD13 //数据/命令
#define LCD_WR_SET gpio_bit_set(GPIOB, GPIO_PIN_14) // Write data PB14 //写数据
#define LCD_RD_SET gpio_bit_set(GPIOD, GPIO_PIN_15) // Read data PD15 //读数据

#define LCD_CS_CLR gpio_bit_reset(GPIOC, GPIO_PIN_8) // Chip select port PC8 //片选端口
#define LCD_RS_CLR gpio_bit_reset(GPIOD, GPIO_PIN_13) // Data / command PD13 //数据/命令
#define LCD_WR_CLR gpio_bit_reset(GPIOB, GPIO_PIN_14) // Write data PB14 //写数据
#define LCD_RD_CLR gpio_bit_reset(GPIOD, GPIO_PIN_15) // Read data PD15 //读数据
/*
#define LCD_WR PB14
#define LCD_RS PD13
#define LCD_CS PC8
#define LCD_RD PD15
*/
// GPIO_SetLevel
#define LCD_CS_SET gpio_bit_set(GPIOC, GPIO_PIN_8 ) // Chip Select Port PC8 //片选端口
#define LCD_RS_SET gpio_bit_set(GPIOD, GPIO_PIN_13) // Data / command PD13 //数据/命令
#define LCD_WR_SET gpio_bit_set(GPIOB, GPIO_PIN_14) // Write data PB14 //写数据
#define LCD_RD_SET gpio_bit_set(GPIOD, GPIO_PIN_15) // Read data PD15 //读数据

#define LCD_CS_CLR gpio_bit_reset(GPIOC, GPIO_PIN_8) // Chip select port PC8 //片选端口
#define LCD_RS_CLR gpio_bit_reset(GPIOD, GPIO_PIN_13) // Data / command PD13 //数据/命令
#define LCD_WR_CLR gpio_bit_reset(GPIOB, GPIO_PIN_14) // Write data PB14 //写数据
#define LCD_RD_CLR gpio_bit_reset(GPIOD, GPIO_PIN_15) // Read data PD15 //读数据

#define DATAOUT(x) do{gpio_port_write(GPIOE, x);}while(0) // Data output //数据输出
#define DATAIN() gpio_input_port_get(GPIOE) // Data input //数据输入
#define DATAIN() gpio_input_port_get(GPIOE) // Data input //数据输入
#else
#error "don't support LCD-GPIO yet"
#endif
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Hal/gd32f30x/uart.c
Original file line number Diff line number Diff line change
Expand Up @@ -78,7 +78,7 @@ void UART_GPIO_DeInit(uint8_t port)
GPIO_InitSet(uart_rx[port], MGPIO_MODE_IPN, 0);
}

void UART_Protocol_Init(uint8_t port,uint32_t baud)
void UART_Protocol_Init(uint8_t port, uint32_t baud)
{
rcu_periph_clock_enable(rcu_uart_en[port]); // Enable clock

Expand All @@ -96,7 +96,7 @@ void UART_Protocol_Init(uint8_t port,uint32_t baud)

void UART_IRQ_Init(uint8_t port, uint16_t usart_it, bool idle_interrupt)
{
uint32_t IRQ_Channel[_UART_CNT] = {USART0_IRQn, USART1_IRQn, USART2_IRQn, UART3_IRQn, UART4_IRQn };
uint32_t IRQ_Channel[_UART_CNT] = {USART0_IRQn, USART1_IRQn, USART2_IRQn, UART3_IRQn, UART4_IRQn};
nvic_irq_enable(IRQ_Channel[port], 0U, 0U);

if (idle_interrupt) // enable or disable serial line IDLE interrupt
Expand Down
10 changes: 5 additions & 5 deletions TFT/src/User/Hal/gd32f30x/uart.h
Original file line number Diff line number Diff line change
Expand Up @@ -4,11 +4,11 @@
#include <stdbool.h>
#include <stdint.h>

#define _USART1 0 // USART0
#define _USART2 1 // USART1
#define _USART3 2 // USART2
#define _UART4 3 // UART3
#define _UART5 4 // UART4
#define _USART1 0 // USART0
#define _USART2 1 // USART1
#define _USART3 2 // USART2
#define _UART4 3 // UART3
#define _UART5 4 // UART4
#define _USART6 5
#define _UART_CNT 6

Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/Variants/pin_GD_TFT35_V3_0.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef _PIN_GD_TFT35_V3_0_H_ // modify to actual filename !!!
#define _PIN_GD_TFT35_V3_0_H_ // modify to actual filename !!!

// MCU type (STM32F10x, STM32F2xx, STM32F4xx, gd32f20x, gd32f30x)
// MCU type (STM32F10x, STM32F2xx, STM32F4xx, GD32F20x, GD32F30x)
#ifndef MCU_TYPE
#define MCU_TYPE
#include "gd32f20x.h"
Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/Variants/pin_GD_TFT43_V3_0.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#endif

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER SSD1963
#define TFTLCD_DRIVER_SPEED 0x10 // SSD1963 needs slower speed
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef _PIN_MKS_GD_TFT28_V1_24_H_ // modify to actual filename !!!
#define _PIN_MKS_GD_TFT28_V1_24_H_ // modify to actual filename !!!
#ifndef _PIN_MKS_GD_TFT28_V1_2_4_H_ // modify to actual filename !!!
#define _PIN_MKS_GD_TFT28_V1_2_4_H_ // modify to actual filename !!!

// MCU type (STM32F10x, STM32F2xx, STM32F4xx, gd32f20x, gd32f30x)
// MCU type (STM32F10x, STM32F2xx, STM32F4xx, GD32F20x, GD32F30x)
#ifndef MCU_TYPE
#define MCU_TYPE
#include "gd32f30x.h"
Expand All @@ -14,14 +14,7 @@

// Hardware version config
#ifndef HARDWARE_VERSION
#define HARDWARE_VERSION "GD_TFT28_V4.0"
#endif

// USB Disk support
#ifndef USB_FLASH_DRIVE_SUPPORT
#define USB_FLASH_DRIVE_SUPPORT
#define USE_USB_FS
#define USE_USB_OTG_FS
#define HARDWARE_VERSION "GD_TFT28_V1.2-4"
#endif

// SERIAL_PORT: communicating with host (Marlin, RRF etc...)
Expand All @@ -37,6 +30,13 @@
#define SERIAL_PORT_4 _UART4
#endif

// USB Disk support
#ifndef USB_FLASH_DRIVE_SUPPORT
#define USB_FLASH_DRIVE_SUPPORT
#define USE_USB_FS
#define USE_USB_OTG_FS
#endif

#include "pin_MKS_TFT32_V1_4.h"

#endif
2 changes: 1 addition & 1 deletion TFT/src/User/Variants/pin_MKS_TFT32_V1_3.h
Original file line number Diff line number Diff line change
Expand Up @@ -11,7 +11,7 @@
#endif

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER ILI9325
#endif
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Variants/pin_MKS_TFT32_V1_4.h
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,7 @@
#define W25Qxx_CS_PIN PB9

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER HX8558
#endif
Expand Down Expand Up @@ -209,7 +209,7 @@
#endif

// LCD Encoder pins + Marlin mode
#ifdef ST7920_EMULATOR
#if defined(ST7920_EMULATOR) && !defined(GD32F3XX)
// Free JTAG (PB3/PB4) for SPI3 and free SWDIO, PA13, PA14 for encoder pins
#define DISABLE_DEBUG() RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE); \
GPIO_PinRemapConfig(GPIO_Remap_SWJ_Disable, ENABLE)
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Variants/pin_MKS_TFT35_V1_0.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef _PIN_TFT35_V1_0_H_ // modify to actual filename !!!
#define _PIN_TFT35_V1_0_H_ // modify to actual filename !!!

// MCU type (STM32F10x, STM32F2xx, STM32F4xx, gd32f20x, gd32f30x)
// MCU type (STM32F10x, STM32F2xx, STM32F4xx, GD32F20x, GD32F30x)
#ifndef MCU_TYPE
#define MCU_TYPE
#include "stm32f4xx.h"
Expand Down Expand Up @@ -59,7 +59,7 @@
#define W25Qxx_CS_PIN PB9

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER (ILI9488 | NT35310)
#define TFTLCD_DRIVER_SPEED 0x03 // testing, was 0x10
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Variants/pin_TFT24_V1_1.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef _PIN_TFT24_V1_1_H_ // modify to actual filename !!!
#define _PIN_TFT24_V1_1_H_ // modify to actual filename !!!

// MCU type (STM32F10x, STM32F2xx, STM32F4xx, gd32f20x, gd32f30x)
// MCU type (STM32F10x, STM32F2xx, STM32F4xx, GD32F20x, GD32F30x)
#ifndef MCU_TYPE
#define MCU_TYPE
#include "stm32f10x.h"
Expand Down Expand Up @@ -60,7 +60,7 @@
#define W25Qxx_CS_PIN PD2

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER ILI9341
#define TFTLCD_DRIVER_SPEED 0x03
Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/Variants/pin_TFT28_V1_0.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#endif

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER ILI9341
#define TFTLCD_DRIVER_SPEED 0x03
Expand Down
2 changes: 1 addition & 1 deletion TFT/src/User/Variants/pin_TFT28_V3_0.h
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@
#endif

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER ST7789
#define TFTLCD_DRIVER_SPEED 0x05
Expand Down
4 changes: 2 additions & 2 deletions TFT/src/User/Variants/pin_TFT35_V1_0.h
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
#ifndef _PIN_TFT35_V1_0_H_ // modify to actual filename !!!
#define _PIN_TFT35_V1_0_H_ // modify to actual filename !!!

// MCU type (STM32F10x, STM32F2xx, STM32F4xx, gd32f20x, gd32f30x)
// MCU type (STM32F10x, STM32F2xx, STM32F4xx, GD32F20x, GD32F30x)
#ifndef MCU_TYPE
#define MCU_TYPE
#include "stm32f10x.h"
Expand Down Expand Up @@ -55,7 +55,7 @@
#define W25Qxx_CS_PIN PA4

// LCD interface
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558]
// Supported LCD drivers: [ST7789, SSD1963, RM68042, NT35310, ILI9488, ILI9341, ILI9325, HX8558, ST7796S]
#ifndef TFTLCD_DRIVER
#define TFTLCD_DRIVER RM68042
#define TFTLCD_DRIVER_SPEED 0x03
Expand Down
Loading

0 comments on commit 7c430b3

Please sign in to comment.