BTT SKR-SE-BX (STM32H743IIT6 ARM Cortex M7) and BIQU_BX_TFT70 (#21536)
This commit is contained in:
parent
ee21e31a17
commit
2c73964b2b
1
.github/workflows/test-builds.yml
vendored
1
.github/workflows/test-builds.yml
vendored
|
@ -89,6 +89,7 @@ jobs:
|
||||||
- mks_robin_nano35_stm32
|
- mks_robin_nano35_stm32
|
||||||
- NUCLEO_F767ZI
|
- NUCLEO_F767ZI
|
||||||
- REMRAM_V1
|
- REMRAM_V1
|
||||||
|
- BTT_SKR_SE_BX
|
||||||
|
|
||||||
# Put lengthy tests last
|
# Put lengthy tests last
|
||||||
|
|
||||||
|
|
|
@ -2496,6 +2496,11 @@
|
||||||
//
|
//
|
||||||
//#define ANET_ET5_TFT35
|
//#define ANET_ET5_TFT35
|
||||||
|
|
||||||
|
//
|
||||||
|
// 1024x600, 7", RGB Stock Display from BIQU-BX
|
||||||
|
//
|
||||||
|
//#define BIQU_BX_TFT70
|
||||||
|
|
||||||
//
|
//
|
||||||
// Generic TFT with detailed options
|
// Generic TFT with detailed options
|
||||||
//
|
//
|
||||||
|
|
|
@ -19,7 +19,7 @@
|
||||||
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
* along with this program. If not, see <https://www.gnu.org/licenses/>.
|
||||||
*
|
*
|
||||||
*/
|
*/
|
||||||
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
|
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC) && !defined(STM32H7xx)
|
||||||
|
|
||||||
#include "MarlinSPI.h"
|
#include "MarlinSPI.h"
|
||||||
|
|
||||||
|
|
|
@ -52,6 +52,6 @@
|
||||||
#error "SERIAL_STATS_DROPPED_RX is not supported on STM32."
|
#error "SERIAL_STATS_DROPPED_RX is not supported on STM32."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32F4xx, STM32F1xx)
|
#if ANY(TFT_COLOR_UI, TFT_LVGL_UI, TFT_CLASSIC_UI) && NOT_TARGET(STM32H7xx, STM32F4xx, STM32F1xx)
|
||||||
#error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32F4 and STM32F1 hardware."
|
#error "TFT_COLOR_UI, TFT_LVGL_UI and TFT_CLASSIC_UI are currently only supported on STM32H7, STM32F4 and STM32F1 hardware."
|
||||||
#endif
|
#endif
|
||||||
|
|
390
Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
Normal file
390
Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
Normal file
|
@ -0,0 +1,390 @@
|
||||||
|
/**
|
||||||
|
* 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 HAS_LTDC_TFT
|
||||||
|
|
||||||
|
#include "tft_ltdc.h"
|
||||||
|
#include "pinconfig.h"
|
||||||
|
|
||||||
|
#define FRAME_BUFFER_ADDRESS 0XC0000000 // SDRAM address
|
||||||
|
|
||||||
|
#define SDRAM_TIMEOUT ((uint32_t)0xFFFF)
|
||||||
|
#define REFRESH_COUNT ((uint32_t)0x02A5) // SDRAM refresh counter
|
||||||
|
|
||||||
|
#define SDRAM_MODEREG_BURST_LENGTH_1 ((uint16_t)0x0000)
|
||||||
|
#define SDRAM_MODEREG_BURST_LENGTH_2 ((uint16_t)0x0001)
|
||||||
|
#define SDRAM_MODEREG_BURST_LENGTH_4 ((uint16_t)0x0002)
|
||||||
|
#define SDRAM_MODEREG_BURST_LENGTH_8 ((uint16_t)0x0004)
|
||||||
|
#define SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL ((uint16_t)0x0000)
|
||||||
|
#define SDRAM_MODEREG_BURST_TYPE_INTERLEAVED ((uint16_t)0x0008)
|
||||||
|
#define SDRAM_MODEREG_CAS_LATENCY_2 ((uint16_t)0x0020)
|
||||||
|
#define SDRAM_MODEREG_CAS_LATENCY_3 ((uint16_t)0x0030)
|
||||||
|
#define SDRAM_MODEREG_OPERATING_MODE_STANDARD ((uint16_t)0x0000)
|
||||||
|
#define SDRAM_MODEREG_WRITEBURST_MODE_PROGRAMMED ((uint16_t)0x0000)
|
||||||
|
#define SDRAM_MODEREG_WRITEBURST_MODE_SINGLE ((uint16_t)0x0200)
|
||||||
|
|
||||||
|
|
||||||
|
void SDRAM_Initialization_Sequence(SDRAM_HandleTypeDef *hsdram, FMC_SDRAM_CommandTypeDef *Command) {
|
||||||
|
|
||||||
|
__IO uint32_t tmpmrd =0;
|
||||||
|
/* Step 1: Configure a clock configuration enable command */
|
||||||
|
Command->CommandMode = FMC_SDRAM_CMD_CLK_ENABLE;
|
||||||
|
Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
|
||||||
|
Command->AutoRefreshNumber = 1;
|
||||||
|
Command->ModeRegisterDefinition = 0;
|
||||||
|
/* Send the command */
|
||||||
|
HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
|
||||||
|
|
||||||
|
/* Step 2: Insert 100 us minimum delay */
|
||||||
|
/* Inserted delay is equal to 1 ms due to systick time base unit (ms) */
|
||||||
|
HAL_Delay(1);
|
||||||
|
|
||||||
|
/* Step 3: Configure a PALL (precharge all) command */
|
||||||
|
Command->CommandMode = FMC_SDRAM_CMD_PALL;
|
||||||
|
Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
|
||||||
|
Command->AutoRefreshNumber = 1;
|
||||||
|
Command->ModeRegisterDefinition = 0;
|
||||||
|
/* Send the command */
|
||||||
|
HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
|
||||||
|
|
||||||
|
/* Step 4 : Configure a Auto-Refresh command */
|
||||||
|
Command->CommandMode = FMC_SDRAM_CMD_AUTOREFRESH_MODE;
|
||||||
|
Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
|
||||||
|
Command->AutoRefreshNumber = 8;
|
||||||
|
Command->ModeRegisterDefinition = 0;
|
||||||
|
/* Send the command */
|
||||||
|
HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
|
||||||
|
|
||||||
|
/* Step 5: Program the external memory mode register */
|
||||||
|
tmpmrd = (uint32_t)(SDRAM_MODEREG_BURST_LENGTH_1 |
|
||||||
|
SDRAM_MODEREG_BURST_TYPE_SEQUENTIAL |
|
||||||
|
SDRAM_MODEREG_CAS_LATENCY_2 |
|
||||||
|
SDRAM_MODEREG_OPERATING_MODE_STANDARD |
|
||||||
|
SDRAM_MODEREG_WRITEBURST_MODE_SINGLE);
|
||||||
|
|
||||||
|
Command->CommandMode = FMC_SDRAM_CMD_LOAD_MODE;
|
||||||
|
Command->CommandTarget = FMC_SDRAM_CMD_TARGET_BANK1;
|
||||||
|
Command->AutoRefreshNumber = 1;
|
||||||
|
Command->ModeRegisterDefinition = tmpmrd;
|
||||||
|
/* Send the command */
|
||||||
|
HAL_SDRAM_SendCommand(hsdram, Command, SDRAM_TIMEOUT);
|
||||||
|
|
||||||
|
/* Step 6: Set the refresh rate counter */
|
||||||
|
/* Set the device refresh rate */
|
||||||
|
HAL_SDRAM_ProgramRefreshRate(hsdram, REFRESH_COUNT);
|
||||||
|
}
|
||||||
|
|
||||||
|
void SDRAM_Config() {
|
||||||
|
|
||||||
|
__HAL_RCC_SYSCFG_CLK_ENABLE();
|
||||||
|
__HAL_RCC_FMC_CLK_ENABLE();
|
||||||
|
|
||||||
|
SDRAM_HandleTypeDef hsdram;
|
||||||
|
FMC_SDRAM_TimingTypeDef SDRAM_Timing;
|
||||||
|
FMC_SDRAM_CommandTypeDef command;
|
||||||
|
|
||||||
|
/* Configure the SDRAM device */
|
||||||
|
hsdram.Instance = FMC_SDRAM_DEVICE;
|
||||||
|
hsdram.Init.SDBank = FMC_SDRAM_BANK1;
|
||||||
|
hsdram.Init.ColumnBitsNumber = FMC_SDRAM_COLUMN_BITS_NUM_9;
|
||||||
|
hsdram.Init.RowBitsNumber = FMC_SDRAM_ROW_BITS_NUM_13;
|
||||||
|
hsdram.Init.MemoryDataWidth = FMC_SDRAM_MEM_BUS_WIDTH_16;
|
||||||
|
hsdram.Init.InternalBankNumber = FMC_SDRAM_INTERN_BANKS_NUM_4;
|
||||||
|
hsdram.Init.CASLatency = FMC_SDRAM_CAS_LATENCY_2;
|
||||||
|
hsdram.Init.WriteProtection = FMC_SDRAM_WRITE_PROTECTION_DISABLE;
|
||||||
|
hsdram.Init.SDClockPeriod = FMC_SDRAM_CLOCK_PERIOD_2;
|
||||||
|
hsdram.Init.ReadBurst = FMC_SDRAM_RBURST_ENABLE;
|
||||||
|
hsdram.Init.ReadPipeDelay = FMC_SDRAM_RPIPE_DELAY_0;
|
||||||
|
|
||||||
|
/* Timing configuration for 100Mhz as SDRAM clock frequency (System clock is up to 200Mhz) */
|
||||||
|
SDRAM_Timing.LoadToActiveDelay = 2;
|
||||||
|
SDRAM_Timing.ExitSelfRefreshDelay = 8;
|
||||||
|
SDRAM_Timing.SelfRefreshTime = 6;
|
||||||
|
SDRAM_Timing.RowCycleDelay = 6;
|
||||||
|
SDRAM_Timing.WriteRecoveryTime = 2;
|
||||||
|
SDRAM_Timing.RPDelay = 2;
|
||||||
|
SDRAM_Timing.RCDDelay = 2;
|
||||||
|
|
||||||
|
/* Initialize the SDRAM controller */
|
||||||
|
if (HAL_SDRAM_Init(&hsdram, &SDRAM_Timing) != HAL_OK)
|
||||||
|
{
|
||||||
|
/* Initialization Error */
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Program the SDRAM external device */
|
||||||
|
SDRAM_Initialization_Sequence(&hsdram, &command);
|
||||||
|
}
|
||||||
|
|
||||||
|
void LTDC_Config() {
|
||||||
|
|
||||||
|
__HAL_RCC_LTDC_CLK_ENABLE();
|
||||||
|
__HAL_RCC_DMA2D_CLK_ENABLE();
|
||||||
|
|
||||||
|
RCC_PeriphCLKInitTypeDef PeriphClkInitStruct;
|
||||||
|
|
||||||
|
/* The PLL3R is configured to provide the LTDC PCLK clock */
|
||||||
|
/* PLL3_VCO Input = HSE_VALUE / PLL3M = 25Mhz / 5 = 5 Mhz */
|
||||||
|
/* PLL3_VCO Output = PLL3_VCO Input * PLL3N = 5Mhz * 160 = 800 Mhz */
|
||||||
|
/* PLLLCDCLK = PLL3_VCO Output/PLL3R = 800Mhz / 16 = 50Mhz */
|
||||||
|
/* LTDC clock frequency = PLLLCDCLK = 50 Mhz */
|
||||||
|
PeriphClkInitStruct.PeriphClockSelection = RCC_PERIPHCLK_LTDC;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3M = 5;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3N = 160;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3FRACN = 0;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3P = 2;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3Q = 2;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3R = (800 / LTDC_LCD_CLK);
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3VCOSEL = RCC_PLL3VCOWIDE;
|
||||||
|
PeriphClkInitStruct.PLL3.PLL3RGE = RCC_PLL3VCIRANGE_2;
|
||||||
|
HAL_RCCEx_PeriphCLKConfig(&PeriphClkInitStruct);
|
||||||
|
|
||||||
|
LTDC_HandleTypeDef hltdc_F;
|
||||||
|
LTDC_LayerCfgTypeDef pLayerCfg;
|
||||||
|
|
||||||
|
/* LTDC Initialization -------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Polarity configuration */
|
||||||
|
/* Initialize the horizontal synchronization polarity as active low */
|
||||||
|
hltdc_F.Init.HSPolarity = LTDC_HSPOLARITY_AL;
|
||||||
|
/* Initialize the vertical synchronization polarity as active low */
|
||||||
|
hltdc_F.Init.VSPolarity = LTDC_VSPOLARITY_AL;
|
||||||
|
/* Initialize the data enable polarity as active low */
|
||||||
|
hltdc_F.Init.DEPolarity = LTDC_DEPOLARITY_AL;
|
||||||
|
/* Initialize the pixel clock polarity as input pixel clock */
|
||||||
|
hltdc_F.Init.PCPolarity = LTDC_PCPOLARITY_IPC;
|
||||||
|
|
||||||
|
/* Timing configuration */
|
||||||
|
hltdc_F.Init.HorizontalSync = (LTDC_LCD_HSYNC - 1);
|
||||||
|
hltdc_F.Init.VerticalSync = (LTDC_LCD_VSYNC - 1);
|
||||||
|
hltdc_F.Init.AccumulatedHBP = (LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1);
|
||||||
|
hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
|
||||||
|
hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
|
||||||
|
hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1);
|
||||||
|
hltdc_F.Init.TotalHeigh = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1);
|
||||||
|
hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1);
|
||||||
|
|
||||||
|
/* Configure R,G,B component values for LCD background color : all black background */
|
||||||
|
hltdc_F.Init.Backcolor.Blue = 0;
|
||||||
|
hltdc_F.Init.Backcolor.Green = 0;
|
||||||
|
hltdc_F.Init.Backcolor.Red = 0;
|
||||||
|
|
||||||
|
hltdc_F.Instance = LTDC;
|
||||||
|
|
||||||
|
/* Layer0 Configuration ------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* Windowing configuration */
|
||||||
|
pLayerCfg.WindowX0 = 0;
|
||||||
|
pLayerCfg.WindowX1 = TFT_WIDTH;
|
||||||
|
pLayerCfg.WindowY0 = 0;
|
||||||
|
pLayerCfg.WindowY1 = TFT_HEIGHT;
|
||||||
|
|
||||||
|
/* Pixel Format configuration*/
|
||||||
|
pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565;
|
||||||
|
|
||||||
|
/* Start Address configuration : frame buffer is located at SDRAM memory */
|
||||||
|
pLayerCfg.FBStartAdress = (uint32_t)(FRAME_BUFFER_ADDRESS);
|
||||||
|
|
||||||
|
/* Alpha constant (255 == totally opaque) */
|
||||||
|
pLayerCfg.Alpha = 255;
|
||||||
|
|
||||||
|
/* Default Color configuration (configure A,R,G,B component values) : no background color */
|
||||||
|
pLayerCfg.Alpha0 = 0; /* fully transparent */
|
||||||
|
pLayerCfg.Backcolor.Blue = 0;
|
||||||
|
pLayerCfg.Backcolor.Green = 0;
|
||||||
|
pLayerCfg.Backcolor.Red = 0;
|
||||||
|
|
||||||
|
/* Configure blending factors */
|
||||||
|
pLayerCfg.BlendingFactor1 = LTDC_BLENDING_FACTOR1_CA;
|
||||||
|
pLayerCfg.BlendingFactor2 = LTDC_BLENDING_FACTOR2_CA;
|
||||||
|
|
||||||
|
/* Configure the number of lines and number of pixels per line */
|
||||||
|
pLayerCfg.ImageWidth = TFT_WIDTH;
|
||||||
|
pLayerCfg.ImageHeight = TFT_HEIGHT;
|
||||||
|
|
||||||
|
/* Configure the LTDC */
|
||||||
|
if (HAL_LTDC_Init(&hltdc_F) != HAL_OK)
|
||||||
|
{
|
||||||
|
/* Initialization Error */
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Configure the Layer*/
|
||||||
|
if (HAL_LTDC_ConfigLayer(&hltdc_F, &pLayerCfg, 0) != HAL_OK)
|
||||||
|
{
|
||||||
|
/* Initialization Error */
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t TFT_LTDC::x_min = 0;
|
||||||
|
uint16_t TFT_LTDC::x_max = 0;
|
||||||
|
uint16_t TFT_LTDC::y_min = 0;
|
||||||
|
uint16_t TFT_LTDC::y_max = 0;
|
||||||
|
uint16_t TFT_LTDC::x_cur = 0;
|
||||||
|
uint16_t TFT_LTDC::y_cur = 0;
|
||||||
|
uint8_t TFT_LTDC::reg = 0;
|
||||||
|
volatile uint16_t* TFT_LTDC::framebuffer = (volatile uint16_t* )FRAME_BUFFER_ADDRESS;
|
||||||
|
|
||||||
|
void TFT_LTDC::Init() {
|
||||||
|
|
||||||
|
// SDRAM pins init
|
||||||
|
for (uint16_t i = 0; PinMap_SDRAM[i].pin != NC; i++)
|
||||||
|
pinmap_pinout(PinMap_SDRAM[i].pin, PinMap_SDRAM);
|
||||||
|
|
||||||
|
// SDRAM peripheral config
|
||||||
|
SDRAM_Config();
|
||||||
|
|
||||||
|
// LTDC pins init
|
||||||
|
for (uint16_t i = 0; PinMap_LTDC[i].pin != NC; i++)
|
||||||
|
pinmap_pinout(PinMap_LTDC[i].pin, PinMap_LTDC);
|
||||||
|
|
||||||
|
// LTDC peripheral config
|
||||||
|
LTDC_Config();
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t TFT_LTDC::GetID() {
|
||||||
|
return 0xABAB;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t TFT_LTDC::ReadID(tft_data_t Reg) {
|
||||||
|
return 0xABAB;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool TFT_LTDC::isBusy() {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t TFT_LTDC::ReadPoint(uint16_t x, uint16_t y) {
|
||||||
|
return framebuffer[(TFT_WIDTH * y) + x];
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::DrawPoint(uint16_t x, uint16_t y, uint16_t color) {
|
||||||
|
framebuffer[(TFT_WIDTH * y) + x] = color;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color) {
|
||||||
|
|
||||||
|
if (sx == ex || sy == ey) return;
|
||||||
|
|
||||||
|
uint16_t offline = TFT_WIDTH - (ex - sx);
|
||||||
|
uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx];
|
||||||
|
|
||||||
|
DMA2D->CR &= ~(1 << 0);
|
||||||
|
DMA2D->CR = 3 << 16;
|
||||||
|
DMA2D->OPFCCR = 0X02;
|
||||||
|
DMA2D->OOR = offline;
|
||||||
|
DMA2D->OMAR = addr;
|
||||||
|
DMA2D->NLR = (ey - sy) | ((ex - sx) << 16);
|
||||||
|
DMA2D->OCOLR = color;
|
||||||
|
DMA2D->CR |= 1<<0;
|
||||||
|
|
||||||
|
uint32_t timeout = 0;
|
||||||
|
while((DMA2D->ISR & (1<<1)) == 0)
|
||||||
|
{
|
||||||
|
timeout++;
|
||||||
|
if(timeout>0X1FFFFF)break;
|
||||||
|
}
|
||||||
|
DMA2D->IFCR |= 1<<1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors) {
|
||||||
|
|
||||||
|
if (sx == ex || sy == ey) return;
|
||||||
|
|
||||||
|
uint16_t offline = TFT_WIDTH - (ex - sx);
|
||||||
|
uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx];
|
||||||
|
|
||||||
|
DMA2D->CR &= ~(1 << 0);
|
||||||
|
DMA2D->CR = 0 << 16;
|
||||||
|
DMA2D->FGPFCCR = 0X02;
|
||||||
|
DMA2D->FGOR = 0;
|
||||||
|
DMA2D->OOR = offline;
|
||||||
|
DMA2D->FGMAR = (uint32_t)colors;
|
||||||
|
DMA2D->OMAR = addr;
|
||||||
|
DMA2D->NLR = (ey - sy) | ((ex - sx) << 16);
|
||||||
|
DMA2D->CR |= 1<<0;
|
||||||
|
|
||||||
|
uint32_t timeout = 0;
|
||||||
|
while((DMA2D->ISR & (1<<1)) == 0)
|
||||||
|
{
|
||||||
|
timeout++;
|
||||||
|
if(timeout>0X1FFFFF)break;
|
||||||
|
}
|
||||||
|
DMA2D->IFCR |= 1<<1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::WriteData(uint16_t data) {
|
||||||
|
switch (reg) {
|
||||||
|
case 0x01: x_cur = x_min = data; return;
|
||||||
|
case 0x02: x_max = data; return;
|
||||||
|
case 0x03: y_cur = y_min = data; return;
|
||||||
|
case 0x04: y_max = data; return;
|
||||||
|
}
|
||||||
|
Transmit(data);
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::Transmit(tft_data_t Data) {
|
||||||
|
DrawPoint(x_cur, y_cur, Data);
|
||||||
|
x_cur++;
|
||||||
|
if (x_cur > x_max) {
|
||||||
|
x_cur = x_min;
|
||||||
|
y_cur++;
|
||||||
|
if (y_cur > y_max) y_cur = y_min;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::WriteReg(uint16_t Reg) {
|
||||||
|
reg = Reg;
|
||||||
|
}
|
||||||
|
|
||||||
|
void TFT_LTDC::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
|
||||||
|
|
||||||
|
while (x_cur != x_min && Count) {
|
||||||
|
Transmit(*Data);
|
||||||
|
if (MemoryIncrease == DMA_PINC_ENABLE) Data++;
|
||||||
|
Count--;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t width = x_max - x_min + 1;
|
||||||
|
uint16_t height = Count / width;
|
||||||
|
uint16_t x_end_cnt = Count - (width * height);
|
||||||
|
|
||||||
|
if (height) {
|
||||||
|
if (MemoryIncrease == DMA_PINC_ENABLE) {
|
||||||
|
DrawImage(x_min, y_cur, x_min + width, y_cur + height, Data);
|
||||||
|
Data += width * height;
|
||||||
|
} else {
|
||||||
|
DrawRect(x_min, y_cur, x_min + width, y_cur + height, *Data);
|
||||||
|
}
|
||||||
|
y_cur += height;
|
||||||
|
}
|
||||||
|
|
||||||
|
while (x_end_cnt) {
|
||||||
|
Transmit(*Data);
|
||||||
|
if (MemoryIncrease == DMA_PINC_ENABLE) Data++;
|
||||||
|
x_end_cnt--;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // HAS_LTDC_TFT
|
||||||
|
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC
|
155
Marlin/src/HAL/STM32/tft/tft_ltdc.h
Normal file
155
Marlin/src/HAL/STM32/tft/tft_ltdc.h
Normal file
|
@ -0,0 +1,155 @@
|
||||||
|
/**
|
||||||
|
* 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"
|
||||||
|
|
||||||
|
#ifdef STM32H7xx
|
||||||
|
#include "stm32h7xx_hal.h"
|
||||||
|
#else
|
||||||
|
#error "LTDC TFT is currently only supported on STM32H7 hardware."
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define DATASIZE_8BIT SPI_DATASIZE_8BIT
|
||||||
|
#define DATASIZE_16BIT SPI_DATASIZE_16BIT
|
||||||
|
#define TFT_IO_DRIVER TFT_LTDC
|
||||||
|
|
||||||
|
#define TFT_DATASIZE DATASIZE_16BIT
|
||||||
|
typedef uint16_t tft_data_t;
|
||||||
|
|
||||||
|
class TFT_LTDC {
|
||||||
|
private:
|
||||||
|
static volatile uint16_t *framebuffer;
|
||||||
|
static uint16_t x_min, x_max, y_min, y_max, x_cur, y_cur;
|
||||||
|
static uint8_t reg;
|
||||||
|
|
||||||
|
static uint32_t ReadID(tft_data_t Reg);
|
||||||
|
|
||||||
|
static uint16_t ReadPoint(uint16_t x, uint16_t y);
|
||||||
|
static void DrawPoint(uint16_t x, uint16_t y, uint16_t color);
|
||||||
|
static void DrawRect(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t color);
|
||||||
|
static void DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uint16_t *colors);
|
||||||
|
static void Transmit(tft_data_t Data);
|
||||||
|
static void TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count);
|
||||||
|
|
||||||
|
public:
|
||||||
|
static void Init();
|
||||||
|
static uint32_t GetID();
|
||||||
|
static bool isBusy();
|
||||||
|
static void Abort() { /*__HAL_DMA_DISABLE(&DMAtx);*/ }
|
||||||
|
|
||||||
|
static void DataTransferBegin(uint16_t DataWidth = TFT_DATASIZE) {}
|
||||||
|
static void DataTransferEnd() {};
|
||||||
|
|
||||||
|
static void WriteData(uint16_t Data);
|
||||||
|
static void WriteReg(uint16_t Reg);
|
||||||
|
|
||||||
|
static void WriteSequence(uint16_t *Data, uint16_t Count) { TransmitDMA(DMA_PINC_ENABLE, Data, Count); }
|
||||||
|
static void WriteMultiple(uint16_t Color, uint16_t Count) { static uint16_t Data; Data = Color; TransmitDMA(DMA_PINC_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;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
const PinMap PinMap_LTDC[] = {
|
||||||
|
{PF_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_DE
|
||||||
|
{PG_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_CLK
|
||||||
|
{PI_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_VSYNC
|
||||||
|
{PI_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_HSYNC
|
||||||
|
|
||||||
|
{PG_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R7
|
||||||
|
{PH_12, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R6
|
||||||
|
{PH_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R5
|
||||||
|
{PH_10, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R4
|
||||||
|
{PH_9, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_R3
|
||||||
|
|
||||||
|
{PI_2, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G7
|
||||||
|
{PI_1, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G6
|
||||||
|
{PI_0, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G5
|
||||||
|
{PH_15, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G4
|
||||||
|
{PH_14, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G3
|
||||||
|
{PH_13, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_G2
|
||||||
|
|
||||||
|
{PI_7, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B7
|
||||||
|
{PI_6, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B6
|
||||||
|
{PI_5, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B5
|
||||||
|
{PI_4, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B4
|
||||||
|
{PG_11, LTDC, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_LTDC)}, // LCD_B3
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
const PinMap PinMap_SDRAM[] = {
|
||||||
|
{PC_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNWE
|
||||||
|
{PC_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNE0
|
||||||
|
{PC_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCKE0
|
||||||
|
{PE_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL0
|
||||||
|
{PE_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_NBL1
|
||||||
|
{PF_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNRAS
|
||||||
|
{PG_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDCLK
|
||||||
|
{PG_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_SDNCAS
|
||||||
|
{PG_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA0
|
||||||
|
{PG_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_BA1
|
||||||
|
{PD_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D0
|
||||||
|
{PD_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D1
|
||||||
|
{PD_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D2
|
||||||
|
{PD_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D3
|
||||||
|
{PE_7, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D4
|
||||||
|
{PE_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D5
|
||||||
|
{PE_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D6
|
||||||
|
{PE_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D7
|
||||||
|
{PE_11, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D8
|
||||||
|
{PE_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D9
|
||||||
|
{PE_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D10
|
||||||
|
{PE_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D11
|
||||||
|
{PE_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D12
|
||||||
|
{PD_8, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D13
|
||||||
|
{PD_9, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D14
|
||||||
|
{PD_10, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_D15
|
||||||
|
{PF_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A0
|
||||||
|
{PF_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A1
|
||||||
|
{PF_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A2
|
||||||
|
{PF_3, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A3
|
||||||
|
{PF_4, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A4
|
||||||
|
{PF_5, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A5
|
||||||
|
{PF_12, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A6
|
||||||
|
{PF_13, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A7
|
||||||
|
{PF_14, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A8
|
||||||
|
{PF_15, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A9
|
||||||
|
{PG_0, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A10
|
||||||
|
{PG_1, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A11
|
||||||
|
{PG_2, FMC_Bank1_R, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_FMC)}, // FMC_A12
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
const PinMap PinMap_QUADSPI[] = {
|
||||||
|
{PB_2, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_CLK
|
||||||
|
{PB_10, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_NCS
|
||||||
|
{PF_6, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO3
|
||||||
|
{PF_7, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_QUADSPI)}, // QUADSPI_BK1_IO2
|
||||||
|
{PF_8, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO0
|
||||||
|
{PF_9, QUADSPI, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_QUADSPI)}, // QUADSPI_BK1_IO1
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
|
@ -74,7 +74,7 @@
|
||||||
#elif defined(STM32F401xC) || defined(STM32F401xE)
|
#elif defined(STM32F401xC) || defined(STM32F401xE)
|
||||||
#define MCU_STEP_TIMER 9
|
#define MCU_STEP_TIMER 9
|
||||||
#define MCU_TEMP_TIMER 10
|
#define MCU_TEMP_TIMER 10
|
||||||
#elif defined(STM32F4xx) || defined(STM32F7xx)
|
#elif defined(STM32F4xx) || defined(STM32F7xx) || defined(STM32H7xx)
|
||||||
#define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
|
#define MCU_STEP_TIMER 6 // STM32F401 has no TIM6, TIM7, or TIM8
|
||||||
#define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
|
#define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used.
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -390,6 +390,7 @@
|
||||||
#define BOARD_TEENSY41 5001 // Teensy 4.1
|
#define BOARD_TEENSY41 5001 // Teensy 4.1
|
||||||
#define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board
|
#define BOARD_T41U5XBB 5002 // T41U5XBB Teensy 4.1 breakout board
|
||||||
#define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board
|
#define BOARD_NUCLEO_F767ZI 5003 // ST NUCLEO-F767ZI Dev Board
|
||||||
|
#define BOARD_BTT_SKR_SE_BX 5004 // BigTreeTech SKR SE BX (STM32H743II)
|
||||||
|
|
||||||
//
|
//
|
||||||
// Espressif ESP32 WiFi
|
// Espressif ESP32 WiFi
|
||||||
|
|
|
@ -1119,6 +1119,10 @@
|
||||||
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY)
|
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY)
|
||||||
#define TFT_RES_480x320
|
#define TFT_RES_480x320
|
||||||
#define TFT_INTERFACE_FSMC
|
#define TFT_INTERFACE_FSMC
|
||||||
|
#elif ENABLED(BIQU_BX_TFT70) // RGB
|
||||||
|
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY)
|
||||||
|
#define TFT_RES_1024x600
|
||||||
|
#define TFT_INTERFACE_LTDC
|
||||||
#elif ENABLED(TFT_GENERIC)
|
#elif ENABLED(TFT_GENERIC)
|
||||||
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y)
|
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y)
|
||||||
#if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320)
|
#if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320)
|
||||||
|
@ -1141,9 +1145,13 @@
|
||||||
#define TFT_WIDTH 480
|
#define TFT_WIDTH 480
|
||||||
#define TFT_HEIGHT 320
|
#define TFT_HEIGHT 320
|
||||||
#define GRAPHICAL_TFT_UPSCALE 3
|
#define GRAPHICAL_TFT_UPSCALE 3
|
||||||
|
#elif ENABLED(TFT_RES_1024x600)
|
||||||
|
#define TFT_WIDTH 1024
|
||||||
|
#define TFT_HEIGHT 600
|
||||||
|
#define GRAPHICAL_TFT_UPSCALE 4
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi).h
|
// FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h
|
||||||
#if ENABLED(TFT_INTERFACE_FSMC)
|
#if ENABLED(TFT_INTERFACE_FSMC)
|
||||||
#define HAS_FSMC_TFT 1
|
#define HAS_FSMC_TFT 1
|
||||||
#if TFT_SCALED_DOGLCD
|
#if TFT_SCALED_DOGLCD
|
||||||
|
@ -1158,6 +1166,13 @@
|
||||||
#elif HAS_TFT_LVGL_UI
|
#elif HAS_TFT_LVGL_UI
|
||||||
#define HAS_TFT_LVGL_UI_SPI 1
|
#define HAS_TFT_LVGL_UI_SPI 1
|
||||||
#endif
|
#endif
|
||||||
|
#elif ENABLED(TFT_INTERFACE_LTDC)
|
||||||
|
#define HAS_LTDC_TFT 1
|
||||||
|
#if TFT_SCALED_DOGLCD
|
||||||
|
#define HAS_LTDC_GRAPHICAL_TFT 1
|
||||||
|
#elif HAS_TFT_LVGL_UI
|
||||||
|
#define HAS_TFT_LVGL_UI_LTDC 1
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(TFT_COLOR_UI)
|
#if ENABLED(TFT_COLOR_UI)
|
||||||
|
@ -1179,6 +1194,10 @@
|
||||||
#elif ENABLED(TFT_INTERFACE_FSMC)
|
#elif ENABLED(TFT_INTERFACE_FSMC)
|
||||||
#define TFT_480x272
|
#define TFT_480x272
|
||||||
#endif
|
#endif
|
||||||
|
#elif TFT_HEIGHT == 600
|
||||||
|
#if ENABLED(TFT_INTERFACE_LTDC)
|
||||||
|
#define TFT_1024x600_LTDC
|
||||||
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1188,9 +1207,13 @@
|
||||||
#define HAS_UI_480x320 1
|
#define HAS_UI_480x320 1
|
||||||
#elif EITHER(TFT_480x272, TFT_480x272_SPI)
|
#elif EITHER(TFT_480x272, TFT_480x272_SPI)
|
||||||
#define HAS_UI_480x272 1
|
#define HAS_UI_480x272 1
|
||||||
|
#elif defined(TFT_1024x600_LTDC)
|
||||||
|
#define HAS_UI_1024x600 1
|
||||||
#endif
|
#endif
|
||||||
#if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272)
|
#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
|
#endif
|
||||||
|
|
||||||
// This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046'
|
// This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046'
|
||||||
|
|
|
@ -2404,7 +2404,7 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal
|
||||||
#undef IS_EXTUI
|
#undef IS_EXTUI
|
||||||
#undef IS_LEGACY_TFT
|
#undef IS_LEGACY_TFT
|
||||||
|
|
||||||
#if ANY(TFT_GENERIC, MKS_TS35_V2_0, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35, MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R, TFT_TRONXY_X5SA, ANYCUBIC_TFT35, ANYCUBIC_TFT35, LONGER_LK_TFT28, ANET_ET4_TFT28, ANET_ET5_TFT35)
|
#if ANY(TFT_GENERIC, MKS_TS35_V2_0, MKS_ROBIN_TFT24, MKS_ROBIN_TFT28, MKS_ROBIN_TFT32, MKS_ROBIN_TFT35, MKS_ROBIN_TFT43, MKS_ROBIN_TFT_V1_1R, TFT_TRONXY_X5SA, ANYCUBIC_TFT35, ANYCUBIC_TFT35, LONGER_LK_TFT28, ANET_ET4_TFT28, ANET_ET5_TFT35, BIQU_BX_TFT70)
|
||||||
#if NONE(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI)
|
#if NONE(TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI)
|
||||||
#error "TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI is required for your TFT. Please enable one."
|
#error "TFT_COLOR_UI, TFT_CLASSIC_UI, TFT_LVGL_UI is required for your TFT. Please enable one."
|
||||||
#elif 1 < ENABLED(TFT_COLOR_UI) + ENABLED(TFT_CLASSIC_UI) + ENABLED(TFT_LVGL_UI)
|
#elif 1 < ENABLED(TFT_COLOR_UI) + ENABLED(TFT_CLASSIC_UI) + ENABLED(TFT_LVGL_UI)
|
||||||
|
@ -2426,16 +2426,16 @@ static_assert(hbm[Z_AXIS] >= 0, "HOMING_BUMP_MM.Z must be greater than or equal
|
||||||
#error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270."
|
#error "Please enable only one LCD_SCREEN_ROT_* option: 0, 90, 180, or 270."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if MANY(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320)
|
#if MANY(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320, TFT_RES_1024x600)
|
||||||
#error "Please select only one of TFT_RES_480x320, TFT_RES_480x320, or TFT_RES_480x272."
|
#error "Please select only one of TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320, or TFT_RES_1024x600."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if HAS_TFT_LVGL_UI && DISABLED(TFT_RES_480x320)
|
#if HAS_TFT_LVGL_UI && DISABLED(TFT_RES_480x320)
|
||||||
#error "(FMSC|SPI)TFT_LVGL_UI requires TFT_RES_480x320."
|
#error "(FMSC|SPI)TFT_LVGL_UI requires TFT_RES_480x320."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 3)
|
#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 4)
|
||||||
#error "GRAPHICAL_TFT_UPSCALE must be set to 2 or 3."
|
#error "GRAPHICAL_TFT_UPSCALE must be 2, 3, or 4."
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -55,14 +55,14 @@
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_MARLINUI_U8GLIB && (PIN_EXISTS(FSMC_CS) || HAS_SPI_GRAPHICAL_TFT)
|
#if HAS_MARLINUI_U8GLIB && (PIN_EXISTS(FSMC_CS) || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_GRAPHICAL_TFT)
|
||||||
|
|
||||||
#include "HAL_LCD_com_defines.h"
|
#include "HAL_LCD_com_defines.h"
|
||||||
#include "marlinui_DOGM.h"
|
#include "marlinui_DOGM.h"
|
||||||
|
|
||||||
#include <string.h>
|
#include <string.h>
|
||||||
|
|
||||||
#if EITHER(LCD_USE_DMA_FSMC, LCD_USE_DMA_SPI)
|
#if ANY(LCD_USE_DMA_FSMC, LCD_USE_DMA_SPI, HAS_LTDC_GRAPHICAL_TFT)
|
||||||
#define HAS_LCD_IO 1
|
#define HAS_LCD_IO 1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -55,7 +55,7 @@ constexpr static float gaugeThickness = 0.25;
|
||||||
static float meshGetter(uint8_t x, uint8_t y, void*) {
|
static float meshGetter(uint8_t x, uint8_t y, void*) {
|
||||||
xy_uint8_t pos;
|
xy_uint8_t pos;
|
||||||
pos.x = x;
|
pos.x = x;
|
||||||
pos.y = y;
|
pos.y = y;
|
||||||
return ExtUI::getMeshPoint(pos);
|
return ExtUI::getMeshPoint(pos);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -46,6 +46,9 @@
|
||||||
#elif HAS_UI_480x272
|
#elif HAS_UI_480x272
|
||||||
#define TFT_WIDTH 480
|
#define TFT_WIDTH 480
|
||||||
#define TFT_HEIGHT 272
|
#define TFT_HEIGHT 272
|
||||||
|
#elif HAS_UI_1024x600
|
||||||
|
#define TFT_WIDTH 1024
|
||||||
|
#define TFT_HEIGHT 600
|
||||||
#else
|
#else
|
||||||
#error "Unsupported display resolution!"
|
#error "Unsupported display resolution!"
|
||||||
#endif
|
#endif
|
||||||
|
|
927
Marlin/src/lcd/tft/ui_1024x600.cpp
Normal file
927
Marlin/src/lcd/tft/ui_1024x600.cpp
Normal file
|
@ -0,0 +1,927 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (c) 2020 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/>.
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "../../inc/MarlinConfigPre.h"
|
||||||
|
|
||||||
|
#if HAS_UI_1024x600
|
||||||
|
|
||||||
|
#include "ui_common.h"
|
||||||
|
|
||||||
|
#include "../marlinui.h"
|
||||||
|
#include "../menu/menu.h"
|
||||||
|
#include "../../libs/numtostr.h"
|
||||||
|
|
||||||
|
#include "../../sd/cardreader.h"
|
||||||
|
#include "../../module/temperature.h"
|
||||||
|
#include "../../module/printcounter.h"
|
||||||
|
#include "../../module/planner.h"
|
||||||
|
#include "../../module/motion.h"
|
||||||
|
|
||||||
|
#if DISABLED(LCD_PROGRESS_BAR) && BOTH(FILAMENT_LCD_DISPLAY, SDSUPPORT)
|
||||||
|
#include "../../feature/filwidth.h"
|
||||||
|
#include "../../gcode/parser.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#include "../../feature/bedlevel/bedlevel.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
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);
|
||||||
|
draw_menu_navigation = false;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
tft.queue.async();
|
||||||
|
TERN_(TOUCH_SCREEN, touch.idle());
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(SHOW_BOOTSCREEN)
|
||||||
|
void MarlinUI::show_bootscreen() {
|
||||||
|
tft.queue.reset();
|
||||||
|
|
||||||
|
tft.canvas(0, 0, TFT_WIDTH, TFT_HEIGHT);
|
||||||
|
#if ENABLED(BOOT_MARLIN_LOGO_SMALL)
|
||||||
|
#define BOOT_LOGO_W 195 // MarlinLogo195x59x16
|
||||||
|
#define BOOT_LOGO_H 59
|
||||||
|
#define SITE_URL_Y (TFT_HEIGHT - 70)
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
#else
|
||||||
|
#define BOOT_LOGO_W TFT_WIDTH // MarlinLogo480x320x16
|
||||||
|
#define BOOT_LOGO_H TFT_HEIGHT
|
||||||
|
#define SITE_URL_Y (TFT_HEIGHT - 90)
|
||||||
|
#endif
|
||||||
|
tft.add_image((TFT_WIDTH - BOOT_LOGO_W) / 2, (TFT_HEIGHT - BOOT_LOGO_H) / 2, imgBootScreen);
|
||||||
|
#ifdef WEBSITE_URL
|
||||||
|
tft_string.set(WEBSITE_URL);
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), SITE_URL_Y, COLOR_WEBSITE_URL, tft_string);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
tft.queue.sync();
|
||||||
|
safe_delay(BOOTSCREEN_TIMEOUT);
|
||||||
|
clear_lcd();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void MarlinUI::draw_kill_screen() {
|
||||||
|
tft.queue.reset();
|
||||||
|
tft.fill(0, 0, TFT_WIDTH, TFT_HEIGHT, COLOR_KILL_SCREEN_BG);
|
||||||
|
|
||||||
|
uint16_t line = 2;
|
||||||
|
|
||||||
|
menu_line(line++, COLOR_KILL_SCREEN_BG);
|
||||||
|
tft_string.set(status_message);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
|
||||||
|
line++;
|
||||||
|
menu_line(line++, COLOR_KILL_SCREEN_BG);
|
||||||
|
tft_string.set(GET_TEXT(MSG_HALTED));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
|
||||||
|
menu_line(line++, COLOR_KILL_SCREEN_BG);
|
||||||
|
tft_string.set(GET_TEXT(MSG_PLEASE_RESET));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
|
||||||
|
tft.queue.sync();
|
||||||
|
}
|
||||||
|
|
||||||
|
void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater) {
|
||||||
|
MarlinImage image = imgHotEnd;
|
||||||
|
uint16_t Color;
|
||||||
|
celsius_t currentTemperature, targetTemperature;
|
||||||
|
|
||||||
|
if (Heater >= 0) { // HotEnd
|
||||||
|
currentTemperature = thermalManager.degHotend(Heater);
|
||||||
|
targetTemperature = thermalManager.degTargetHotend(Heater);
|
||||||
|
}
|
||||||
|
#if HAS_HEATED_BED
|
||||||
|
else if (Heater == H_BED) {
|
||||||
|
currentTemperature = thermalManager.degBed();
|
||||||
|
targetTemperature = thermalManager.degTargetBed();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if HAS_TEMP_CHAMBER
|
||||||
|
else if (Heater == H_CHAMBER) {
|
||||||
|
currentTemperature = thermalManager.degChamber();
|
||||||
|
#if HAS_HEATED_CHAMBER
|
||||||
|
targetTemperature = thermalManager.degTargetChamber();
|
||||||
|
#else
|
||||||
|
targetTemperature = ABSOLUTE_ZERO;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if HAS_TEMP_COOLER
|
||||||
|
else if (Heater == H_COOLER) {
|
||||||
|
currentTemperature = thermalManager.degCooler();
|
||||||
|
targetTemperature = TERN(HAS_COOLER, thermalManager.degTargetCooler(), ABSOLUTE_ZERO);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
else return;
|
||||||
|
|
||||||
|
TERN_(TOUCH_SCREEN, if (targetTemperature >= 0) touch.add_control(HEATER, x, y, 80, 120, Heater));
|
||||||
|
tft.canvas(x, y, 80, 120);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
|
||||||
|
Color = currentTemperature < 0 ? COLOR_INACTIVE : COLOR_COLD;
|
||||||
|
|
||||||
|
if (Heater >= 0) { // HotEnd
|
||||||
|
if (currentTemperature >= 50) Color = COLOR_HOTEND;
|
||||||
|
}
|
||||||
|
#if HAS_HEATED_BED
|
||||||
|
else if (Heater == H_BED) {
|
||||||
|
if (currentTemperature >= 50) Color = COLOR_HEATED_BED;
|
||||||
|
image = targetTemperature > 0 ? imgBedHeated : imgBed;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
#if HAS_TEMP_CHAMBER
|
||||||
|
else if (Heater == H_CHAMBER) {
|
||||||
|
if (currentTemperature >= 50) Color = COLOR_CHAMBER;
|
||||||
|
image = targetTemperature > 0 ? imgChamberHeated : imgChamber;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
tft.add_image(8, 28, image, Color);
|
||||||
|
|
||||||
|
tft_string.set((uint8_t *)i16tostr3rj(currentTemperature));
|
||||||
|
tft_string.add(LCD_STR_DEGREE);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(80) + 2, 82, Color, tft_string);
|
||||||
|
|
||||||
|
if (targetTemperature >= 0) {
|
||||||
|
tft_string.set((uint8_t *)i16tostr3rj(targetTemperature));
|
||||||
|
tft_string.add(LCD_STR_DEGREE);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(80) + 2, 8, Color, tft_string);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void draw_fan_status(uint16_t x, uint16_t y, const bool blink) {
|
||||||
|
TERN_(TOUCH_SCREEN, touch.add_control(FAN, x, y, 80, 120));
|
||||||
|
tft.canvas(x, y, 80, 120);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
|
||||||
|
uint8_t fanSpeed = thermalManager.fan_speed[0];
|
||||||
|
MarlinImage image;
|
||||||
|
|
||||||
|
if (fanSpeed >= 127)
|
||||||
|
image = blink ? imgFanFast1 : imgFanFast0;
|
||||||
|
else if (fanSpeed > 0)
|
||||||
|
image = blink ? imgFanSlow1 : imgFanSlow0;
|
||||||
|
else
|
||||||
|
image = imgFanIdle;
|
||||||
|
|
||||||
|
tft.add_image(8, 20, image, COLOR_FAN);
|
||||||
|
|
||||||
|
tft_string.set((uint8_t *)ui8tostr4pctrj(thermalManager.fan_speed[0]));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(80) + 6, 82, COLOR_FAN, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
void MarlinUI::draw_status_screen() {
|
||||||
|
const bool blink = get_blink();
|
||||||
|
|
||||||
|
TERN_(TOUCH_SCREEN, touch.clear());
|
||||||
|
|
||||||
|
// heaters and fan
|
||||||
|
uint16_t i, x, y = TFT_STATUS_TOP_Y;
|
||||||
|
|
||||||
|
for (i = 0 ; i < ITEMS_COUNT; i++) {
|
||||||
|
x = (TFT_WIDTH / ITEMS_COUNT - 80) / 2 + (TFT_WIDTH * i / ITEMS_COUNT);
|
||||||
|
switch (i) {
|
||||||
|
#ifdef ITEM_E0
|
||||||
|
case ITEM_E0: draw_heater_status(x, y, H_E0); break;
|
||||||
|
#endif
|
||||||
|
#ifdef ITEM_E1
|
||||||
|
case ITEM_E1: draw_heater_status(x, y, H_E1); break;
|
||||||
|
#endif
|
||||||
|
#ifdef ITEM_E2
|
||||||
|
case ITEM_E2: draw_heater_status(x, y, H_E2); break;
|
||||||
|
#endif
|
||||||
|
#ifdef ITEM_BED
|
||||||
|
case ITEM_BED: draw_heater_status(x, y, H_BED); break;
|
||||||
|
#endif
|
||||||
|
#ifdef ITEM_CHAMBER
|
||||||
|
case ITEM_CHAMBER: draw_heater_status(x, y, H_CHAMBER); break;
|
||||||
|
#endif
|
||||||
|
#ifdef ITEM_FAN
|
||||||
|
case ITEM_FAN: draw_fan_status(x, y, blink); break;
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
y += 200;
|
||||||
|
|
||||||
|
// coordinates
|
||||||
|
tft.canvas(4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_rectangle(0, 0, TFT_WIDTH - 8, FONT_LINE_HEIGHT, COLOR_AXIS_HOMED);
|
||||||
|
|
||||||
|
tft.add_text(200, 3, COLOR_AXIS_HOMED , "X");
|
||||||
|
tft.add_text(500, 3, COLOR_AXIS_HOMED , "Y");
|
||||||
|
tft.add_text(800, 3, COLOR_AXIS_HOMED , "Z");
|
||||||
|
|
||||||
|
bool not_homed = axis_should_home(X_AXIS);
|
||||||
|
tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_X_POSITION(current_position.x)));
|
||||||
|
tft.add_text(300 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string);
|
||||||
|
|
||||||
|
not_homed = axis_should_home(Y_AXIS);
|
||||||
|
tft_string.set(blink && not_homed ? "?" : ftostr4sign(LOGICAL_Y_POSITION(current_position.y)));
|
||||||
|
tft.add_text(600 - tft_string.width(), 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string);
|
||||||
|
|
||||||
|
uint16_t offset = 32;
|
||||||
|
not_homed = axis_should_home(Z_AXIS);
|
||||||
|
if (blink && not_homed)
|
||||||
|
tft_string.set("?");
|
||||||
|
else {
|
||||||
|
const float z = LOGICAL_Z_POSITION(current_position.z);
|
||||||
|
tft_string.set(ftostr52sp((int16_t)z));
|
||||||
|
tft_string.rtrim();
|
||||||
|
offset += tft_string.width();
|
||||||
|
|
||||||
|
tft_string.set(ftostr52sp(z));
|
||||||
|
offset -= tft_string.width();
|
||||||
|
}
|
||||||
|
tft.add_text(900 - tft_string.width() - offset, 3, not_homed ? COLOR_AXIS_NOT_HOMED : COLOR_AXIS_HOMED, tft_string);
|
||||||
|
TERN_(TOUCH_SCREEN, touch.add_control(MOVE_AXIS, 4, y, TFT_WIDTH - 8, FONT_LINE_HEIGHT));
|
||||||
|
|
||||||
|
y += 100;
|
||||||
|
// feed rate
|
||||||
|
tft.canvas(274, y, 100, 32);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
uint16_t color = feedrate_percentage == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED;
|
||||||
|
tft.add_image(0, 0, imgFeedRate, color);
|
||||||
|
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));
|
||||||
|
|
||||||
|
// flow rate
|
||||||
|
tft.canvas(650, y, 100, 32);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
color = planner.flow_percentage[0] == 100 ? COLOR_RATE_100 : COLOR_RATE_ALTERED;
|
||||||
|
tft.add_image(0, 0, imgFlowRate, color);
|
||||||
|
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));
|
||||||
|
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
add_control(404, 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
|
||||||
|
|
||||||
|
y += 100;
|
||||||
|
// print duration
|
||||||
|
char buffer[14];
|
||||||
|
duration_t elapsed = print_job_timer.duration();
|
||||||
|
elapsed.toDigital(buffer);
|
||||||
|
|
||||||
|
tft.canvas((TFT_WIDTH - 128) / 2, y, 128, 29);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(buffer);
|
||||||
|
tft.add_text(tft_string.center(128), 0, COLOR_PRINT_TIME, tft_string);
|
||||||
|
|
||||||
|
y += 50;
|
||||||
|
// progress bar
|
||||||
|
const uint8_t progress = ui.get_progress_percent();
|
||||||
|
tft.canvas(4, y, TFT_WIDTH - 8, 9);
|
||||||
|
tft.set_background(COLOR_PROGRESS_BG);
|
||||||
|
tft.add_rectangle(0, 0, TFT_WIDTH - 8, 9, COLOR_PROGRESS_FRAME);
|
||||||
|
if (progress)
|
||||||
|
tft.add_bar(1, 1, ((TFT_WIDTH - 10) * progress) / 100, 7, COLOR_PROGRESS_BAR);
|
||||||
|
|
||||||
|
y += 50;
|
||||||
|
// status message
|
||||||
|
tft.canvas(0, y, TFT_WIDTH, FONT_LINE_HEIGHT - 5);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(status_message);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_STATUS_MESSAGE, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Low-level draw_edit_screen can be used to draw an edit screen from anyplace
|
||||||
|
void MenuEditItemBase::draw_edit_screen(PGM_P const pstr, const char * const value/*=nullptr*/) {
|
||||||
|
ui.encoder_direction_normal();
|
||||||
|
TERN_(TOUCH_SCREEN, touch.clear());
|
||||||
|
|
||||||
|
uint16_t line = 1;
|
||||||
|
|
||||||
|
menu_line(line++);
|
||||||
|
tft_string.set(pstr, itemIndex, itemString);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
|
||||||
|
TERN_(AUTO_BED_LEVELING_UBL, if (ui.external_control) line++); // ftostr52() will overwrite *value so *value has to be displayed first
|
||||||
|
|
||||||
|
menu_line(line);
|
||||||
|
tft_string.set(value);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
if (ui.external_control) {
|
||||||
|
menu_line(line - 1);
|
||||||
|
|
||||||
|
tft_string.set(X_LBL);
|
||||||
|
tft.add_text((TFT_WIDTH / 2 - 120), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.x)));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text((TFT_WIDTH / 2 - 16) - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
tft_string.set(Y_LBL);
|
||||||
|
tft.add_text((TFT_WIDTH / 2 + 16), MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
tft_string.set(ftostr52(LOGICAL_X_POSITION(current_position.y)));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text((TFT_WIDTH / 2 + 120) - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
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
|
||||||
|
|
||||||
|
tft.canvas((TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION, SLIDER_LENGTH, 16);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
|
||||||
|
int16_t position = (SLIDER_LENGTH - 2) * ui.encoderPosition / maxEditValue;
|
||||||
|
tft.add_bar(0, 7, 1, 2, ui.encoderPosition == 0 ? COLOR_SLIDER_INACTIVE : COLOR_SLIDER);
|
||||||
|
tft.add_bar(1, 6, position, 4, COLOR_SLIDER);
|
||||||
|
tft.add_bar(position + 1, 6, SLIDER_LENGTH - 2 - position, 4, COLOR_SLIDER_INACTIVE);
|
||||||
|
tft.add_bar(SLIDER_LENGTH - 1, 7, 1, 2, int32_t(ui.encoderPosition) == maxEditValue ? COLOR_SLIDER : COLOR_SLIDER_INACTIVE);
|
||||||
|
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
tft.add_image((SLIDER_LENGTH - 8) * ui.encoderPosition / maxEditValue, 0, imgSlider, COLOR_SLIDER);
|
||||||
|
touch.add_control(SLIDER, (TFT_WIDTH - SLIDER_LENGTH) / 2, SLIDER_Y_POSITION - 8, SLIDER_LENGTH, 32, maxEditValue);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
tft.draw_edit_screen_buttons();
|
||||||
|
}
|
||||||
|
|
||||||
|
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);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
// The Select Screen presents a prompt and two "buttons"
|
||||||
|
void MenuItem_confirm::draw_select_screen(PGM_P const yes, PGM_P const no, const bool yesno, PGM_P const pref, const char * const string/*=nullptr*/, PGM_P const suff/*=nullptr*/) {
|
||||||
|
uint16_t line = 1;
|
||||||
|
|
||||||
|
if (!string) line++;
|
||||||
|
|
||||||
|
menu_line(line++);
|
||||||
|
tft_string.set(pref);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
|
||||||
|
if (string) {
|
||||||
|
menu_line(line++);
|
||||||
|
tft_string.set(string);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (suff) {
|
||||||
|
menu_line(line);
|
||||||
|
tft_string.set(suff);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
}
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
add_control(88, TFT_HEIGHT - 64, CANCEL, imgCancel, true, yesno ? HALF(COLOR_CONTROL_CANCEL) : COLOR_CONTROL_CANCEL);
|
||||||
|
add_control(328, TFT_HEIGHT - 64, CONFIRM, imgConfirm, true, yesno ? COLOR_CONTROL_CONFIRM : HALF(COLOR_CONTROL_CONFIRM));
|
||||||
|
#else
|
||||||
|
menu_line(++line);
|
||||||
|
if (no) {
|
||||||
|
tft_string.set(no);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH / 2), 0, !yesno ? COLOR_RED : COLOR_MENU_TEXT, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (yes) {
|
||||||
|
tft_string.set(yes);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(TFT_WIDTH / 2 + tft_string.center(TFT_WIDTH / 2), 0, yesno ? COLOR_RED : COLOR_MENU_TEXT, tft_string);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#if ENABLED(ADVANCED_PAUSE_FEATURE)
|
||||||
|
|
||||||
|
void MarlinUI::draw_hotend_status(const uint8_t row, const uint8_t extruder) {
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
touch.clear();
|
||||||
|
draw_menu_navigation = false;
|
||||||
|
touch.add_control(RESUME_CONTINUE , 0, 0, TFT_WIDTH, TFT_HEIGHT);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
menu_line(row);
|
||||||
|
tft_string.set(GET_TEXT(MSG_FILAMENT_CHANGE_NOZZLE));
|
||||||
|
tft_string.add('E');
|
||||||
|
tft_string.add((char)('1' + extruder));
|
||||||
|
tft_string.add(' ');
|
||||||
|
tft_string.add(i16tostr3rj(thermalManager.degHotend(extruder)));
|
||||||
|
tft_string.add(LCD_STR_DEGREE);
|
||||||
|
tft_string.add(" / ");
|
||||||
|
tft_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder)));
|
||||||
|
tft_string.add(LCD_STR_DEGREE);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(TFT_WIDTH), 0, COLOR_MENU_TEXT, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // ADVANCED_PAUSE_FEATURE
|
||||||
|
|
||||||
|
#if ENABLED(AUTO_BED_LEVELING_UBL)
|
||||||
|
#define GRID_OFFSET_X 8
|
||||||
|
#define GRID_OFFSET_Y 8
|
||||||
|
#define GRID_WIDTH 192
|
||||||
|
#define GRID_HEIGHT 192
|
||||||
|
#define CONTROL_OFFSET 16
|
||||||
|
|
||||||
|
void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) {
|
||||||
|
|
||||||
|
tft.canvas(GRID_OFFSET_X, GRID_OFFSET_Y, GRID_WIDTH, GRID_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_rectangle(0, 0, GRID_WIDTH, GRID_HEIGHT, COLOR_WHITE);
|
||||||
|
|
||||||
|
for (uint16_t x = 0; x < GRID_MAX_POINTS_X ; x++)
|
||||||
|
for (uint16_t y = 0; y < GRID_MAX_POINTS_Y ; y++)
|
||||||
|
if (position_is_reachable({ ubl.mesh_index_to_xpos(x), ubl.mesh_index_to_ypos(y) }))
|
||||||
|
tft.add_bar(1 + (x * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2, GRID_HEIGHT - 3 - ((y * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 2, 2, COLOR_UBL);
|
||||||
|
|
||||||
|
tft.add_rectangle((x_plot * 2 + 1) * (GRID_WIDTH - 4) / GRID_MAX_POINTS_X / 2 - 1, GRID_HEIGHT - 5 - ((y_plot * 2 + 1) * (GRID_HEIGHT - 4) / GRID_MAX_POINTS_Y / 2), 6, 6, COLOR_UBL);
|
||||||
|
|
||||||
|
const xy_pos_t pos = { ubl.mesh_index_to_xpos(x_plot), ubl.mesh_index_to_ypos(y_plot) },
|
||||||
|
lpos = pos.asLogical();
|
||||||
|
|
||||||
|
tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 - MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(X_LBL);
|
||||||
|
tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
tft_string.set(ftostr52(lpos.x));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, 120, MENU_ITEM_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(Y_LBL);
|
||||||
|
tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
tft_string.set(ftostr52(lpos.y));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
tft.canvas(320, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2 + MENU_ITEM_HEIGHT, 120, MENU_ITEM_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(Z_LBL);
|
||||||
|
tft.add_text(0, MENU_TEXT_Y_OFFSET, COLOR_MENU_TEXT, tft_string);
|
||||||
|
tft_string.set(isnan(ubl.z_values[x_plot][y_plot]) ? "-----" : ftostr43sign(ubl.z_values[x_plot][y_plot]));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(120 - tft_string.width(), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
constexpr uint8_t w = (TFT_WIDTH) / 10;
|
||||||
|
tft.canvas(GRID_OFFSET_X + (GRID_WIDTH - w) / 2, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET - 5, w, MENU_ITEM_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(ui8tostr3rj(x_plot));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
tft.canvas(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET + 16 - 24, GRID_OFFSET_Y + (GRID_HEIGHT - MENU_ITEM_HEIGHT) / 2, w, MENU_ITEM_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(ui8tostr3rj(y_plot));
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(w), MENU_TEXT_Y_OFFSET, COLOR_MENU_VALUE, tft_string);
|
||||||
|
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
touch.clear();
|
||||||
|
draw_menu_navigation = false;
|
||||||
|
add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgUp);
|
||||||
|
add_control(GRID_OFFSET_X + GRID_WIDTH + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT - CONTROL_OFFSET - 32, UBL, - ENCODER_STEPS_PER_MENU_ITEM * GRID_MAX_POINTS_X, imgDown);
|
||||||
|
add_control(GRID_OFFSET_X + CONTROL_OFFSET, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, - ENCODER_STEPS_PER_MENU_ITEM, imgLeft);
|
||||||
|
add_control(GRID_OFFSET_X + GRID_WIDTH - CONTROL_OFFSET - 32, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, UBL, ENCODER_STEPS_PER_MENU_ITEM, imgRight);
|
||||||
|
add_control(320, GRID_OFFSET_Y + GRID_HEIGHT + CONTROL_OFFSET, CLICK, imgLeveling);
|
||||||
|
add_control(224, TFT_HEIGHT - 34, BACK, imgBack);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
#endif // AUTO_BED_LEVELING_UBL
|
||||||
|
|
||||||
|
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||||
|
#include "../../feature/babystep.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
#include "../../module/probe.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define Z_SELECTION_Z 1
|
||||||
|
#define Z_SELECTION_Z_PROBE -1
|
||||||
|
|
||||||
|
struct MotionAxisState {
|
||||||
|
xy_int_t xValuePos, yValuePos, zValuePos, eValuePos, stepValuePos, zTypePos, eNamePos;
|
||||||
|
float currentStepSize = 10.0;
|
||||||
|
int z_selection = Z_SELECTION_Z;
|
||||||
|
uint8_t e_selection = 0;
|
||||||
|
bool homming = false;
|
||||||
|
bool blocked = false;
|
||||||
|
char message[32];
|
||||||
|
};
|
||||||
|
|
||||||
|
MotionAxisState motionAxisState;
|
||||||
|
|
||||||
|
#define E_BTN_COLOR COLOR_YELLOW
|
||||||
|
#define X_BTN_COLOR COLOR_CORAL_RED
|
||||||
|
#define Y_BTN_COLOR COLOR_VIVID_GREEN
|
||||||
|
#define Z_BTN_COLOR COLOR_LIGHT_BLUE
|
||||||
|
|
||||||
|
#define BTN_WIDTH 64
|
||||||
|
#define BTN_HEIGHT 52
|
||||||
|
#define X_MARGIN 20
|
||||||
|
#define Y_MARGIN 15
|
||||||
|
|
||||||
|
static void quick_feedback() {
|
||||||
|
#if HAS_CHIRP
|
||||||
|
ui.chirp(); // Buzz and wait. Is the delay needed for buttons to settle?
|
||||||
|
#if BOTH(HAS_LCD_MENU, USE_BEEPER)
|
||||||
|
for (int8_t i = 5; i--;) { buzzer.tick(); delay(2); }
|
||||||
|
#elif HAS_LCD_MENU
|
||||||
|
delay(10);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
#define CUR_STEP_VALUE_WIDTH 104
|
||||||
|
static void drawCurStepValue() {
|
||||||
|
tft_string.set((uint8_t *)ftostr52sp(motionAxisState.currentStepSize));
|
||||||
|
tft_string.add("mm");
|
||||||
|
tft.canvas(motionAxisState.stepValuePos.x, motionAxisState.stepValuePos.y, CUR_STEP_VALUE_WIDTH, BTN_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_text(tft_string.center(CUR_STEP_VALUE_WIDTH), 0, COLOR_AXIS_HOMED, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void drawCurZSelection() {
|
||||||
|
tft_string.set("Z");
|
||||||
|
tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y, tft_string.width(), 34);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_text(0, 0, Z_BTN_COLOR, tft_string);
|
||||||
|
tft.queue.sync();
|
||||||
|
tft_string.set("Offset");
|
||||||
|
tft.canvas(motionAxisState.zTypePos.x, motionAxisState.zTypePos.y + 34, tft_string.width(), 34);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
if (motionAxisState.z_selection == Z_SELECTION_Z_PROBE) {
|
||||||
|
tft.add_text(0, 0, Z_BTN_COLOR, tft_string);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void drawCurESelection() {
|
||||||
|
tft.canvas(motionAxisState.eNamePos.x, motionAxisState.eNamePos.y, BTN_WIDTH, BTN_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set("E");
|
||||||
|
tft.add_text(0, 0, E_BTN_COLOR , tft_string);
|
||||||
|
tft.add_text(tft_string.width(), 0, E_BTN_COLOR, ui8tostr3rj(motionAxisState.e_selection));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void drawMessage(const char *msg) {
|
||||||
|
tft.canvas(X_MARGIN, TFT_HEIGHT - Y_MARGIN - 34, TFT_HEIGHT / 2, 34);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_text(0, 0, COLOR_YELLOW, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void drawAxisValue(AxisEnum axis) {
|
||||||
|
const float value =
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE ?
|
||||||
|
probe.offset.z :
|
||||||
|
#endif
|
||||||
|
NATIVE_TO_LOGICAL(
|
||||||
|
ui.manual_move.processing ? destination[axis] : current_position[axis] + TERN0(IS_KINEMATIC, ui.manual_move.offset),
|
||||||
|
axis
|
||||||
|
);
|
||||||
|
xy_int_t pos;
|
||||||
|
uint16_t color;
|
||||||
|
switch (axis) {
|
||||||
|
case X_AXIS: pos = motionAxisState.xValuePos; color = X_BTN_COLOR; break;
|
||||||
|
case Y_AXIS: pos = motionAxisState.yValuePos; color = Y_BTN_COLOR; break;
|
||||||
|
case Z_AXIS: pos = motionAxisState.zValuePos; color = Z_BTN_COLOR; break;
|
||||||
|
case E_AXIS: pos = motionAxisState.eValuePos; color = E_BTN_COLOR; break;
|
||||||
|
default: return;
|
||||||
|
}
|
||||||
|
tft.canvas(pos.x, pos.y, BTN_WIDTH + X_MARGIN, BTN_HEIGHT);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft_string.set(ftostr52sp(value));
|
||||||
|
tft.add_text(0, 0, color, tft_string);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void moveAxis(AxisEnum axis, const int8_t direction) {
|
||||||
|
quick_feedback();
|
||||||
|
|
||||||
|
if (axis == E_AXIS && thermalManager.temp_hotend[motionAxisState.e_selection].celsius < EXTRUDE_MINTEMP) {
|
||||||
|
drawMessage("Too cold");
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const float diff = motionAxisState.currentStepSize * direction;
|
||||||
|
|
||||||
|
if (axis == Z_AXIS && motionAxisState.z_selection == Z_SELECTION_Z_PROBE) {
|
||||||
|
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
|
||||||
|
const int16_t babystep_increment = direction * BABYSTEP_SIZE_Z;
|
||||||
|
const bool do_probe = DISABLED(BABYSTEP_HOTEND_Z_OFFSET) || active_extruder == 0;
|
||||||
|
const float bsDiff = planner.steps_to_mm[Z_AXIS] * babystep_increment,
|
||||||
|
new_probe_offset = probe.offset.z + bsDiff,
|
||||||
|
new_offs = TERN(BABYSTEP_HOTEND_Z_OFFSET
|
||||||
|
, do_probe ? new_probe_offset : hotend_offset[active_extruder].z - bsDiff
|
||||||
|
, new_probe_offset
|
||||||
|
);
|
||||||
|
if (WITHIN(new_offs, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) {
|
||||||
|
babystep.add_steps(Z_AXIS, babystep_increment);
|
||||||
|
if (do_probe)
|
||||||
|
probe.offset.z = new_offs;
|
||||||
|
else
|
||||||
|
TERN(BABYSTEP_HOTEND_Z_OFFSET, hotend_offset[active_extruder].z = new_offs, NOOP);
|
||||||
|
drawMessage(""); // clear the error
|
||||||
|
drawAxisValue(axis);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS));
|
||||||
|
}
|
||||||
|
#elif HAS_BED_PROBE
|
||||||
|
// only change probe.offset.z
|
||||||
|
probe.offset.z += diff;
|
||||||
|
if (direction < 0 && current_position[axis] < Z_PROBE_OFFSET_RANGE_MIN) {
|
||||||
|
current_position[axis] = Z_PROBE_OFFSET_RANGE_MIN;
|
||||||
|
drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS));
|
||||||
|
}
|
||||||
|
else if (direction > 0 && current_position[axis] > Z_PROBE_OFFSET_RANGE_MAX) {
|
||||||
|
current_position[axis] = Z_PROBE_OFFSET_RANGE_MAX;
|
||||||
|
drawMessage(GET_TEXT(MSG_LCD_SOFT_ENDSTOPS));
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
drawMessage(""); // clear the error
|
||||||
|
}
|
||||||
|
drawAxisValue(axis);
|
||||||
|
#endif
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!ui.manual_move.processing) {
|
||||||
|
// Get motion limit from software endstops, if any
|
||||||
|
float min, max;
|
||||||
|
soft_endstop.get_manual_axis_limits(axis, min, max);
|
||||||
|
|
||||||
|
// Delta limits XY based on the current offset from center
|
||||||
|
// This assumes the center is 0,0
|
||||||
|
#if ENABLED(DELTA)
|
||||||
|
if (axis != Z_AXIS && axis != E_AXIS) {
|
||||||
|
max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); // (Y_AXIS - axis) == the other axis
|
||||||
|
min = -max;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Get the new position
|
||||||
|
#if IS_KINEMATIC
|
||||||
|
ui.manual_move.offset += diff;
|
||||||
|
if (direction < 0)
|
||||||
|
NOLESS(ui.manual_move.offset, min - current_position[axis]);
|
||||||
|
else
|
||||||
|
NOMORE(ui.manual_move.offset, max - current_position[axis]);
|
||||||
|
#else
|
||||||
|
current_position[axis] += diff;
|
||||||
|
const char *msg = NUL_STR; // clear the error
|
||||||
|
if (direction < 0 && current_position[axis] < min) {
|
||||||
|
current_position[axis] = min;
|
||||||
|
msg = GET_TEXT(MSG_LCD_SOFT_ENDSTOPS);
|
||||||
|
}
|
||||||
|
else if (direction > 0 && current_position[axis] > max) {
|
||||||
|
current_position[axis] = max;
|
||||||
|
msg = GET_TEXT(MSG_LCD_SOFT_ENDSTOPS);
|
||||||
|
}
|
||||||
|
drawMessage(msg);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
ui.manual_move.soon(axis
|
||||||
|
#if MULTI_MANUAL
|
||||||
|
, motionAxisState.e_selection
|
||||||
|
#endif
|
||||||
|
);
|
||||||
|
}
|
||||||
|
|
||||||
|
drawAxisValue(axis);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void e_plus() { moveAxis(E_AXIS, 1); }
|
||||||
|
static void e_minus() { moveAxis(E_AXIS, -1); }
|
||||||
|
static void x_minus() { moveAxis(X_AXIS, -1); }
|
||||||
|
static void x_plus() { moveAxis(X_AXIS, 1); }
|
||||||
|
static void y_plus() { moveAxis(Y_AXIS, 1); }
|
||||||
|
static void y_minus() { moveAxis(Y_AXIS, -1); }
|
||||||
|
static void z_plus() { moveAxis(Z_AXIS, 1); }
|
||||||
|
static void z_minus() { moveAxis(Z_AXIS, -1); }
|
||||||
|
|
||||||
|
#if ENABLED(TOUCH_SCREEN)
|
||||||
|
static void e_select() {
|
||||||
|
motionAxisState.e_selection++;
|
||||||
|
if (motionAxisState.e_selection >= EXTRUDERS) {
|
||||||
|
motionAxisState.e_selection = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
quick_feedback();
|
||||||
|
drawCurESelection();
|
||||||
|
drawAxisValue(E_AXIS);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void do_home() {
|
||||||
|
quick_feedback();
|
||||||
|
drawMessage(GET_TEXT(MSG_LEVEL_BED_HOMING));
|
||||||
|
queue.inject_P(G28_STR);
|
||||||
|
// Disable touch until home is done
|
||||||
|
TERN_(HAS_TFT_XPT2046, touch.disable());
|
||||||
|
drawAxisValue(E_AXIS);
|
||||||
|
drawAxisValue(X_AXIS);
|
||||||
|
drawAxisValue(Y_AXIS);
|
||||||
|
drawAxisValue(Z_AXIS);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void step_size() {
|
||||||
|
motionAxisState.currentStepSize = motionAxisState.currentStepSize / 10.0;
|
||||||
|
if (motionAxisState.currentStepSize < 0.0015) motionAxisState.currentStepSize = 10.0;
|
||||||
|
quick_feedback();
|
||||||
|
drawCurStepValue();
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_BED_PROBE
|
||||||
|
static void z_select() {
|
||||||
|
motionAxisState.z_selection *= -1;
|
||||||
|
quick_feedback();
|
||||||
|
drawCurZSelection();
|
||||||
|
drawAxisValue(Z_AXIS);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static void disable_steppers() {
|
||||||
|
quick_feedback();
|
||||||
|
queue.inject_P(PSTR("M84"));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void drawBtn(int x, int y, const char *label, intptr_t data, MarlinImage img, uint16_t bgColor, bool enabled = true) {
|
||||||
|
uint16_t width = Images[imgBtn52Rounded].width;
|
||||||
|
uint16_t height = Images[imgBtn52Rounded].height;
|
||||||
|
|
||||||
|
if (!enabled) bgColor = COLOR_CONTROL_DISABLED;
|
||||||
|
|
||||||
|
tft.canvas(x, y, width, height);
|
||||||
|
tft.set_background(COLOR_BACKGROUND);
|
||||||
|
tft.add_image(0, 0, imgBtn52Rounded, bgColor, COLOR_BACKGROUND, COLOR_DARKGREY);
|
||||||
|
|
||||||
|
// TODO: Make an add_text() taking a font arg
|
||||||
|
if (label) {
|
||||||
|
tft_string.set(label);
|
||||||
|
tft_string.trim();
|
||||||
|
tft.add_text(tft_string.center(width), height / 2 - tft_string.font_height() / 2, bgColor, tft_string);
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
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));
|
||||||
|
}
|
||||||
|
|
||||||
|
void MarlinUI::move_axis_screen() {
|
||||||
|
// Reset
|
||||||
|
defer_status_screen(true);
|
||||||
|
motionAxisState.blocked = false;
|
||||||
|
TERN_(HAS_TFT_XPT2046, touch.enable());
|
||||||
|
|
||||||
|
ui.clear_lcd();
|
||||||
|
|
||||||
|
TERN_(TOUCH_SCREEN, touch.clear());
|
||||||
|
|
||||||
|
const bool busy = printingIsActive();
|
||||||
|
|
||||||
|
// Babysteps during printing? Select babystep for Z probe offset
|
||||||
|
if (busy && ENABLED(BABYSTEP_ZPROBE_OFFSET))
|
||||||
|
motionAxisState.z_selection = Z_SELECTION_Z_PROBE;
|
||||||
|
|
||||||
|
// ROW 1 -> E- Y- CurY Z+
|
||||||
|
int x = X_MARGIN, y = Y_MARGIN, spacing = 0;
|
||||||
|
|
||||||
|
drawBtn(x, y, "E+", (intptr_t)e_plus, imgUp, E_BTN_COLOR, !busy);
|
||||||
|
|
||||||
|
spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2;
|
||||||
|
x += BTN_WIDTH + spacing;
|
||||||
|
drawBtn(x, y, "Y+", (intptr_t)y_plus, imgUp, Y_BTN_COLOR, !busy);
|
||||||
|
|
||||||
|
// Cur Y
|
||||||
|
x += BTN_WIDTH;
|
||||||
|
motionAxisState.yValuePos.x = x + 2;
|
||||||
|
motionAxisState.yValuePos.y = y;
|
||||||
|
drawAxisValue(Y_AXIS);
|
||||||
|
|
||||||
|
x += spacing;
|
||||||
|
drawBtn(x, y, "Z+", (intptr_t)z_plus, imgUp, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step
|
||||||
|
|
||||||
|
// ROW 2 -> "Ex" X- HOME X+ "Z"
|
||||||
|
y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3;
|
||||||
|
x = X_MARGIN;
|
||||||
|
spacing = (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4;
|
||||||
|
|
||||||
|
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));
|
||||||
|
|
||||||
|
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));
|
||||||
|
|
||||||
|
x += BTN_WIDTH + spacing;
|
||||||
|
uint16_t xplus_x = x;
|
||||||
|
drawBtn(x, y, "X+", (intptr_t)x_plus, imgRight, X_BTN_COLOR, !busy);
|
||||||
|
|
||||||
|
x += BTN_WIDTH + spacing;
|
||||||
|
motionAxisState.zTypePos.x = x;
|
||||||
|
motionAxisState.zTypePos.y = y;
|
||||||
|
drawCurZSelection();
|
||||||
|
#if BOTH(HAS_BED_PROBE, TOUCH_SCREEN)
|
||||||
|
if (!busy) touch.add_control(BUTTON, x, y, BTN_WIDTH, 34 * 2, (intptr_t)z_select);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// ROW 3 -> E- CurX Y- Z-
|
||||||
|
y += BTN_HEIGHT + (TFT_HEIGHT - Y_MARGIN * 2 - 4 * BTN_HEIGHT) / 3;
|
||||||
|
x = X_MARGIN;
|
||||||
|
spacing = (TFT_WIDTH - X_MARGIN * 2 - 3 * BTN_WIDTH) / 2;
|
||||||
|
|
||||||
|
drawBtn(x, y, "E-", (intptr_t)e_minus, imgDown, E_BTN_COLOR, !busy);
|
||||||
|
|
||||||
|
// Cur E
|
||||||
|
motionAxisState.eValuePos.x = x;
|
||||||
|
motionAxisState.eValuePos.y = y + BTN_HEIGHT + 2;
|
||||||
|
drawAxisValue(E_AXIS);
|
||||||
|
|
||||||
|
// Cur X
|
||||||
|
motionAxisState.xValuePos.x = BTN_WIDTH + (TFT_WIDTH - X_MARGIN * 2 - 5 * BTN_WIDTH) / 4; //X- pos
|
||||||
|
motionAxisState.xValuePos.y = y - 10;
|
||||||
|
drawAxisValue(X_AXIS);
|
||||||
|
|
||||||
|
x += BTN_WIDTH + spacing;
|
||||||
|
drawBtn(x, y, "Y-", (intptr_t)y_minus, imgDown, Y_BTN_COLOR, !busy);
|
||||||
|
|
||||||
|
x += BTN_WIDTH + spacing;
|
||||||
|
drawBtn(x, y, "Z-", (intptr_t)z_minus, imgDown, Z_BTN_COLOR, !busy || ENABLED(BABYSTEP_ZPROBE_OFFSET)); //only enabled when not busy or have baby step
|
||||||
|
|
||||||
|
// Cur Z
|
||||||
|
motionAxisState.zValuePos.x = x;
|
||||||
|
motionAxisState.zValuePos.y = y + BTN_HEIGHT + 2;
|
||||||
|
drawAxisValue(Z_AXIS);
|
||||||
|
|
||||||
|
// ROW 4 -> step_size disable steppers back
|
||||||
|
y = TFT_HEIGHT - Y_MARGIN - 32; //
|
||||||
|
x = TFT_WIDTH / 2 - CUR_STEP_VALUE_WIDTH / 2;
|
||||||
|
motionAxisState.stepValuePos.x = x;
|
||||||
|
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));
|
||||||
|
}
|
||||||
|
|
||||||
|
// 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));
|
||||||
|
}
|
||||||
|
|
||||||
|
#undef BTN_WIDTH
|
||||||
|
#undef BTN_HEIGHT
|
||||||
|
|
||||||
|
#endif // HAS_UI_480x320
|
43
Marlin/src/lcd/tft/ui_1024x600.h
Normal file
43
Marlin/src/lcd/tft/ui_1024x600.h
Normal file
|
@ -0,0 +1,43 @@
|
||||||
|
/**
|
||||||
|
* Marlin 3D Printer Firmware
|
||||||
|
* Copyright (c) 2020 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
|
||||||
|
|
||||||
|
#define MARLIN_LOGO_FULL_SIZE MarlinLogo480x320x16
|
||||||
|
|
||||||
|
#include "ui_common.h"
|
||||||
|
|
||||||
|
#define TFT_STATUS_TOP_Y 4
|
||||||
|
#define TFT_TOP_LINE_Y 4
|
||||||
|
|
||||||
|
#define MENU_TEXT_X_OFFSET 16
|
||||||
|
#define MENU_TEXT_Y_OFFSET 7
|
||||||
|
|
||||||
|
#define MENU_ITEM_ICON_X 5
|
||||||
|
#define MENU_ITEM_ICON_Y 5
|
||||||
|
#define MENU_ITEM_ICON_SPACE 42
|
||||||
|
|
||||||
|
#define MENU_FONT_NAME Helvetica18
|
||||||
|
#define SYMBOLS_FONT_NAME Helvetica18_symbols
|
||||||
|
#define MENU_ITEM_HEIGHT 43
|
||||||
|
#define FONT_LINE_HEIGHT 34
|
||||||
|
|
||||||
|
#define MENU_LINE_HEIGHT (MENU_ITEM_HEIGHT + 2)
|
|
@ -39,6 +39,10 @@
|
||||||
#include "ui_320x240.h"
|
#include "ui_320x240.h"
|
||||||
#elif HAS_UI_480x320 || HAS_UI_480x272
|
#elif HAS_UI_480x320 || HAS_UI_480x272
|
||||||
#include "ui_480x320.h"
|
#include "ui_480x320.h"
|
||||||
|
#elif HAS_UI_1024x600
|
||||||
|
#include "ui_1024x600.h"
|
||||||
|
#else
|
||||||
|
#error "Unsupported display resolution!"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater);
|
void draw_heater_status(uint16_t x, uint16_t y, const int8_t Heater);
|
||||||
|
|
|
@ -22,7 +22,7 @@
|
||||||
|
|
||||||
#include "tft_io.h"
|
#include "tft_io.h"
|
||||||
|
|
||||||
#if HAS_SPI_TFT || HAS_FSMC_TFT
|
#if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT
|
||||||
|
|
||||||
#include "st7735.h"
|
#include "st7735.h"
|
||||||
#include "st7789v.h"
|
#include "st7789v.h"
|
||||||
|
@ -90,6 +90,8 @@ if (lcd_id != 0xFFFFFFFF) return;
|
||||||
lcd_id = io.GetID() & 0xFFFF;
|
lcd_id = io.GetID() & 0xFFFF;
|
||||||
|
|
||||||
switch (lcd_id) {
|
switch (lcd_id) {
|
||||||
|
case LTDC_RGB:
|
||||||
|
break;
|
||||||
case ST7796: // ST7796S 480x320
|
case ST7796: // ST7796S 480x320
|
||||||
DEBUG_ECHO_MSG(" ST7796S");
|
DEBUG_ECHO_MSG(" ST7796S");
|
||||||
write_esc_sequence(st7796s_init);
|
write_esc_sequence(st7796s_init);
|
||||||
|
@ -144,6 +146,17 @@ void TFT_IO::set_window(uint16_t Xmin, uint16_t Ymin, uint16_t Xmax, uint16_t Ym
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
switch (lcd_id) {
|
switch (lcd_id) {
|
||||||
|
case LTDC_RGB:
|
||||||
|
io.WriteReg(0x01);
|
||||||
|
io.WriteData(Xmin);
|
||||||
|
io.WriteReg(0x02);
|
||||||
|
io.WriteData(Xmax);
|
||||||
|
io.WriteReg(0x03);
|
||||||
|
io.WriteData(Ymin);
|
||||||
|
io.WriteReg(0x04);
|
||||||
|
io.WriteData(Ymax);
|
||||||
|
io.WriteReg(0x00);
|
||||||
|
break;
|
||||||
case ST7735: // ST7735 160x128
|
case ST7735: // ST7735 160x128
|
||||||
case ST7789: // ST7789V 320x240
|
case ST7789: // ST7789V 320x240
|
||||||
case ST7796: // ST7796 480x320
|
case ST7796: // ST7796 480x320
|
||||||
|
|
|
@ -23,14 +23,16 @@
|
||||||
|
|
||||||
#include "../../inc/MarlinConfig.h"
|
#include "../../inc/MarlinConfig.h"
|
||||||
|
|
||||||
#if HAS_SPI_TFT || HAS_FSMC_TFT
|
#if HAS_SPI_TFT || HAS_FSMC_TFT || HAS_LTDC_TFT
|
||||||
|
|
||||||
#if HAS_SPI_TFT
|
#if HAS_SPI_TFT
|
||||||
#include HAL_PATH(../../HAL, tft/tft_spi.h)
|
#include HAL_PATH(../../HAL, tft/tft_spi.h)
|
||||||
#elif HAS_FSMC_TFT
|
#elif HAS_FSMC_TFT
|
||||||
#include HAL_PATH(../../HAL, tft/tft_fsmc.h)
|
#include HAL_PATH(../../HAL, tft/tft_fsmc.h)
|
||||||
|
#elif HAS_LTDC_TFT
|
||||||
|
#include HAL_PATH(../../HAL, tft/tft_ltdc.h)
|
||||||
#else
|
#else
|
||||||
#error "TFT IO only supports SPI or FSMC interface"
|
#error "TFT IO only supports SPI, FSMC or LTDC interface"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define TFT_EXCHANGE_XY (1UL << 1)
|
#define TFT_EXCHANGE_XY (1UL << 1)
|
||||||
|
@ -91,6 +93,7 @@
|
||||||
#define TOUCH_ORIENTATION TOUCH_LANDSCAPE
|
#define TOUCH_ORIENTATION TOUCH_LANDSCAPE
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#define LTDC_RGB 0xABAB
|
||||||
#define SSD1963 0x5761
|
#define SSD1963 0x5761
|
||||||
#define ST7735 0x89F0
|
#define ST7735 0x89F0
|
||||||
#define ST7789 0x8552
|
#define ST7789 0x8552
|
||||||
|
|
|
@ -631,6 +631,8 @@
|
||||||
#include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1
|
#include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1
|
||||||
#elif MB(NUCLEO_F767ZI)
|
#elif MB(NUCLEO_F767ZI)
|
||||||
#include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI
|
#include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI
|
||||||
|
#elif MB(BTT_SKR_SE_BX)
|
||||||
|
#include "stm32h7/pins_BTT_SKR_SE_BX.h" // STM32H7 env:BTT_SKR_SE_BX
|
||||||
#elif MB(TEENSY41)
|
#elif MB(TEENSY41)
|
||||||
#include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41
|
#include "teensy4/pins_TEENSY41.h" // Teensy-4.x env:teensy41
|
||||||
#elif MB(T41U5XBB)
|
#elif MB(T41U5XBB)
|
||||||
|
|
226
Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h
Normal file
226
Marlin/src/pins/stm32h7/pins_BTT_SKR_SE_BX.h
Normal file
|
@ -0,0 +1,226 @@
|
||||||
|
/**
|
||||||
|
* 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
|
||||||
|
|
||||||
|
#if NOT_TARGET(STM32H7)
|
||||||
|
#error "Oops! Select an STM32H7 board in 'Tools > Board.'"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BOARD_INFO_NAME "BTT SKR SE BX"
|
||||||
|
#define DEFAULT_MACHINE_NAME "BIQU-BX"
|
||||||
|
|
||||||
|
// Onboard I2C EEPROM
|
||||||
|
#define I2C_EEPROM
|
||||||
|
#define MARLIN_EEPROM_SIZE 0x1000 // 4KB (24C32 ... 32Kb = 4KB)
|
||||||
|
|
||||||
|
// USB Flash Drive support
|
||||||
|
#define HAS_OTG_USB_HOST_SUPPORT
|
||||||
|
|
||||||
|
//
|
||||||
|
// Limit Switches
|
||||||
|
//
|
||||||
|
#define X_MIN_PIN PB11
|
||||||
|
#define X_MAX_PIN PD13
|
||||||
|
#define Y_MIN_PIN PB12
|
||||||
|
#define Y_MAX_PIN PB13
|
||||||
|
#define Z_MIN_PIN PD12
|
||||||
|
#define Z_MAX_PIN PD11
|
||||||
|
|
||||||
|
#define FIL_RUNOUT_PIN PD13
|
||||||
|
#define FIL_RUNOUT2_PIN PB13
|
||||||
|
|
||||||
|
#define LED_PIN PA13
|
||||||
|
#define BEEPER_PIN PA14
|
||||||
|
|
||||||
|
#define TFT_BACKLIGHT_PIN PB5
|
||||||
|
|
||||||
|
#define POWER_MONITOR_PIN PB0
|
||||||
|
#define RPI_POWER_PIN PE5
|
||||||
|
|
||||||
|
#define SAFE_POWER_PIN PI11
|
||||||
|
#define SERVO0_PIN PA2
|
||||||
|
|
||||||
|
//
|
||||||
|
// Z Probe (when not Z_MIN_PIN)
|
||||||
|
//
|
||||||
|
#ifndef Z_MIN_PROBE_PIN
|
||||||
|
#define Z_MIN_PROBE_PIN PH2 // Probe
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Steppers
|
||||||
|
//
|
||||||
|
#define X_STEP_PIN PG13
|
||||||
|
#define X_DIR_PIN PG12
|
||||||
|
#define X_ENABLE_PIN PG14
|
||||||
|
#define X_CS_PIN PG10
|
||||||
|
|
||||||
|
#define Y_STEP_PIN PB3
|
||||||
|
#define Y_DIR_PIN PD3
|
||||||
|
#define Y_ENABLE_PIN PB4
|
||||||
|
#define Y_CS_PIN PD4
|
||||||
|
|
||||||
|
#define Z_STEP_PIN PD7
|
||||||
|
#define Z_DIR_PIN PD6
|
||||||
|
#define Z_ENABLE_PIN PG9
|
||||||
|
#define Z_CS_PIN PD5
|
||||||
|
|
||||||
|
#define E0_STEP_PIN PC14
|
||||||
|
#define E0_DIR_PIN PC13
|
||||||
|
#define E0_ENABLE_PIN PC15
|
||||||
|
#define E0_CS_PIN PI8
|
||||||
|
|
||||||
|
#define E1_STEP_PIN PA8
|
||||||
|
#define E1_DIR_PIN PC9
|
||||||
|
#define E1_ENABLE_PIN PD2
|
||||||
|
#define E1_CS_PIN PC8
|
||||||
|
|
||||||
|
//
|
||||||
|
// Software SPI pins for TMC2130 stepper drivers
|
||||||
|
//
|
||||||
|
#if ENABLED(TMC_USE_SW_SPI)
|
||||||
|
#ifndef TMC_SW_MOSI
|
||||||
|
#define TMC_SW_MOSI PC6
|
||||||
|
#endif
|
||||||
|
#ifndef TMC_SW_MISO
|
||||||
|
#define TMC_SW_MISO PG3
|
||||||
|
#endif
|
||||||
|
#ifndef TMC_SW_SCK
|
||||||
|
#define TMC_SW_SCK PC7
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if HAS_TMC_UART
|
||||||
|
/**
|
||||||
|
* TMC2208/TMC2209 stepper drivers
|
||||||
|
*
|
||||||
|
* Hardware serial communication ports.
|
||||||
|
* If undefined software serial is used according to the pins below
|
||||||
|
*/
|
||||||
|
//#define X_HARDWARE_SERIAL Serial
|
||||||
|
//#define X2_HARDWARE_SERIAL Serial1
|
||||||
|
//#define Y_HARDWARE_SERIAL Serial1
|
||||||
|
//#define Y2_HARDWARE_SERIAL Serial1
|
||||||
|
//#define Z_HARDWARE_SERIAL Serial1
|
||||||
|
//#define Z2_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E0_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E1_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E2_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E3_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E4_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E5_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E6_HARDWARE_SERIAL Serial1
|
||||||
|
//#define E7_HARDWARE_SERIAL Serial1
|
||||||
|
|
||||||
|
//
|
||||||
|
// Software serial
|
||||||
|
//
|
||||||
|
#define X_SERIAL_TX_PIN PG10
|
||||||
|
#define X_SERIAL_RX_PIN PG10
|
||||||
|
|
||||||
|
#define Y_SERIAL_TX_PIN PD4
|
||||||
|
#define Y_SERIAL_RX_PIN PD4
|
||||||
|
|
||||||
|
#define Z_SERIAL_TX_PIN PD5
|
||||||
|
#define Z_SERIAL_RX_PIN PD5
|
||||||
|
|
||||||
|
#define E0_SERIAL_TX_PIN PI8
|
||||||
|
#define E0_SERIAL_RX_PIN PI8
|
||||||
|
|
||||||
|
#define E1_SERIAL_TX_PIN PC8
|
||||||
|
#define E1_SERIAL_RX_PIN PC8
|
||||||
|
|
||||||
|
// Reduce baud rate to improve software serial reliability
|
||||||
|
#define TMC_BAUD_RATE 19200
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//
|
||||||
|
// Temperature Sensors
|
||||||
|
//
|
||||||
|
#define TEMP_0_PIN PH4 // TH0
|
||||||
|
#define TEMP_1_PIN PA3 // TH1
|
||||||
|
#define TEMP_BED_PIN PH5 // TB
|
||||||
|
|
||||||
|
//
|
||||||
|
// Heaters / Fans
|
||||||
|
//
|
||||||
|
#define HEATER_0_PIN PC4
|
||||||
|
#define HEATER_1_PIN PC5
|
||||||
|
#define HEATER_BED_PIN PA4
|
||||||
|
|
||||||
|
#define FAN_PIN PA5 // "FAN0"
|
||||||
|
#define FAN1_PIN PA6 // "FAN1"
|
||||||
|
#define FAN2_PIN PA7 // "FAN2"
|
||||||
|
|
||||||
|
#define NEOPIXEL_PIN PH3
|
||||||
|
#define NEOPIXEL2_PIN PB1
|
||||||
|
|
||||||
|
#if HAS_LTDC_TFT
|
||||||
|
|
||||||
|
// LTDC_LCD Timing
|
||||||
|
#define LTDC_LCD_CLK 50 // LTDC clock frequency = 50Mhz
|
||||||
|
#define LTDC_LCD_HSYNC 30 // Horizontal synchronization
|
||||||
|
#define LTDC_LCD_HBP 114 // Horizontal back porch
|
||||||
|
#define LTDC_LCD_HFP 16 // Horizontal front porch
|
||||||
|
#define LTDC_LCD_VSYNC 3 // Vertical synchronization
|
||||||
|
#define LTDC_LCD_VBP 32 // Vertical back porch
|
||||||
|
#define LTDC_LCD_VFP 10 // Vertical front porch
|
||||||
|
|
||||||
|
#define TFT_BACKLIGHT_PIN PB5
|
||||||
|
#define LCD_DE_PIN PF10
|
||||||
|
#define LCD_CLK_PIN PG7
|
||||||
|
#define LCD_VSYNC_PIN PI9
|
||||||
|
#define LCD_HSYNC_PIN PI10
|
||||||
|
#define LCD_R7_PIN PG6 // R5
|
||||||
|
#define LCD_R6_PIN PH12
|
||||||
|
#define LCD_R5_PIN PH11
|
||||||
|
#define LCD_R4_PIN PH10
|
||||||
|
#define LCD_R3_PIN PH9
|
||||||
|
#define LCD_G7_PIN PI2 // G6
|
||||||
|
#define LCD_G6_PIN PI1
|
||||||
|
#define LCD_G5_PIN PI0
|
||||||
|
#define LCD_G4_PIN PH15
|
||||||
|
#define LCD_G3_PIN PH14
|
||||||
|
#define LCD_G2_PIN PH13
|
||||||
|
#define LCD_B7_PIN PI7 // B5
|
||||||
|
#define LCD_B6_PIN PI6
|
||||||
|
#define LCD_B5_PIN PI5
|
||||||
|
#define LCD_B4_PIN PI4
|
||||||
|
#define LCD_B3_PIN PG11
|
||||||
|
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define BTN_EN1 PH6
|
||||||
|
#define BTN_EN2 PH7
|
||||||
|
#define BTN_ENC PH8
|
||||||
|
|
||||||
|
#ifndef SDCARD_CONNECTION
|
||||||
|
#define SDCARD_CONNECTION ONBOARD
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define SOFTWARE_SPI
|
||||||
|
#define SDSS PA15
|
||||||
|
#define SS_PIN SDSS
|
||||||
|
#define SD_SCK_PIN PC10
|
||||||
|
#define SD_MISO_PIN PC11
|
||||||
|
#define SD_MOSI_PIN PC12
|
||||||
|
#define SD_DETECT_PIN PI3
|
56
buildroot/share/PlatformIO/boards/BTT_SKR_SE_BX.json
Normal file
56
buildroot/share/PlatformIO/boards/BTT_SKR_SE_BX.json
Normal file
|
@ -0,0 +1,56 @@
|
||||||
|
{
|
||||||
|
"build": {
|
||||||
|
"core": "stm32",
|
||||||
|
"cpu": "cortex-m7",
|
||||||
|
"extra_flags": "-DSTM32H743xx",
|
||||||
|
"f_cpu": "400000000L",
|
||||||
|
"mcu": "stm32h743iit6",
|
||||||
|
"variant": "BTT_SKR_SE_BX"
|
||||||
|
},
|
||||||
|
"debug": {
|
||||||
|
"jlink_device": "STM32H743II",
|
||||||
|
"openocd_target": "stm32h7x",
|
||||||
|
"svd_path": "STM32H7x3.svd",
|
||||||
|
"tools": {
|
||||||
|
"stlink": {
|
||||||
|
"server": {
|
||||||
|
"arguments": [
|
||||||
|
"-f",
|
||||||
|
"scripts/interface/stlink.cfg",
|
||||||
|
"-c",
|
||||||
|
"transport select hla_swd",
|
||||||
|
"-f",
|
||||||
|
"scripts/target/stm32h7x.cfg",
|
||||||
|
"-c",
|
||||||
|
"reset_config none"
|
||||||
|
],
|
||||||
|
"executable": "bin/openocd",
|
||||||
|
"package": "tool-openocd"
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
},
|
||||||
|
"frameworks": [
|
||||||
|
"arduino",
|
||||||
|
"stm32cube"
|
||||||
|
],
|
||||||
|
"name": "STM32H743II (1024k RAM. 2048k Flash)",
|
||||||
|
"upload": {
|
||||||
|
"disable_flushing": false,
|
||||||
|
"maximum_ram_size": 1048576,
|
||||||
|
"maximum_size": 2097152,
|
||||||
|
"protocol": "stlink",
|
||||||
|
"protocols": [
|
||||||
|
"stlink",
|
||||||
|
"dfu",
|
||||||
|
"jlink",
|
||||||
|
"cmsis-dap"
|
||||||
|
],
|
||||||
|
"offset_address": "0x8020000",
|
||||||
|
"require_upload_port": true,
|
||||||
|
"use_1200bps_touch": false,
|
||||||
|
"wait_for_upload_port": false
|
||||||
|
},
|
||||||
|
"url": "https://www.st.com/en/microcontrollers-microprocessors/stm32h743ii.html",
|
||||||
|
"vendor": "Generic"
|
||||||
|
}
|
|
@ -0,0 +1,491 @@
|
||||||
|
/*
|
||||||
|
*******************************************************************************
|
||||||
|
* Copyright (c) 2019, STMicroelectronics
|
||||||
|
* All rights reserved.
|
||||||
|
*
|
||||||
|
* Redistribution and use in source and binary forms, with or without
|
||||||
|
* modification, are permitted provided that the following conditions are met:
|
||||||
|
*
|
||||||
|
* 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer.
|
||||||
|
* 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
* this list of conditions and the following disclaimer in the documentation
|
||||||
|
* and/or other materials provided with the distribution.
|
||||||
|
* 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||||
|
* may be used to endorse or promote products derived from this software
|
||||||
|
* without specific prior written permission.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
* AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
* IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||||
|
* DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||||
|
* FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
* DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||||
|
* SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||||
|
* OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
* OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
*******************************************************************************
|
||||||
|
* Automatically generated from STM32H743ZITx.xml
|
||||||
|
*/
|
||||||
|
#include "Arduino.h"
|
||||||
|
#include "PeripheralPins.h"
|
||||||
|
|
||||||
|
/* =====
|
||||||
|
* Note: Commented lines are alternative possibilities which are not used per default.
|
||||||
|
* If you change them, you will have to know what you do
|
||||||
|
* =====
|
||||||
|
*/
|
||||||
|
|
||||||
|
//*** ADC ***
|
||||||
|
|
||||||
|
#ifdef HAL_ADC_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_ADC[] = {
|
||||||
|
{PA_3, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC1_INP15
|
||||||
|
{PH_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 15, 0)}, // ADC3_INP15
|
||||||
|
{PH_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC3_INP16
|
||||||
|
{PA_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 16, 0)}, // ADC1_INP16
|
||||||
|
{PA_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 17, 0)}, // ADC1_INP17
|
||||||
|
{PA_2, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 14, 0)}, // ADC1_INP14
|
||||||
|
{PA_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 18, 0)}, // ADC1_INP18
|
||||||
|
{PA_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 19, 0)}, // ADC1_INP19
|
||||||
|
{PA_6, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC1_INP3
|
||||||
|
{PA_7, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC1_INP7
|
||||||
|
{PB_0, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC1_INP9
|
||||||
|
{PB_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC1_INP5
|
||||||
|
{PC_0, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC3_INP10
|
||||||
|
{PC_1, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 10, 0)}, // ADC1_INN10
|
||||||
|
{PC_2, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 0, 0)}, // ADC3_INN0
|
||||||
|
{PC_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // ADC3_INP1
|
||||||
|
{PC_4, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC1_INP4
|
||||||
|
{PC_5, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC1_INP8
|
||||||
|
{PF_3, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 5, 0)}, // ADC3_INP5
|
||||||
|
{PF_4, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 9, 0)}, // ADC3_INP9
|
||||||
|
{PF_5, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 4, 0)}, // ADC3_INP4
|
||||||
|
{PF_6, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 8, 0)}, // ADC3_INP8
|
||||||
|
{PF_7, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 3, 0)}, // ADC3_INP3
|
||||||
|
{PF_8, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 7, 0)}, // ADC3_INP7
|
||||||
|
{PF_9, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC3_INP2
|
||||||
|
{PF_10, ADC3, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC3_INP6
|
||||||
|
{PF_11, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC1_INP2
|
||||||
|
{PF_12, ADC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC1_INP6
|
||||||
|
{PF_13, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // ADC2_INP2
|
||||||
|
{PF_14, ADC2, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 6, 0)}, // ADC2_INP6
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** DAC ***
|
||||||
|
|
||||||
|
#ifdef HAL_DAC_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_DAC[] = {
|
||||||
|
{PA_4, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 1, 0)}, // DAC1_OUT1
|
||||||
|
{PA_5, DAC1, STM_PIN_DATA_EXT(STM_MODE_ANALOG, GPIO_NOPULL, 0, 2, 0)}, // DAC1_OUT2
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** I2C ***
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_I2C_SDA[] = {
|
||||||
|
// {PB_7, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // LD2 LED_BLUE (ZI)
|
||||||
|
{PB_9, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_7, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, // LD2 LED_BLUE (ZI)
|
||||||
|
// {PB_9, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)},
|
||||||
|
{PB_11, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
// {PC_9, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)},
|
||||||
|
{PD_13, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)},
|
||||||
|
{PF_0, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
{PF_15, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_I2C_SCL[] = {
|
||||||
|
// {PA_8, I2C3, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C3)}, // USB SOF
|
||||||
|
// {PB_6, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)}, // QSPI_CS
|
||||||
|
{PB_8, I2C1, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C1)},
|
||||||
|
{PB_6, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)}, // QSPI_CS
|
||||||
|
// {PB_8, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF6_I2C4)},
|
||||||
|
{PB_10, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
{PD_12, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)},
|
||||||
|
{PF_1, I2C2, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C2)},
|
||||||
|
{PF_14, I2C4, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_NOPULL, GPIO_AF4_I2C4)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** PWM ***
|
||||||
|
|
||||||
|
#ifdef HAL_TIM_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_PWM[] = {
|
||||||
|
// {PA_0, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
// {PA_0, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 1, 0)}, // TIM5_CH1
|
||||||
|
// {PA_1, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - ETH RMII Ref Clk
|
||||||
|
// {PA_1, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 2, 0)}, // TIM5_CH2 - ETH RMII Ref Clk
|
||||||
|
// {PA_1, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N - ETH RMII Ref Clk
|
||||||
|
// {PA_2, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3 - ETH RMII MDIO
|
||||||
|
{PA_2, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 3, 0)}, // TIM5_CH3 - ETH RMII MDIO
|
||||||
|
// {PA_2, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1 - ETH RMII MDIO
|
||||||
|
// {PA_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||||
|
// {PA_3, TIM5, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM5, 4, 0)}, // TIM5_CH4
|
||||||
|
{PA_3, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2
|
||||||
|
// {PA_5, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
{PA_5, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N
|
||||||
|
// {PA_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
{PA_6, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
|
||||||
|
// {PA_7, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
// {PA_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2 - Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
// {PA_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 1)}, // TIM8_CH1N - Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
{PA_7, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1 - Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
// {PA_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1 - USB SOF
|
||||||
|
// {PA_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2 - USB VBUS
|
||||||
|
// {PA_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3 - USB ID
|
||||||
|
// {PA_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4 - USB DM
|
||||||
|
// {PA_15, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 1, 0)}, // TIM2_CH1
|
||||||
|
{PB_0, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - LD1 LED_GREEN
|
||||||
|
// {PB_0, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3 - LD1 LED_GREEN
|
||||||
|
// {PB_0, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - LD1 LED_GREEN
|
||||||
|
// {PB_1, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
{PB_1, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||||
|
// {PB_1, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||||
|
// {PB_3, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 2, 0)}, // TIM2_CH2 - SWO
|
||||||
|
{PB_4, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
{PB_5, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||||
|
// {PB_6, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||||
|
{PB_6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N
|
||||||
|
// {PB_7, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2 - LD2 LED_BLUE (ZI)
|
||||||
|
{PB_7, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N - LD2 LED_BLUE (ZI)
|
||||||
|
{PB_8, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||||
|
// {PB_8, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1
|
||||||
|
// {PB_9, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||||
|
{PB_9, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1
|
||||||
|
// {PB_10, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 3, 0)}, // TIM2_CH3
|
||||||
|
// {PB_11, TIM2, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM2, 4, 0)}, // TIM2_CH4
|
||||||
|
// {PB_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N - Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
{PB_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N - LD3 LED_RED
|
||||||
|
// {PB_14, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 1)}, // TIM8_CH2N - LD3 LED_RED
|
||||||
|
// {PB_14, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 1, 0)}, // TIM12_CH1 - LD3 LED_RED
|
||||||
|
// {PB_15, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
{PB_15, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 1)}, // TIM8_CH3N
|
||||||
|
// {PB_15, TIM12, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM12, 2, 0)}, // TIM12_CH2
|
||||||
|
// {PC_6, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 1, 0)}, // TIM3_CH1
|
||||||
|
{PC_6, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 1, 0)}, // TIM8_CH1
|
||||||
|
{PC_7, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 2, 0)}, // TIM3_CH2
|
||||||
|
// {PC_7, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 2, 0)}, // TIM8_CH2
|
||||||
|
// {PC_8, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 3, 0)}, // TIM3_CH3
|
||||||
|
{PC_8, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 3, 0)}, // TIM8_CH3
|
||||||
|
{PC_9, TIM3, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM3, 4, 0)}, // TIM3_CH4
|
||||||
|
// {PC_9, TIM8, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_TIM8, 4, 0)}, // TIM8_CH4
|
||||||
|
{PD_12, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 1, 0)}, // TIM4_CH1
|
||||||
|
{PD_13, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 2, 0)}, // TIM4_CH2
|
||||||
|
{PD_14, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 3, 0)}, // TIM4_CH3
|
||||||
|
{PD_15, TIM4, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF2_TIM4, 4, 0)}, // TIM4_CH4
|
||||||
|
{PE_4, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 1)}, // TIM15_CH1N
|
||||||
|
{PE_5, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 1, 0)}, // TIM15_CH1
|
||||||
|
{PE_6, TIM15, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_TIM15, 2, 0)}, // TIM15_CH2
|
||||||
|
{PE_8, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 1)}, // TIM1_CH1N
|
||||||
|
{PE_9, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 1, 0)}, // TIM1_CH1
|
||||||
|
{PE_10, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 1)}, // TIM1_CH2N
|
||||||
|
{PE_11, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 2, 0)}, // TIM1_CH2
|
||||||
|
{PE_12, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 1)}, // TIM1_CH3N
|
||||||
|
{PE_13, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 3, 0)}, // TIM1_CH3
|
||||||
|
{PE_14, TIM1, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM1, 4, 0)}, // TIM1_CH4
|
||||||
|
{PF_6, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 0)}, // TIM16_CH1
|
||||||
|
{PF_7, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 0)}, // TIM17_CH1
|
||||||
|
{PF_8, TIM13, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM13, 1, 0)}, // TIM13_CH1
|
||||||
|
// {PF_8, TIM16, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM16, 1, 1)}, // TIM16_CH1N
|
||||||
|
{PF_9, TIM14, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF9_TIM14, 1, 0)}, // TIM14_CH1
|
||||||
|
// {PF_9, TIM17, STM_PIN_DATA_EXT(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF1_TIM17, 1, 1)}, // TIM17_CH1N
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** SERIAL ***
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_TX[] = {
|
||||||
|
{PA_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PA_2, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // ETH RMII MDIO
|
||||||
|
// {PA_9, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB VBUS
|
||||||
|
{PA_9, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB VBUS
|
||||||
|
// {PA_12, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, // USB DP
|
||||||
|
//{PA_15, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)},
|
||||||
|
//{PB_4, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)},
|
||||||
|
// {PB_6, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)},
|
||||||
|
// {PB_6, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)},
|
||||||
|
//{PB_6, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)},
|
||||||
|
//{PB_9, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PB_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
// {PB_13, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
// {PB_14, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)}, // LD3 LED_RED
|
||||||
|
//{PC_6, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
//{PC_10, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PC_10, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
//{PC_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
//{PD_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
//{PD_5, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
//{PD_8, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // STLink TX
|
||||||
|
//{PE_1, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)}, //LD2 LED_YELLOW (ZI2)
|
||||||
|
//{PE_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
//{PF_7, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
//{PG_14, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_RX[] = {
|
||||||
|
{PA_1, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // ETH RMII Ref Clk
|
||||||
|
// {PA_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
// {PA_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, // USB SOF
|
||||||
|
// {PA_10, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB ID
|
||||||
|
{PA_10, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB ID
|
||||||
|
// {PA_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_UART4)}, // USB DM
|
||||||
|
//{PB_3, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_UART7)}, // SWO
|
||||||
|
//{PB_5, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)},
|
||||||
|
// {PB_7, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_LPUART)}, // LD2 LED_BLUE (ZI)
|
||||||
|
// {PB_7, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // LD2 LED_BLUE (ZI)
|
||||||
|
//{PB_8, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PB_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
//{PB_12, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF14_UART5)},
|
||||||
|
//{PB_15, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF4_USART1)},
|
||||||
|
//{PC_7, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
//{PC_11, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PC_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
//{PD_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
//{PD_2, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
//{PD_6, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
//{PD_9, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // STLink RX
|
||||||
|
//{PE_0, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)},
|
||||||
|
//{PE_7, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
//{PF_6, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
//{PG_9, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_RTS[] = {
|
||||||
|
// {PA_1, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)}, // ETH RMII Ref Clk
|
||||||
|
// {PA_12, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB DP
|
||||||
|
// {PA_12, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB DP
|
||||||
|
{PA_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
// {PB_14, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // LD3 LED_RED
|
||||||
|
// {PB_14, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // LD3 LED_RED
|
||||||
|
{PC_8, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
{PD_4, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_12, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PD_15, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)},
|
||||||
|
{PE_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
{PF_8, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
{PG_8, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{PG_12, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_UART_CTS[] = {
|
||||||
|
{PA_0, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
// {PA_11, LPUART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF3_LPUART)}, // USB DM
|
||||||
|
// {PA_11, USART1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART1)}, // USB DM
|
||||||
|
// {PB_0, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)}, // LD1 LED_GREEN
|
||||||
|
// {PB_13, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
{PB_15, UART4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART4)},
|
||||||
|
{PC_9, UART5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART5)},
|
||||||
|
{PD_3, USART2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART2)},
|
||||||
|
{PD_11, USART3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART3)},
|
||||||
|
{PD_14, UART8, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_UART8)},
|
||||||
|
{PE_10, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
{PF_9, UART7, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_UART7)},
|
||||||
|
// {PG_13, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{PG_15, USART6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_USART6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** SPI ***
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_MOSI[] = {
|
||||||
|
{PC_12, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
//{PA_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
// {PA_7, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, // Used by ETH when JP6(ZI)/SB31(ZI2) ON
|
||||||
|
// {PB_2, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
|
||||||
|
// {PB_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PB_5, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI3)},
|
||||||
|
// // {PB_5, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)},
|
||||||
|
// {PB_15, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// // {PC_1, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // ETH RMII MDC
|
||||||
|
// {PC_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// {PD_6, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI3)},
|
||||||
|
// {PD_7, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PE_6, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PE_14, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PF_9, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)},
|
||||||
|
// {PF_11, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)},
|
||||||
|
// {PG_14, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_MISO[] = {
|
||||||
|
{PC_11, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PA_6, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PA_6, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)},
|
||||||
|
// {PB_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PB_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// // {PB_4, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)},
|
||||||
|
// {PB_14, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // LD3 LED_RED
|
||||||
|
// {PC_2, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// {PE_5, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PE_13, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PF_8, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)},
|
||||||
|
// {PG_9, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// {PG_12, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_SCLK[] = {
|
||||||
|
{PC_10, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PA_5, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PA_5, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)},
|
||||||
|
// // {PA_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB VBUS
|
||||||
|
// // {PA_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB DP
|
||||||
|
// // {PB_3, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // SWO
|
||||||
|
// // {PB_3, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)}, // SWO
|
||||||
|
// {PB_3, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)}, // SWO
|
||||||
|
// {PB_10, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// // {PB_13, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
// {PD_3, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// {PE_2, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PE_12, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PF_7, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)},
|
||||||
|
// {PG_11, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)}, // ETH RMII TX Enable
|
||||||
|
// {PG_13, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)}, // ETH RXII TXD0
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_SPI_SSEL[] = {
|
||||||
|
{PA_15, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// {PA_4, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PA_4, SPI3, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF6_SPI3)},
|
||||||
|
// // {PA_4, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF8_SPI6)},
|
||||||
|
// // {PA_11, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)}, // USB DM
|
||||||
|
// // {PA_15, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
// // {PA_15, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI6)},
|
||||||
|
// {PB_4, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF7_SPI2)},
|
||||||
|
// {PB_9, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// {PB_12, SPI2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI2)},
|
||||||
|
// {PE_4, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PE_11, SPI4, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI4)},
|
||||||
|
// {PF_6, SPI5, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI5)},
|
||||||
|
// {PG_8, SPI6, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI6)},
|
||||||
|
// {PG_10, SPI1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF5_SPI1)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** CAN ***
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_CAN_RD[] = {
|
||||||
|
// {PA_11, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, // USB DM
|
||||||
|
{PB_5, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)},
|
||||||
|
{PB_8, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)},
|
||||||
|
{PB_12, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)},
|
||||||
|
{PD_0, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_CAN_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_CAN_TD[] = {
|
||||||
|
// {PA_12, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)}, // USB DP
|
||||||
|
{PB_6, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // QSPI_CS
|
||||||
|
{PB_7, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // LD2 LED_BLUE (ZI)
|
||||||
|
{PB_9, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)},
|
||||||
|
// {PB_13, CANFD2, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN2)}, // Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
{PD_1, CANFD1, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_NOPULL, GPIO_AF9_FDCAN1)},
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** ETHERNET ***
|
||||||
|
|
||||||
|
#ifdef HAL_ETH_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_Ethernet[] = {
|
||||||
|
// {PA_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS
|
||||||
|
{PA_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_REF_CLK|ETH_RX_CLK
|
||||||
|
{PA_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDIO
|
||||||
|
// {PA_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_COL
|
||||||
|
{PA_7, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_CRS_DV|ETH_RX_DV
|
||||||
|
// {PB_0, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD2
|
||||||
|
// {PB_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD3
|
||||||
|
// {PB_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
|
||||||
|
// {PB_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||||
|
// {PB_10, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RX_ER
|
||||||
|
// {PB_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
|
||||||
|
// {PB_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
|
||||||
|
{PB_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||||
|
{PC_1, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_MDC
|
||||||
|
// {PC_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD2
|
||||||
|
// {PC_3, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_CLK
|
||||||
|
{PC_4, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD0
|
||||||
|
{PC_5, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_RXD1
|
||||||
|
// {PE_2, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD3
|
||||||
|
// {PG_8, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_PPS_OUT
|
||||||
|
{PG_11, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TX_EN
|
||||||
|
// {PG_12, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||||
|
{PG_13, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD0
|
||||||
|
// {PG_14, ETH, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF11_ETH)}, // ETH_TXD1
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//*** USB ***
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_USB_OTG_FS[] = {
|
||||||
|
// {PA_8, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_SOF
|
||||||
|
// {PA_9, USB_OTG_FS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_FS_VBUS
|
||||||
|
// {PA_10, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_ID
|
||||||
|
{PA_11, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_DM
|
||||||
|
{PA_12, USB_OTG_FS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG1_FS)}, // USB_OTG_FS_DP
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
WEAK const PinMap PinMap_USB_OTG_HS[] = {
|
||||||
|
#ifdef USE_USB_HS_IN_FS
|
||||||
|
// {PA_4, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_SOF
|
||||||
|
// {PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_OD, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_ID
|
||||||
|
// {PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_INPUT, GPIO_NOPULL, GPIO_AF_NONE)}, // USB_OTG_HS_VBUS - Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
{PB_14, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_DM
|
||||||
|
{PB_15, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF12_OTG2_FS)}, // USB_OTG_HS_DP
|
||||||
|
#else
|
||||||
|
{PA_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D0
|
||||||
|
{PA_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_CK
|
||||||
|
{PB_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D1
|
||||||
|
{PB_1, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D2
|
||||||
|
{PB_5, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D7
|
||||||
|
{PB_10, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D3
|
||||||
|
{PB_11, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D4
|
||||||
|
{PB_12, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D5
|
||||||
|
{PB_13, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_D6 - Used by ETH when JP7(ZI)/JP6(ZI2) ON
|
||||||
|
{PC_0, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_STP
|
||||||
|
{PC_2, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_DIR
|
||||||
|
{PC_3, USB_OTG_HS, STM_PIN_DATA(STM_MODE_AF_PP, GPIO_PULLUP, GPIO_AF10_OTG2_HS)}, // USB_OTG_HS_ULPI_NXT
|
||||||
|
#endif /* USE_USB_HS_IN_FS */
|
||||||
|
{NC, NP, 0}
|
||||||
|
};
|
||||||
|
#endif
|
|
@ -0,0 +1,50 @@
|
||||||
|
/* SYS_WKUP */
|
||||||
|
#ifdef PWR_WAKEUP_PIN1
|
||||||
|
SYS_WKUP1 = PA_0, /* SYS_WKUP0 */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN2
|
||||||
|
SYS_WKUP2 = PA_2, /* SYS_WKUP1 */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN3
|
||||||
|
SYS_WKUP3 = PC_13, /* SYS_WKUP2 */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN4
|
||||||
|
SYS_WKUP4 = PI_8, /* SYS_WKUP3 - Manually added */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN5
|
||||||
|
SYS_WKUP5 = PI_11, /* SYS_WKUP4 - Manually added */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN6
|
||||||
|
SYS_WKUP6 = PC_1, /* SYS_WKUP5 */
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN7
|
||||||
|
SYS_WKUP7 = NC,
|
||||||
|
#endif
|
||||||
|
#ifdef PWR_WAKEUP_PIN8
|
||||||
|
SYS_WKUP8 = NC,
|
||||||
|
#endif
|
||||||
|
/* USB */
|
||||||
|
#ifdef USBCON
|
||||||
|
USB_OTG_FS_SOF = PA_8,
|
||||||
|
USB_OTG_FS_VBUS = PA_9,
|
||||||
|
USB_OTG_FS_ID = PA_10,
|
||||||
|
USB_OTG_FS_DM = PA_11,
|
||||||
|
USB_OTG_FS_DP = PA_12,
|
||||||
|
USB_OTG_HS_ULPI_D0 = PA_3,
|
||||||
|
USB_OTG_HS_SOF = PA_4,
|
||||||
|
USB_OTG_HS_ULPI_CK = PA_5,
|
||||||
|
USB_OTG_HS_ULPI_D1 = PB_0,
|
||||||
|
USB_OTG_HS_ULPI_D2 = PB_1,
|
||||||
|
USB_OTG_HS_ULPI_D7 = PB_5,
|
||||||
|
USB_OTG_HS_ULPI_D3 = PB_10,
|
||||||
|
USB_OTG_HS_ULPI_D4 = PB_11,
|
||||||
|
USB_OTG_HS_ID = PB_12,
|
||||||
|
USB_OTG_HS_ULPI_D5 = PB_12,
|
||||||
|
USB_OTG_HS_ULPI_D6 = PB_13,
|
||||||
|
USB_OTG_HS_VBUS = PB_13,
|
||||||
|
USB_OTG_HS_DM = PB_14,
|
||||||
|
USB_OTG_HS_DP = PB_15,
|
||||||
|
USB_OTG_HS_ULPI_STP = PC_0,
|
||||||
|
USB_OTG_HS_ULPI_DIR = PC_2,
|
||||||
|
USB_OTG_HS_ULPI_NXT = PC_3,
|
||||||
|
#endif
|
|
@ -0,0 +1,479 @@
|
||||||
|
/**
|
||||||
|
******************************************************************************
|
||||||
|
* @file stm32h7xx_hal_conf_default.h
|
||||||
|
* @brief HAL default configuration file.
|
||||||
|
******************************************************************************
|
||||||
|
* @attention
|
||||||
|
*
|
||||||
|
* <h2><center>© Copyright (c) 2017 STMicroelectronics.
|
||||||
|
* All rights reserved.</center></h2>
|
||||||
|
*
|
||||||
|
* This software component is licensed by ST under BSD 3-Clause license,
|
||||||
|
* the "License"; You may not use this file except in compliance with the
|
||||||
|
* License. You may obtain a copy of the License at:
|
||||||
|
* opensource.org/licenses/BSD-3-Clause
|
||||||
|
*
|
||||||
|
******************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Define to prevent recursive inclusion -------------------------------------*/
|
||||||
|
#ifndef __STM32H7xx_HAL_CONF_DEFAULT_H
|
||||||
|
#define __STM32H7xx_HAL_CONF_DEFAULT_H
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* Exported types ------------------------------------------------------------*/
|
||||||
|
/* Exported constants --------------------------------------------------------*/
|
||||||
|
|
||||||
|
/* ########################## Module Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief Include the default list of modules to be used in the HAL driver
|
||||||
|
* and manage module deactivation
|
||||||
|
*/
|
||||||
|
#include "stm32yyxx_hal_conf.h"
|
||||||
|
#if 0
|
||||||
|
/**
|
||||||
|
* @brief This is the list of modules to be used in the HAL driver
|
||||||
|
*/
|
||||||
|
#define HAL_MODULE_ENABLED
|
||||||
|
#define HAL_ADC_MODULE_ENABLED
|
||||||
|
#define HAL_CEC_MODULE_ENABLED
|
||||||
|
#define HAL_COMP_MODULE_ENABLED
|
||||||
|
#define HAL_CORTEX_MODULE_ENABLED
|
||||||
|
#define HAL_CRC_MODULE_ENABLED
|
||||||
|
#define HAL_CRYP_MODULE_ENABLED
|
||||||
|
#define HAL_DAC_MODULE_ENABLED
|
||||||
|
#define HAL_DCMI_MODULE_ENABLED
|
||||||
|
#define HAL_DFSDM_MODULE_ENABLED
|
||||||
|
#define HAL_DMA_MODULE_ENABLED
|
||||||
|
#define HAL_DMA2D_MODULE_ENABLED
|
||||||
|
#define HAL_DSI_MODULE_ENABLED
|
||||||
|
#define HAL_ETH_MODULE_ENABLED
|
||||||
|
#define HAL_EXTI_MODULE_ENABLED
|
||||||
|
#define HAL_FDCAN_MODULE_ENABLED
|
||||||
|
#define HAL_FLASH_MODULE_ENABLED
|
||||||
|
#define HAL_GPIO_MODULE_ENABLED
|
||||||
|
#define HAL_HASH_MODULE_ENABLED
|
||||||
|
#define HAL_HCD_MODULE_ENABLED
|
||||||
|
#define HAL_HRTIM_MODULE_ENABLED
|
||||||
|
#define HAL_HSEM_MODULE_ENABLED
|
||||||
|
#define HAL_I2C_MODULE_ENABLED
|
||||||
|
#define HAL_I2S_MODULE_ENABLED
|
||||||
|
#define HAL_IRDA_MODULE_ENABLED
|
||||||
|
#define HAL_IWDG_MODULE_ENABLED
|
||||||
|
#define HAL_JPEG_MODULE_ENABLED
|
||||||
|
#define HAL_LPTIM_MODULE_ENABLED
|
||||||
|
#define HAL_LTDC_MODULE_ENABLED
|
||||||
|
#define HAL_MDIOS_MODULE_ENABLED
|
||||||
|
#define HAL_MDMA_MODULE_ENABLED
|
||||||
|
#define HAL_MMC_MODULE_ENABLED
|
||||||
|
#define HAL_NAND_MODULE_ENABLED
|
||||||
|
#define HAL_NOR_MODULE_ENABLED
|
||||||
|
#define HAL_OPAMP_MODULE_ENABLED
|
||||||
|
#define HAL_PCD_MODULE_ENABLED
|
||||||
|
#define HAL_PWR_MODULE_ENABLED
|
||||||
|
#define HAL_QSPI_MODULE_ENABLED
|
||||||
|
#define HAL_RAMECC_MODULE_ENABLED
|
||||||
|
#define HAL_RCC_MODULE_ENABLED
|
||||||
|
#define HAL_RNG_MODULE_ENABLED
|
||||||
|
#define HAL_RTC_MODULE_ENABLED
|
||||||
|
#define HAL_SAI_MODULE_ENABLED
|
||||||
|
#define HAL_SD_MODULE_ENABLED
|
||||||
|
#define HAL_SDRAM_MODULE_ENABLED
|
||||||
|
#define HAL_SMARTCARD_MODULE_ENABLED
|
||||||
|
#define HAL_SMBUS_MODULE_ENABLED
|
||||||
|
#define HAL_SPDIFRX_MODULE_ENABLED
|
||||||
|
#define HAL_SPI_MODULE_ENABLED
|
||||||
|
#define HAL_SRAM_MODULE_ENABLED
|
||||||
|
#define HAL_SWPMI_MODULE_ENABLED
|
||||||
|
#define HAL_TIM_MODULE_ENABLED
|
||||||
|
#define HAL_UART_MODULE_ENABLED
|
||||||
|
#define HAL_USART_MODULE_ENABLED
|
||||||
|
#define HAL_WWDG_MODULE_ENABLED
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/* ########################## Oscillator Values adaptation ####################*/
|
||||||
|
/**
|
||||||
|
* @brief Adjust the value of External High Speed oscillator (HSE) used in your application.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSE is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSE_VALUE)
|
||||||
|
#define HSE_VALUE ((uint32_t)25000000) /*!< Value of the External oscillator in Hz */
|
||||||
|
#endif /* HSE_VALUE */
|
||||||
|
|
||||||
|
#if !defined (HSE_STARTUP_TIMEOUT)
|
||||||
|
#define HSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for HSE start up, in ms */
|
||||||
|
#endif /* HSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal oscillator (CSI) default value.
|
||||||
|
* This value is the default CSI value after Reset.
|
||||||
|
*/
|
||||||
|
#if !defined (CSI_VALUE)
|
||||||
|
#define CSI_VALUE ((uint32_t)4000000) /*!< Value of the Internal oscillator in Hz*/
|
||||||
|
#endif /* CSI_VALUE */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief Internal High Speed oscillator (HSI) value.
|
||||||
|
* This value is used by the RCC HAL module to compute the system frequency
|
||||||
|
* (when HSI is used as system clock source, directly or through the PLL).
|
||||||
|
*/
|
||||||
|
#if !defined (HSI_VALUE)
|
||||||
|
#define HSI_VALUE ((uint32_t)64000000) /*!< Value of the Internal oscillator in Hz*/
|
||||||
|
#endif /* HSI_VALUE */
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief External Low Speed oscillator (LSE) value.
|
||||||
|
* This value is used by the UART, RTC HAL module to compute the system frequency
|
||||||
|
*/
|
||||||
|
#if !defined (LSE_VALUE)
|
||||||
|
#define LSE_VALUE ((uint32_t)32768) /*!< Value of the External oscillator in Hz*/
|
||||||
|
#endif /* LSE_VALUE */
|
||||||
|
|
||||||
|
|
||||||
|
#if !defined (LSE_STARTUP_TIMEOUT)
|
||||||
|
#define LSE_STARTUP_TIMEOUT ((uint32_t)5000) /*!< Time out for LSE start up, in ms */
|
||||||
|
#endif /* LSE_STARTUP_TIMEOUT */
|
||||||
|
|
||||||
|
#if !defined (LSI_VALUE)
|
||||||
|
#define LSI_VALUE ((uint32_t)32000) /*!< LSI Typical Value in Hz*/
|
||||||
|
#endif /* LSI_VALUE */ /*!< Value of the Internal Low Speed oscillator in Hz
|
||||||
|
The real value may vary depending on the variations
|
||||||
|
in voltage and temperature.*/
|
||||||
|
/**
|
||||||
|
* @brief External clock source for I2S peripheral
|
||||||
|
* This value is used by the I2S HAL module to compute the I2S clock source
|
||||||
|
* frequency, this source is inserted directly through I2S_CKIN pad.
|
||||||
|
*/
|
||||||
|
#if !defined (EXTERNAL_CLOCK_VALUE)
|
||||||
|
#define EXTERNAL_CLOCK_VALUE 12288000U /*!< Value of the External clock in Hz*/
|
||||||
|
#endif /* EXTERNAL_CLOCK_VALUE */
|
||||||
|
|
||||||
|
/* Tip: To avoid modifying this file each time you need to use different HSE,
|
||||||
|
=== you can define the HSE value in your toolchain compiler preprocessor. */
|
||||||
|
|
||||||
|
/* ########################### System Configuration ######################### */
|
||||||
|
/**
|
||||||
|
* @brief This is the HAL system configuration section
|
||||||
|
*/
|
||||||
|
#if !defined (VDD_VALUE)
|
||||||
|
#define VDD_VALUE ((uint32_t)3300) /*!< Value of VDD in mv */
|
||||||
|
#endif
|
||||||
|
#if !defined (TICK_INT_PRIORITY)
|
||||||
|
#define TICK_INT_PRIORITY ((uint32_t)0x00) /*!< tick interrupt priority */
|
||||||
|
#endif
|
||||||
|
#if !defined (USE_RTOS)
|
||||||
|
#define USE_RTOS 0
|
||||||
|
#endif
|
||||||
|
#if !defined (USE_SD_TRANSCEIVER)
|
||||||
|
#define USE_SD_TRANSCEIVER 1U /*!< use uSD Transceiver */
|
||||||
|
#endif
|
||||||
|
#if !defined (USE_SPI_CRC)
|
||||||
|
#define USE_SPI_CRC 0U /*!< use CRC in SPI */
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define USE_HAL_ADC_REGISTER_CALLBACKS 0U /* ADC register callback disabled */
|
||||||
|
#define USE_HAL_CEC_REGISTER_CALLBACKS 0U /* CEC register callback disabled */
|
||||||
|
#define USE_HAL_COMP_REGISTER_CALLBACKS 0U /* COMP register callback disabled */
|
||||||
|
#define USE_HAL_CRYP_REGISTER_CALLBACKS 0U /* CRYP register callback disabled */
|
||||||
|
#define USE_HAL_DAC_REGISTER_CALLBACKS 0U /* DAC register callback disabled */
|
||||||
|
#define USE_HAL_DCMI_REGISTER_CALLBACKS 0U /* DCMI register callback disabled */
|
||||||
|
#define USE_HAL_DFSDM_REGISTER_CALLBACKS 0U /* DFSDM register callback disabled */
|
||||||
|
#define USE_HAL_DMA2D_REGISTER_CALLBACKS 0U /* DMA2D register callback disabled */
|
||||||
|
#define USE_HAL_DSI_REGISTER_CALLBACKS 0U /* DSI register callback disabled */
|
||||||
|
#define USE_HAL_ETH_REGISTER_CALLBACKS 0U /* ETH register callback disabled */
|
||||||
|
#define USE_HAL_FDCAN_REGISTER_CALLBACKS 0U /* FDCAN register callback disabled */
|
||||||
|
#define USE_HAL_NAND_REGISTER_CALLBACKS 0U /* NAND register callback disabled */
|
||||||
|
#define USE_HAL_NOR_REGISTER_CALLBACKS 0U /* NOR register callback disabled */
|
||||||
|
#define USE_HAL_SDRAM_REGISTER_CALLBACKS 0U /* SDRAM register callback disabled */
|
||||||
|
#define USE_HAL_SRAM_REGISTER_CALLBACKS 0U /* SRAM register callback disabled */
|
||||||
|
#define USE_HAL_HASH_REGISTER_CALLBACKS 0U /* HASH register callback disabled */
|
||||||
|
#define USE_HAL_HCD_REGISTER_CALLBACKS 1U /* HCD register callback disabled */
|
||||||
|
#define USE_HAL_HRTIM_REGISTER_CALLBACKS 0U /* HRTIM register callback disabled */
|
||||||
|
#define USE_HAL_I2C_REGISTER_CALLBACKS 0U /* I2C register callback disabled */
|
||||||
|
#define USE_HAL_I2S_REGISTER_CALLBACKS 0U /* I2S register callback disabled */
|
||||||
|
#define USE_HAL_JPEG_REGISTER_CALLBACKS 0U /* JPEG register callback disabled */
|
||||||
|
#define USE_HAL_LPTIM_REGISTER_CALLBACKS 0U /* LPTIM register callback disabled */
|
||||||
|
#define USE_HAL_LTDC_REGISTER_CALLBACKS 0U /* LTDC register callback disabled */
|
||||||
|
#define USE_HAL_MDIOS_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */
|
||||||
|
#define USE_HAL_OPAMP_REGISTER_CALLBACKS 0U /* MDIO register callback disabled */
|
||||||
|
#define USE_HAL_PCD_REGISTER_CALLBACKS 0U /* PCD register callback disabled */
|
||||||
|
#define USE_HAL_QSPI_REGISTER_CALLBACKS 0U /* QSPI register callback disabled */
|
||||||
|
#define USE_HAL_RNG_REGISTER_CALLBACKS 0U /* RNG register callback disabled */
|
||||||
|
#define USE_HAL_RTC_REGISTER_CALLBACKS 0U /* RTC register callback disabled */
|
||||||
|
#define USE_HAL_SAI_REGISTER_CALLBACKS 0U /* SAI register callback disabled */
|
||||||
|
#define USE_HAL_SPDIFRX_REGISTER_CALLBACKS 0U /* SPDIFRX register callback disabled */
|
||||||
|
#define USE_HAL_SMBUS_REGISTER_CALLBACKS 0U /* SMBUS register callback disabled */
|
||||||
|
#define USE_HAL_SPI_REGISTER_CALLBACKS 0U /* SPI register callback disabled */
|
||||||
|
#define USE_HAL_SWPMI_REGISTER_CALLBACKS 0U /* SWPMI register callback disabled */
|
||||||
|
#define USE_HAL_TIM_REGISTER_CALLBACKS 0U /* TIM register callback disabled */
|
||||||
|
#define USE_HAL_WWDG_REGISTER_CALLBACKS 0U /* WWDG register callback disabled */
|
||||||
|
|
||||||
|
/* ########################### Ethernet Configuration ######################### */
|
||||||
|
#define ETH_TX_DESC_CNT 4 /* number of Ethernet Tx DMA descriptors */
|
||||||
|
#define ETH_RX_DESC_CNT 4 /* number of Ethernet Rx DMA descriptors */
|
||||||
|
|
||||||
|
#define ETH_MAC_ADDR0 ((uint8_t)0x02)
|
||||||
|
#define ETH_MAC_ADDR1 ((uint8_t)0x00)
|
||||||
|
#define ETH_MAC_ADDR2 ((uint8_t)0x00)
|
||||||
|
#define ETH_MAC_ADDR3 ((uint8_t)0x00)
|
||||||
|
#define ETH_MAC_ADDR4 ((uint8_t)0x00)
|
||||||
|
#define ETH_MAC_ADDR5 ((uint8_t)0x00)
|
||||||
|
|
||||||
|
|
||||||
|
/* ########################## Assert Selection ############################## */
|
||||||
|
/**
|
||||||
|
* @brief Uncomment the line below to expanse the "assert_param" macro in the
|
||||||
|
* HAL drivers code
|
||||||
|
*/
|
||||||
|
/* #define USE_FULL_ASSERT 1 */
|
||||||
|
|
||||||
|
/* Includes ------------------------------------------------------------------*/
|
||||||
|
/**
|
||||||
|
* @brief Include module's header file
|
||||||
|
*/
|
||||||
|
|
||||||
|
#ifdef HAL_RCC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_rcc.h"
|
||||||
|
#endif /* HAL_RCC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_GPIO_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_gpio.h"
|
||||||
|
#endif /* HAL_GPIO_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dma.h"
|
||||||
|
#endif /* HAL_DMA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_MDMA_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_mdma.h"
|
||||||
|
#endif /* HAL_MDMA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HASH_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_hash.h"
|
||||||
|
#endif /* HAL_HASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DCMI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dcmi.h"
|
||||||
|
#endif /* HAL_DCMI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DMA2D_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dma2d.h"
|
||||||
|
#endif /* HAL_DMA2D_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DSI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dsi.h"
|
||||||
|
#endif /* HAL_DSI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DFSDM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dfsdm.h"
|
||||||
|
#endif /* HAL_DFSDM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ETH_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_eth.h"
|
||||||
|
#endif /* HAL_ETH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_EXTI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_exti.h"
|
||||||
|
#endif /* HAL_EXTI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CORTEX_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_cortex.h"
|
||||||
|
#endif /* HAL_CORTEX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_ADC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_adc.h"
|
||||||
|
#endif /* HAL_ADC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_FDCAN_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_fdcan.h"
|
||||||
|
#endif /* HAL_FDCAN_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CEC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_cec.h"
|
||||||
|
#endif /* HAL_CEC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_COMP_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_comp.h"
|
||||||
|
#endif /* HAL_COMP_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_crc.h"
|
||||||
|
#endif /* HAL_CRC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_CRYP_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_cryp.h"
|
||||||
|
#endif /* HAL_CRYP_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_DAC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_dac.h"
|
||||||
|
#endif /* HAL_DAC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_FLASH_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_flash.h"
|
||||||
|
#endif /* HAL_FLASH_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HRTIM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_hrtim.h"
|
||||||
|
#endif /* HAL_HRTIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HSEM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_hsem.h"
|
||||||
|
#endif /* HAL_HSEM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SRAM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_sram.h"
|
||||||
|
#endif /* HAL_SRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NOR_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_nor.h"
|
||||||
|
#endif /* HAL_NOR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_NAND_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_nand.h"
|
||||||
|
#endif /* HAL_NAND_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2C_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_i2c.h"
|
||||||
|
#endif /* HAL_I2C_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_I2S_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_i2s.h"
|
||||||
|
#endif /* HAL_I2S_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IWDG_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_iwdg.h"
|
||||||
|
#endif /* HAL_IWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_JPEG_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_jpeg.h"
|
||||||
|
#endif /* HAL_JPEG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_MDIOS_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_mdios.h"
|
||||||
|
#endif /* HAL_MDIOS_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_MMC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_mmc.h"
|
||||||
|
#endif /* HAL_MMC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LPTIM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_lptim.h"
|
||||||
|
#endif /* HAL_LPTIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_LTDC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_ltdc.h"
|
||||||
|
#endif /* HAL_LTDC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_OPAMP_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_opamp.h"
|
||||||
|
#endif /* HAL_OPAMP_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PWR_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_pwr.h"
|
||||||
|
#endif /* HAL_PWR_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_QSPI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_qspi.h"
|
||||||
|
#endif /* HAL_QSPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RAMECC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_ramecc.h"
|
||||||
|
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RNG_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_rng.h"
|
||||||
|
#endif /* HAL_RNG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_RTC_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_rtc.h"
|
||||||
|
#endif /* HAL_RTC_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SAI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_sai.h"
|
||||||
|
#endif /* HAL_SAI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SD_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_sd.h"
|
||||||
|
#endif /* HAL_SD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SDRAM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_sdram.h"
|
||||||
|
#endif /* HAL_SDRAM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_spi.h"
|
||||||
|
#endif /* HAL_SPI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SPDIFRX_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_spdifrx.h"
|
||||||
|
#endif /* HAL_SPDIFRX_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SWPMI_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_swpmi.h"
|
||||||
|
#endif /* HAL_SWPMI_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_TIM_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_tim.h"
|
||||||
|
#endif /* HAL_TIM_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_UART_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_uart.h"
|
||||||
|
#endif /* HAL_UART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_USART_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_usart.h"
|
||||||
|
#endif /* HAL_USART_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_IRDA_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_irda.h"
|
||||||
|
#endif /* HAL_IRDA_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SMARTCARD_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_smartcard.h"
|
||||||
|
#endif /* HAL_SMARTCARD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_SMBUS_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_smbus.h"
|
||||||
|
#endif /* HAL_SMBUS_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_WWDG_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_wwdg.h"
|
||||||
|
#endif /* HAL_WWDG_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_PCD_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_pcd.h"
|
||||||
|
#endif /* HAL_PCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
#ifdef HAL_HCD_MODULE_ENABLED
|
||||||
|
#include "stm32h7xx_hal_hcd.h"
|
||||||
|
#endif /* HAL_HCD_MODULE_ENABLED */
|
||||||
|
|
||||||
|
/* Exported macro ------------------------------------------------------------*/
|
||||||
|
#ifdef USE_FULL_ASSERT
|
||||||
|
/**
|
||||||
|
* @brief The assert_param macro is used for function's parameters check.
|
||||||
|
* @param expr: If expr is false, it calls assert_failed function
|
||||||
|
* which reports the name of the source file and the source
|
||||||
|
* line number of the call that failed.
|
||||||
|
* If expr is true, it returns no value.
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
#define assert_param(expr) ((expr) ? (void)0U : assert_failed((uint8_t *)__FILE__, __LINE__))
|
||||||
|
/* Exported functions ------------------------------------------------------- */
|
||||||
|
void assert_failed(uint8_t *file, uint32_t line);
|
||||||
|
#else
|
||||||
|
#define assert_param(expr) ((void)0U)
|
||||||
|
#endif /* USE_FULL_ASSERT */
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* __STM32H7xx_HAL_CONF_DEFAULT_H */
|
||||||
|
|
||||||
|
|
||||||
|
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
|
208
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/ldscript.ld
Normal file
208
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/ldscript.ld
Normal file
|
@ -0,0 +1,208 @@
|
||||||
|
/*
|
||||||
|
******************************************************************************
|
||||||
|
**
|
||||||
|
** File : LinkerScript.ld
|
||||||
|
**
|
||||||
|
** Author : Auto-generated by STM32CubeIDE
|
||||||
|
**
|
||||||
|
** Abstract : Linker script for NUCLEO-H743II(2) Board embedding STM32H743IITx Device from STM32H7 series
|
||||||
|
** 2048Kbytes FLASH
|
||||||
|
** 128Kbytes DTCMRAM
|
||||||
|
** 64Kbytes ITCMRAM
|
||||||
|
** 512Kbytes RAM_D1
|
||||||
|
** 288Kbytes RAM_D2
|
||||||
|
** 64Kbytes RAM_D3
|
||||||
|
**
|
||||||
|
** Set heap size, stack size and stack location according
|
||||||
|
** to application requirements.
|
||||||
|
**
|
||||||
|
** Set memory bank area and size if external memory is used.
|
||||||
|
**
|
||||||
|
** Target : STMicroelectronics STM32
|
||||||
|
**
|
||||||
|
** Distribution: The file is distributed as is without any warranty
|
||||||
|
** of any kind.
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
** @attention
|
||||||
|
**
|
||||||
|
** <h2><center>© COPYRIGHT(c) 2019 STMicroelectronics</center></h2>
|
||||||
|
**
|
||||||
|
** Redistribution and use in source and binary forms, with or without modification,
|
||||||
|
** are permitted provided that the following conditions are met:
|
||||||
|
** 1. Redistributions of source code must retain the above copyright notice,
|
||||||
|
** this list of conditions and the following disclaimer.
|
||||||
|
** 2. Redistributions in binary form must reproduce the above copyright notice,
|
||||||
|
** this list of conditions and the following disclaimer in the documentation
|
||||||
|
** and/or other materials provided with the distribution.
|
||||||
|
** 3. Neither the name of STMicroelectronics nor the names of its contributors
|
||||||
|
** may be used to endorse or promote products derived from this software
|
||||||
|
** without specific prior written permission.
|
||||||
|
**
|
||||||
|
** THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
|
||||||
|
** AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
|
||||||
|
** IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
|
||||||
|
** DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
|
||||||
|
** FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
|
||||||
|
** DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
|
||||||
|
** SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
|
||||||
|
** CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
|
||||||
|
** OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||||
|
** OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||||
|
**
|
||||||
|
*****************************************************************************
|
||||||
|
*/
|
||||||
|
|
||||||
|
/* Entry Point */
|
||||||
|
ENTRY(Reset_Handler)
|
||||||
|
|
||||||
|
/* Highest address of the user mode stack */
|
||||||
|
_estack = 0x24080000; /* end of "RAM_D1" Ram type memory */
|
||||||
|
|
||||||
|
_Min_Heap_Size = 0x200; /* required amount of heap */
|
||||||
|
_Min_Stack_Size = 0x400; /* required amount of stack */
|
||||||
|
|
||||||
|
/* Memories definition */
|
||||||
|
MEMORY
|
||||||
|
{
|
||||||
|
DTCMRAM (xrw) : ORIGIN = 0x20000000, LENGTH = 128K
|
||||||
|
ITCMRAM (xrw) : ORIGIN = 0x00000000, LENGTH = 64K
|
||||||
|
RAM_D1 (xrw) : ORIGIN = 0x24000000, LENGTH = 512K
|
||||||
|
RAM_D2 (xrw) : ORIGIN = 0x30000000, LENGTH = 288K
|
||||||
|
RAM_D3 (xrw) : ORIGIN = 0x38000000, LENGTH = 64K
|
||||||
|
FLASH (rx) : ORIGIN = 0x8020000, LENGTH = 2048K - 128K
|
||||||
|
}
|
||||||
|
|
||||||
|
/* Sections */
|
||||||
|
SECTIONS
|
||||||
|
{
|
||||||
|
/* The startup code into "FLASH" Rom type memory */
|
||||||
|
.isr_vector :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
KEEP(*(.isr_vector)) /* Startup code */
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* The program code and other data into "FLASH" Rom type memory */
|
||||||
|
.text :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.text) /* .text sections (code) */
|
||||||
|
*(.text*) /* .text* sections (code) */
|
||||||
|
*(.glue_7) /* glue arm to thumb code */
|
||||||
|
*(.glue_7t) /* glue thumb to arm code */
|
||||||
|
*(.eh_frame)
|
||||||
|
|
||||||
|
KEEP (*(.init))
|
||||||
|
KEEP (*(.fini))
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_etext = .; /* define a global symbols at end of code */
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* Constant data into "FLASH" Rom type memory */
|
||||||
|
.rodata :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.rodata) /* .rodata sections (constants, strings, etc.) */
|
||||||
|
*(.rodata*) /* .rodata* sections (constants, strings, etc.) */
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.ARM.extab : {
|
||||||
|
. = ALIGN(4);
|
||||||
|
*(.ARM.extab* .gnu.linkonce.armextab.*)
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.ARM : {
|
||||||
|
. = ALIGN(4);
|
||||||
|
__exidx_start = .;
|
||||||
|
*(.ARM.exidx*)
|
||||||
|
__exidx_end = .;
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.preinit_array :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_start = .);
|
||||||
|
KEEP (*(.preinit_array*))
|
||||||
|
PROVIDE_HIDDEN (__preinit_array_end = .);
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.init_array :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
PROVIDE_HIDDEN (__init_array_start = .);
|
||||||
|
KEEP (*(SORT(.init_array.*)))
|
||||||
|
KEEP (*(.init_array*))
|
||||||
|
PROVIDE_HIDDEN (__init_array_end = .);
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
.fini_array :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
PROVIDE_HIDDEN (__fini_array_start = .);
|
||||||
|
KEEP (*(SORT(.fini_array.*)))
|
||||||
|
KEEP (*(.fini_array*))
|
||||||
|
PROVIDE_HIDDEN (__fini_array_end = .);
|
||||||
|
. = ALIGN(4);
|
||||||
|
} >FLASH
|
||||||
|
|
||||||
|
/* Used by the startup to initialize data */
|
||||||
|
_sidata = LOADADDR(.data);
|
||||||
|
|
||||||
|
/* Initialized data sections into "RAM_D1" Ram type memory */
|
||||||
|
.data :
|
||||||
|
{
|
||||||
|
. = ALIGN(4);
|
||||||
|
_sdata = .; /* create a global symbol at data start */
|
||||||
|
*(.data) /* .data sections */
|
||||||
|
*(.data*) /* .data* sections */
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_edata = .; /* define a global symbol at data end */
|
||||||
|
|
||||||
|
} >RAM_D1 AT> FLASH
|
||||||
|
|
||||||
|
/* Uninitialized data section into "RAM_D1" Ram type memory */
|
||||||
|
. = ALIGN(4);
|
||||||
|
.bss :
|
||||||
|
{
|
||||||
|
/* This is used by the startup in order to initialize the .bss secion */
|
||||||
|
_sbss = .; /* define a global symbol at bss start */
|
||||||
|
__bss_start__ = _sbss;
|
||||||
|
*(.bss)
|
||||||
|
*(.bss*)
|
||||||
|
*(COMMON)
|
||||||
|
|
||||||
|
. = ALIGN(4);
|
||||||
|
_ebss = .; /* define a global symbol at bss end */
|
||||||
|
__bss_end__ = _ebss;
|
||||||
|
} >RAM_D1
|
||||||
|
|
||||||
|
/* User_heap_stack section, used to check that there is enough "RAM_D1" Ram type memory left */
|
||||||
|
._user_heap_stack :
|
||||||
|
{
|
||||||
|
. = ALIGN(8);
|
||||||
|
PROVIDE ( end = . );
|
||||||
|
PROVIDE ( _end = . );
|
||||||
|
. = . + _Min_Heap_Size;
|
||||||
|
. = . + _Min_Stack_Size;
|
||||||
|
. = ALIGN(8);
|
||||||
|
} >RAM_D1
|
||||||
|
|
||||||
|
/* Remove information from the compiler libraries */
|
||||||
|
/DISCARD/ :
|
||||||
|
{
|
||||||
|
libc.a ( * )
|
||||||
|
libm.a ( * )
|
||||||
|
libgcc.a ( * )
|
||||||
|
}
|
||||||
|
|
||||||
|
.ARM.attributes 0 : { *(.ARM.attributes) }
|
||||||
|
}
|
332
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/variant.cpp
Normal file
332
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/variant.cpp
Normal file
|
@ -0,0 +1,332 @@
|
||||||
|
#include "pins_arduino.h"
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Pin number
|
||||||
|
const PinName digitalPin[] = {
|
||||||
|
PE_2, // D0
|
||||||
|
PE_3, // D1
|
||||||
|
PE_4, // D2
|
||||||
|
PE_5, // D3
|
||||||
|
PE_6, // D4
|
||||||
|
PI_8, // D5
|
||||||
|
PC_13, // D6
|
||||||
|
PC_14, // D7
|
||||||
|
PC_15, // D8
|
||||||
|
PI_9, // D9
|
||||||
|
PI_10, // D10
|
||||||
|
PI_11, // D11
|
||||||
|
PF_0, // D12
|
||||||
|
PF_1, // D13
|
||||||
|
PF_2, // D14
|
||||||
|
PH_0, // D15
|
||||||
|
PH_1, // D16
|
||||||
|
PB_2, // D17
|
||||||
|
PF_15, // D18
|
||||||
|
PG_0, // D19
|
||||||
|
PG_1, // D20
|
||||||
|
PE_7, // D21
|
||||||
|
PE_8, // D22
|
||||||
|
PE_9, // D23
|
||||||
|
PE_10, // D24
|
||||||
|
PE_11, // D25
|
||||||
|
PE_12, // D26
|
||||||
|
PE_13, // D27
|
||||||
|
PE_14, // D28
|
||||||
|
PE_15, // D29
|
||||||
|
PB_10, // D30
|
||||||
|
PB_11, // D31
|
||||||
|
PH_6, // D32
|
||||||
|
PH_7, // D33
|
||||||
|
PH_8, // D34
|
||||||
|
PH_9, // D35
|
||||||
|
PH_10, // D36
|
||||||
|
PH_11, // D37
|
||||||
|
PH_12, // D38
|
||||||
|
PB_12, // D39
|
||||||
|
PB_13, // D40
|
||||||
|
PB_14, // D41
|
||||||
|
PB_15, // D42
|
||||||
|
PD_8, // D43
|
||||||
|
PD_9, // D44
|
||||||
|
PD_10, // D45
|
||||||
|
PD_11, // D46
|
||||||
|
PD_12, // D47
|
||||||
|
PD_13, // D48
|
||||||
|
PD_14, // D49
|
||||||
|
PD_15, // D50
|
||||||
|
PG_2, // D51
|
||||||
|
PG_3, // D52
|
||||||
|
PG_4, // D53
|
||||||
|
PG_5, // D54
|
||||||
|
PG_6, // D55
|
||||||
|
PG_7, // D56
|
||||||
|
PG_8, // D57
|
||||||
|
PC_6, // D58
|
||||||
|
PC_7, // D59
|
||||||
|
PC_8, // D60
|
||||||
|
PC_9, // D61
|
||||||
|
PA_8, // D62
|
||||||
|
PA_9, // D63
|
||||||
|
PA_10, // D64
|
||||||
|
PA_11, // D65
|
||||||
|
PA_12, // D66
|
||||||
|
PA_13, // D67
|
||||||
|
PH_13, // D68
|
||||||
|
PH_14, // D69
|
||||||
|
PH_15, // D70
|
||||||
|
PI_0, // D71
|
||||||
|
PI_1, // D72
|
||||||
|
PI_2, // D73
|
||||||
|
PI_3, // D74
|
||||||
|
PA_14, // D75
|
||||||
|
PA_15, // D76
|
||||||
|
PC_10, // D77
|
||||||
|
PC_11, // D78
|
||||||
|
PC_12, // D79
|
||||||
|
PD_0, // D80
|
||||||
|
PD_1, // D81
|
||||||
|
PD_2, // D82
|
||||||
|
PD_3, // D83
|
||||||
|
PD_4, // D84
|
||||||
|
PD_5, // D85
|
||||||
|
PD_6, // D86
|
||||||
|
PD_7, // D87
|
||||||
|
PG_9, // D88
|
||||||
|
PG_10, // D89
|
||||||
|
PG_11, // D90
|
||||||
|
PG_12, // D91
|
||||||
|
PG_13, // D92
|
||||||
|
PG_14, // D93
|
||||||
|
PG_15, // D94
|
||||||
|
PB_3, // D95
|
||||||
|
PB_4, // D96
|
||||||
|
PB_5, // D97
|
||||||
|
PB_6, // D98
|
||||||
|
PB_7, // D99
|
||||||
|
PB_8, // D100
|
||||||
|
PB_9, // D101
|
||||||
|
PE_0, // D102
|
||||||
|
PE_1, // D103
|
||||||
|
PI_4, // D104
|
||||||
|
PI_5, // D105
|
||||||
|
PI_6, // D106
|
||||||
|
PI_7, // D107
|
||||||
|
PA_0, // D108 / A0
|
||||||
|
PA_1, // D109 / A1
|
||||||
|
PA_2, // D110 / A2
|
||||||
|
PA_3, // D111 / A3
|
||||||
|
PA_4, // D112 / A4
|
||||||
|
PA_5, // D113 / A5
|
||||||
|
PA_6, // D114 / A6
|
||||||
|
PA_7, // D115 / A7
|
||||||
|
PB_0, // D116 / A8
|
||||||
|
PB_1, // D117 / A9
|
||||||
|
PH_2, // D118 / A10
|
||||||
|
PH_3, // D119 / A11
|
||||||
|
PH_4, // D120 / A12
|
||||||
|
PH_5, // D121 / A13
|
||||||
|
PC_0, // D122 / A14
|
||||||
|
PC_1, // D123 / A15
|
||||||
|
PC_2, // D124 / A16
|
||||||
|
PC_3, // D125 / A17
|
||||||
|
PC_4, // D126 / A18
|
||||||
|
PC_5, // D127 / A19
|
||||||
|
PF_3, // D128 / A20
|
||||||
|
PF_4, // D129 / A21
|
||||||
|
PF_5, // D130 / A22
|
||||||
|
PF_6, // D131 / A23
|
||||||
|
PF_7, // D132 / A24
|
||||||
|
PF_8, // D133 / A25
|
||||||
|
PF_9, // D134 / A26
|
||||||
|
PF_10, // D135 / A27
|
||||||
|
PF_11, // D136 / A28
|
||||||
|
PF_12, // D137 / A29
|
||||||
|
PF_13, // D138 / A30
|
||||||
|
PF_14, // D139 / A31
|
||||||
|
};
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// ----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
extern "C" {
|
||||||
|
#endif
|
||||||
|
|
||||||
|
void SystemClockStartupInit() {
|
||||||
|
// Confirm is called only once time to avoid hang up caused by repeated calls in USB wakeup interrupt
|
||||||
|
static bool first_call = true;
|
||||||
|
if (!first_call) return;
|
||||||
|
first_call = false;
|
||||||
|
|
||||||
|
// Clear all clock setting register
|
||||||
|
RCC->CR = 0x00000001;
|
||||||
|
RCC->CFGR = 0x00000000;
|
||||||
|
RCC->D1CFGR = 0x00000000;
|
||||||
|
RCC->D2CFGR = 0x00000000;
|
||||||
|
RCC->D3CFGR = 0x00000000;
|
||||||
|
RCC->PLLCKSELR = 0x00000000;
|
||||||
|
RCC->PLLCFGR = 0x00000000;
|
||||||
|
RCC->CIER = 0x00000000;
|
||||||
|
|
||||||
|
// AXI_TARG7_FN_MOD for SRAM
|
||||||
|
*((volatile uint32_t*)0x51008108)=0x00000001;
|
||||||
|
|
||||||
|
// Enable L1-Cache
|
||||||
|
SCB_EnableICache();
|
||||||
|
SCB_EnableDCache();
|
||||||
|
SCB->CACR |= 1<<2;
|
||||||
|
|
||||||
|
PWR->CR3 &= ~(1 << 2); // SCUEN=0
|
||||||
|
PWR->D3CR |= 3 << 14; // VOS=3,Scale1,1.15~1.26V core voltage
|
||||||
|
while((PWR->D3CR & (1 << 13)) == 0); // Wait for the voltage to stabilize
|
||||||
|
RCC->CR |= 1<<16; // Enable HSE
|
||||||
|
|
||||||
|
uint16_t timeout = 0;
|
||||||
|
while(((RCC->CR & (1 << 17)) == 0) && (timeout < 0X7FFF)) {
|
||||||
|
timeout++; // Wait for HSE RDY
|
||||||
|
}
|
||||||
|
|
||||||
|
if(timeout == 0X7FFF) {
|
||||||
|
Error_Handler();
|
||||||
|
} else {
|
||||||
|
RCC->PLLCKSELR |= 2 << 0; // PLLSRC[1:0] = 2, HSE for PLL clock source
|
||||||
|
RCC->PLLCKSELR |= 5 << 4; // DIVM1[5:0] = pllm, Prescaler for PLL1
|
||||||
|
RCC->PLL1DIVR |= (160 - 1) << 0; // DIVN1[8:0] = plln - 1, Multiplication factor for PLL1 VCO
|
||||||
|
RCC->PLL1DIVR |= (2 - 1) << 9; // DIVP1[6:0] = pllp - 1, PLL1 DIVP division factor
|
||||||
|
RCC->PLL1DIVR |= (4 - 1) << 16; // DIVQ1[6:0] = pllq - 1, PLL1 DIVQ division factor
|
||||||
|
RCC->PLL1DIVR |= 1 << 24; // DIVR1[6:0] = pllr - 1, PLL1 DIVR division factor
|
||||||
|
RCC->PLLCFGR |= 2 << 2; // PLL1 input (ref1_ck) clock range frequency is between 4 and 8 MHz
|
||||||
|
RCC->PLLCFGR |= 0 << 1; // PLL1 VCO selection, 0: 192 to 836 MHz, 1 : 150 to 420 MHz
|
||||||
|
RCC->PLLCFGR |= 3 << 16; // pll1_q_ck and pll1_p_ck output is enabled
|
||||||
|
RCC->CR |= 1 << 24; // PLL1 enable
|
||||||
|
while((RCC->CR & (1 << 25)) == 0); // PLL1 clock ready flag
|
||||||
|
|
||||||
|
// PLL2 DIVR clock frequency = 220MHz, so that SDRAM clock can be set to 110MHz
|
||||||
|
RCC->PLLCKSELR |= 25 << 12; // DIVM2[5:0] = 25, Prescaler for PLL2
|
||||||
|
RCC->PLL2DIVR |= (440 - 1) << 0; // DIVN2[8:0] = 440 - 1, Multiplication factor for PLL2 VCO
|
||||||
|
RCC->PLL2DIVR |= (2 - 1) << 9; // DIVP2[6:0] = 2-1, PLL2 DIVP division factor
|
||||||
|
RCC->PLL2DIVR |= (2 - 1) << 24; // DIVR2[6:0] = 2-1, PLL2 DIVR division factor
|
||||||
|
RCC->PLLCFGR |= 0 << 6; // PLL2RGE[1:0]=0, PLL2 input (ref2_ck) clock range frequency is between 1 and 2 MHz
|
||||||
|
RCC->PLLCFGR |= 0 << 5; // PLL2 VCO selection, 0: 192 to 836 MHz, 1: 150 to 420 MHz
|
||||||
|
RCC->PLLCFGR |= 1 << 19; // pll2_p_ck output is enabled
|
||||||
|
RCC->PLLCFGR |= 1 << 21; // pll2_r_ck output is enabled
|
||||||
|
RCC->D1CCIPR &= ~(3 << 0); // clear FMC kernel clock source selection
|
||||||
|
RCC->D1CCIPR |= 2 << 0; // pll2_r_ck clock selected as kernel peripheral clock
|
||||||
|
RCC->CR |= 1 << 26; // PLL2 enable
|
||||||
|
while((RCC->CR&(1<<27)) == 0); // PLL2 clock ready flag
|
||||||
|
|
||||||
|
RCC->D1CFGR |= 8 << 0; // rcc_hclk3 = sys_d1cpre_ck / 2 = 400 / 2 = 200MHz. AHB1/2/3/4
|
||||||
|
RCC->D1CFGR |= 0 << 8; // sys_ck not divided, sys_d1cpre_ck = sys_clk / 1 = 400 / 1 = 400MHz, System Clock = 400MHz
|
||||||
|
RCC->CFGR |= 3 << 0; // PLL1 selected as system clock (pll1_p_ck). 400MHz
|
||||||
|
while(1) {
|
||||||
|
timeout = (RCC->CFGR & (7 << 3)) >> 3; // System clock switch status
|
||||||
|
if(timeout == 3) break; // Wait for SW[2:0] = 3 (011: PLL1 selected as system clock (pll1_p_ck))
|
||||||
|
}
|
||||||
|
|
||||||
|
FLASH->ACR |= 2 << 0; // LATENCY[2:0] = 2 (@VOS1 Level,maxclock=210MHz)
|
||||||
|
FLASH->ACR |= 2 << 4; // WRHIGHFREQ[1:0] = 2, flash access frequency < 285MHz
|
||||||
|
|
||||||
|
RCC->D1CFGR |= 4 << 4; // D1PPRE[2:0] = 4, rcc_pclk3 = rcc_hclk3 / 2 = 100MHz, APB3.
|
||||||
|
RCC->D2CFGR |= 4 << 4; // D2PPRE1[2:0] = 4, rcc_pclk1 = rcc_hclk1 / 2 = 100MHz, APB1.
|
||||||
|
RCC->D2CFGR |= 4 << 8; // D2PPRE2[2:0] = 4, rcc_pclk2 = rcc_hclk1 / 2 = 100MHz, APB2.
|
||||||
|
RCC->D3CFGR |= 4 << 4; // D3PPRE[2:0] = 4, rcc_pclk4 = rcc_hclk4 / 2 = 100MHz, APB4.
|
||||||
|
|
||||||
|
RCC->CR |= 1 << 7; // CSI clock enable
|
||||||
|
RCC->APB4ENR |= 1 << 1; // SYSCFG peripheral clock enable
|
||||||
|
SYSCFG->CCCSR |= 1 << 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// USB clock, (use HSI48 clock)
|
||||||
|
RCC->CR |= 1 << 12; // HSI48 clock enabl
|
||||||
|
while((RCC->CR & (1 << 13)) == 0);// 1: HSI48 clock is ready
|
||||||
|
RCC->APB1HENR |= 1 << 1; // CRS peripheral clock enabled
|
||||||
|
RCC->APB1HRSTR |= 1 << 1; // Resets CRS
|
||||||
|
RCC->APB1HRSTR &= ~(1 << 1); // Does not reset CRS
|
||||||
|
CRS->CFGR &= ~(3 << 28); // USB2 SOF selected as SYNC signal source
|
||||||
|
CRS->CR |= 3 << 5; // Automatic trimming and Frequency error counter enabled
|
||||||
|
RCC->D2CCIP2R &= ~(3 << 20); // Clear USBOTG 1 and 2 kernel clock source selection
|
||||||
|
RCC->D2CCIP2R |= 3 << 20; // HSI48_ck clock is selected as kernel clock
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t MPU_Convert_Bytes_To_POT(uint32_t nbytes)
|
||||||
|
{
|
||||||
|
uint8_t count = 0;
|
||||||
|
while(nbytes != 1)
|
||||||
|
{
|
||||||
|
nbytes >>= 1;
|
||||||
|
count++;
|
||||||
|
}
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t MPU_Set_Protection(uint32_t baseaddr, uint32_t size, uint32_t rnum, uint8_t ap, uint8_t sen, uint8_t cen, uint8_t ben)
|
||||||
|
{
|
||||||
|
uint32_t tempreg = 0;
|
||||||
|
uint8_t rnr = 0;
|
||||||
|
if ((size % 32) || size == 0) return 1;
|
||||||
|
rnr = MPU_Convert_Bytes_To_POT(size) - 1;
|
||||||
|
SCB->SHCSR &= ~(1 << 16); //disable MemManage
|
||||||
|
MPU->CTRL &= ~(1 << 0); //disable MPU
|
||||||
|
MPU->RNR = rnum;
|
||||||
|
MPU->RBAR = baseaddr;
|
||||||
|
tempreg |= 0 << 28;
|
||||||
|
tempreg |= ((uint32_t)ap) << 24;
|
||||||
|
tempreg |= 0 << 19;
|
||||||
|
tempreg |= ((uint32_t)sen) << 18;
|
||||||
|
tempreg |= ((uint32_t)cen) << 17;
|
||||||
|
tempreg |= ((uint32_t)ben) << 16;
|
||||||
|
tempreg |= 0 << 8;
|
||||||
|
tempreg |= rnr << 1;
|
||||||
|
tempreg |= 1 << 0;
|
||||||
|
MPU->RASR = tempreg;
|
||||||
|
MPU->CTRL = (1 << 2) | (1 << 0); //enable PRIVDEFENA
|
||||||
|
SCB->SHCSR |= 1 << 16; //enable MemManage
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void MPU_Memory_Protection(void)
|
||||||
|
{
|
||||||
|
MPU_Set_Protection(0x20000000, 128 * 1024, 1, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect DTCM 128k, Sharing is prohibited, cache is allowed, and buffering is allowed
|
||||||
|
|
||||||
|
MPU_Set_Protection(0x24000000, 512 * 1024, 2, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect AXI SRAM, Sharing is prohibited, cache is allowed, and buffering is allowed
|
||||||
|
MPU_Set_Protection(0x30000000, 512 * 1024, 3, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SRAM1~SRAM3, Sharing is prohibited, cache is allowed, and buffering is allowed
|
||||||
|
MPU_Set_Protection(0x38000000, 64 * 1024, 4, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SRAM4, Sharing is prohibited, cache is allowed, and buffering is allowed
|
||||||
|
|
||||||
|
MPU_Set_Protection(0x60000000, 64 * 1024 * 1024, 5, MPU_REGION_FULL_ACCESS, 0, 0, 0); // protect LCD FMC 64M, No sharing, no cache, no buffering
|
||||||
|
MPU_Set_Protection(0XC0000000, 32 * 1024 * 1024, 6, MPU_REGION_FULL_ACCESS, 0, 1, 1); // protect SDRAM 32M, Sharing is prohibited, cache is allowed, and buffering is allowed
|
||||||
|
MPU_Set_Protection(0X80000000, 256 * 1024 * 1024, 7, MPU_REGION_FULL_ACCESS, 0, 0, 0); // protect NAND FLASH 256M, No sharing, no cache, no buffering
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* @brief System Clock Configuration
|
||||||
|
* @param None
|
||||||
|
* @retval None
|
||||||
|
*/
|
||||||
|
WEAK void SystemClock_Config(void)
|
||||||
|
{
|
||||||
|
SystemClockStartupInit();
|
||||||
|
|
||||||
|
MPU_Memory_Protection();
|
||||||
|
|
||||||
|
/* Update current SystemCoreClock value */
|
||||||
|
SystemCoreClockUpdate();
|
||||||
|
|
||||||
|
/* Configure the Systick interrupt time */
|
||||||
|
HAL_SYSTICK_Config(SystemCoreClock/1000);
|
||||||
|
|
||||||
|
/* Configure the Systick */
|
||||||
|
HAL_SYSTICK_CLKSourceConfig(SYSTICK_CLKSOURCE_HCLK);
|
||||||
|
|
||||||
|
/* SysTick_IRQn interrupt configuration */
|
||||||
|
HAL_NVIC_SetPriority(SysTick_IRQn, 0, 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
}
|
||||||
|
#endif
|
222
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/variant.h
Normal file
222
buildroot/share/PlatformIO/variants/BTT_SKR_SE_BX/variant.h
Normal file
|
@ -0,0 +1,222 @@
|
||||||
|
#ifndef _VARIANT_ARDUINO_STM32_
|
||||||
|
#define _VARIANT_ARDUINO_STM32_
|
||||||
|
#ifdef __cplusplus
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#endif // __cplusplus
|
||||||
|
/*----------------------------------------------------------------------------
|
||||||
|
* Pins
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
#define PE2 0
|
||||||
|
#define PE3 1
|
||||||
|
#define PE4 2
|
||||||
|
#define PE5 3
|
||||||
|
#define PE6 4
|
||||||
|
#define PI8 5
|
||||||
|
#define PC13 6
|
||||||
|
#define PC14 7
|
||||||
|
#define PC15 8
|
||||||
|
#define PI9 9
|
||||||
|
#define PI10 10
|
||||||
|
#define PI11 11
|
||||||
|
#define PF0 12
|
||||||
|
#define PF1 13
|
||||||
|
#define PF2 14
|
||||||
|
#define PH0 15
|
||||||
|
#define PH1 16
|
||||||
|
#define PB2 17
|
||||||
|
#define PF15 18
|
||||||
|
#define PG0 19
|
||||||
|
#define PG1 20
|
||||||
|
#define PE7 21
|
||||||
|
#define PE8 22
|
||||||
|
#define PE9 23
|
||||||
|
#define PE10 24
|
||||||
|
#define PE11 25
|
||||||
|
#define PE12 26
|
||||||
|
#define PE13 27
|
||||||
|
#define PE14 28
|
||||||
|
#define PE15 29
|
||||||
|
#define PB10 30
|
||||||
|
#define PB11 31
|
||||||
|
#define PH6 32
|
||||||
|
#define PH7 33
|
||||||
|
#define PH8 34
|
||||||
|
#define PH9 35
|
||||||
|
#define PH10 36
|
||||||
|
#define PH11 37
|
||||||
|
#define PH12 38
|
||||||
|
#define PB12 39
|
||||||
|
#define PB13 40
|
||||||
|
#define PB14 41
|
||||||
|
#define PB15 42
|
||||||
|
#define PD8 43
|
||||||
|
#define PD9 44
|
||||||
|
#define PD10 45
|
||||||
|
#define PD11 46
|
||||||
|
#define PD12 47
|
||||||
|
#define PD13 48
|
||||||
|
#define PD14 49
|
||||||
|
#define PD15 50
|
||||||
|
#define PG2 51
|
||||||
|
#define PG3 52
|
||||||
|
#define PG4 53
|
||||||
|
#define PG5 54
|
||||||
|
#define PG6 55
|
||||||
|
#define PG7 56
|
||||||
|
#define PG8 57
|
||||||
|
#define PC6 58
|
||||||
|
#define PC7 59
|
||||||
|
#define PC8 60
|
||||||
|
#define PC9 61
|
||||||
|
#define PA8 62
|
||||||
|
#define PA9 63
|
||||||
|
#define PA10 64
|
||||||
|
#define PA11 65
|
||||||
|
#define PA12 66
|
||||||
|
#define PA13 67
|
||||||
|
#define PH13 68
|
||||||
|
#define PH14 69
|
||||||
|
#define PH15 70
|
||||||
|
#define PI0 71
|
||||||
|
#define PI1 72
|
||||||
|
#define PI2 73
|
||||||
|
#define PI3 74
|
||||||
|
#define PA14 75
|
||||||
|
#define PA15 76
|
||||||
|
#define PC10 77
|
||||||
|
#define PC11 78
|
||||||
|
#define PC12 79
|
||||||
|
#define PD0 80
|
||||||
|
#define PD1 81
|
||||||
|
#define PD2 82
|
||||||
|
#define PD3 83
|
||||||
|
#define PD4 84
|
||||||
|
#define PD5 85
|
||||||
|
#define PD6 86
|
||||||
|
#define PD7 87
|
||||||
|
#define PG9 88
|
||||||
|
#define PG10 89
|
||||||
|
#define PG11 90
|
||||||
|
#define PG12 91
|
||||||
|
#define PG13 92
|
||||||
|
#define PG14 93
|
||||||
|
#define PG15 94
|
||||||
|
#define PB3 95
|
||||||
|
#define PB4 96
|
||||||
|
#define PB5 97
|
||||||
|
#define PB6 98
|
||||||
|
#define PB7 99
|
||||||
|
#define PB8 100
|
||||||
|
#define PB9 101
|
||||||
|
#define PE0 102
|
||||||
|
#define PE1 103
|
||||||
|
#define PI4 104
|
||||||
|
#define PI5 105
|
||||||
|
#define PI6 106
|
||||||
|
#define PI7 107
|
||||||
|
#define PA0 108
|
||||||
|
#define PA1 109
|
||||||
|
#define PA2 110
|
||||||
|
#define PA3 111
|
||||||
|
#define PA4 112
|
||||||
|
#define PA5 113
|
||||||
|
#define PA6 114
|
||||||
|
#define PA7 115
|
||||||
|
#define PB0 116
|
||||||
|
#define PB1 117
|
||||||
|
#define PH2 118
|
||||||
|
#define PH3 119
|
||||||
|
#define PH4 120
|
||||||
|
#define PH5 121
|
||||||
|
#define PC0 122
|
||||||
|
#define PC1 123
|
||||||
|
#define PC2 124
|
||||||
|
#define PC3 125
|
||||||
|
#define PC4 126
|
||||||
|
#define PC5 127
|
||||||
|
#define PF3 128
|
||||||
|
#define PF4 129
|
||||||
|
#define PF5 130
|
||||||
|
#define PF6 131
|
||||||
|
#define PF7 132
|
||||||
|
#define PF8 133
|
||||||
|
#define PF9 134
|
||||||
|
#define PF10 135
|
||||||
|
#define PF11 136
|
||||||
|
#define PF12 137
|
||||||
|
#define PF13 138
|
||||||
|
#define PF14 139
|
||||||
|
|
||||||
|
// This must be a literal with the same value as PEND
|
||||||
|
#define NUM_DIGITAL_PINS 140
|
||||||
|
|
||||||
|
// This must be a literal with a value less than or equal to to MAX_ANALOG_INPUTS
|
||||||
|
#define NUM_ANALOG_INPUTS 24
|
||||||
|
#define NUM_ANALOG_FIRST 108
|
||||||
|
|
||||||
|
// Timer Definitions
|
||||||
|
//Do not use timer used by PWM pins when possible. See PinMap_PWM in PeripheralPins.c
|
||||||
|
#define TIMER_TONE TIM2
|
||||||
|
#define TIMER_SERVO TIM5
|
||||||
|
#define TIMER_SERIAL TIM7
|
||||||
|
|
||||||
|
// UART1 for TFT port
|
||||||
|
#define ENABLE_HWSERIAL1
|
||||||
|
#define PIN_SERIAL1_RX PA10
|
||||||
|
#define PIN_SERIAL1_TX PA9
|
||||||
|
|
||||||
|
// UART4 for ESP-01 port
|
||||||
|
#define ENABLE_HWSERIAL4
|
||||||
|
#define PIN_SERIAL4_RX PA1
|
||||||
|
#define PIN_SERIAL4_TX PA0
|
||||||
|
|
||||||
|
// IIC1 for onboard 24C32 EEPROM
|
||||||
|
#define PIN_WIRE_SDA PB9
|
||||||
|
#define PIN_WIRE_SCL PB8
|
||||||
|
|
||||||
|
// SPI3 for onboard SD card
|
||||||
|
// #define PIN_SPI_MOSI PC12
|
||||||
|
// #define PIN_SPI_MISO PC11
|
||||||
|
// #define PIN_SPI_SCK PC10
|
||||||
|
|
||||||
|
// HSE default value is 25MHz in HAL
|
||||||
|
// HSE_BYPASS is 25MHz
|
||||||
|
#ifndef HSE_BYPASS_NOT_USED
|
||||||
|
#define HSE_VALUE 25000000
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// #define USE_USB_FS
|
||||||
|
/* Extra HAL modules */
|
||||||
|
//#define HAL_HCD_MODULE_ENABLED
|
||||||
|
//#define HAL_DAC_MODULE_ENABLED
|
||||||
|
//#define HAL_ETH_MODULE_ENABLED
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
} // extern "C"
|
||||||
|
#endif
|
||||||
|
/*----------------------------------------------------------------------------
|
||||||
|
* Arduino objects - C++ only
|
||||||
|
*----------------------------------------------------------------------------*/
|
||||||
|
|
||||||
|
#ifdef __cplusplus
|
||||||
|
// These serial port names are intended to allow libraries and architecture-neutral
|
||||||
|
// sketches to automatically default to the correct port name for a particular type
|
||||||
|
// of use. For example, a GPS module would normally connect to SERIAL_PORT_HARDWARE_OPEN,
|
||||||
|
// the first hardware serial port whose RX/TX pins are not dedicated to another use.
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_MONITOR Port which normally prints to the Arduino Serial Monitor
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_USBVIRTUAL Port which is USB virtual serial
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_LINUXBRIDGE Port which connects to a Linux system via Bridge library
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_HARDWARE Hardware serial port, physical RX & TX pins.
|
||||||
|
//
|
||||||
|
// SERIAL_PORT_HARDWARE_OPEN Hardware serial ports which are open for use. Their RX & TX
|
||||||
|
// pins are NOT connected to anything by default.
|
||||||
|
#define SERIAL_PORT_MONITOR Serial
|
||||||
|
#define SERIAL_PORT_HARDWARE Serial
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif /* _VARIANT_ARDUINO_STM32_ */
|
18
buildroot/tests/BTT_SKR_SE_BX
Executable file
18
buildroot/tests/BTT_SKR_SE_BX
Executable file
|
@ -0,0 +1,18 @@
|
||||||
|
#!/usr/bin/env bash
|
||||||
|
#
|
||||||
|
# Build tests for BTT_SKR_SE_BX
|
||||||
|
#
|
||||||
|
|
||||||
|
# exit on first failure
|
||||||
|
set -e
|
||||||
|
|
||||||
|
#
|
||||||
|
# Build with the default configurations
|
||||||
|
#
|
||||||
|
restore_configs
|
||||||
|
opt_set MOTHERBOARD BOARD_BTT_SKR_SE_BX
|
||||||
|
opt_set SERIAL_PORT 1
|
||||||
|
exec_test $1 $2 "Default Configuration" "$3"
|
||||||
|
|
||||||
|
# clean up
|
||||||
|
restore_configs
|
|
@ -37,7 +37,7 @@ HAS_WIRED_LCD = src_filter=+<src/lcd/lcdprint.cpp>
|
||||||
HAS_MARLINUI_HD44780 = src_filter=+<src/lcd/HD44780>
|
HAS_MARLINUI_HD44780 = src_filter=+<src/lcd/HD44780>
|
||||||
HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.1
|
HAS_MARLINUI_U8GLIB = U8glib-HAL@~0.4.1
|
||||||
src_filter=+<src/lcd/dogm>
|
src_filter=+<src/lcd/dogm>
|
||||||
HAS_(FSMC|SPI)_TFT = src_filter=+<src/HAL/STM32/tft> +<src/HAL/STM32F1/tft> +<src/lcd/tft_io>
|
HAS_(FSMC|SPI|LTDC)_TFT = src_filter=+<src/HAL/STM32/tft> +<src/HAL/STM32F1/tft> +<src/lcd/tft_io>
|
||||||
HAS_FSMC_TFT = src_filter=+<src/HAL/STM32/tft/tft_fsmc.cpp> +<src/HAL/STM32F1/tft/tft_fsmc.cpp>
|
HAS_FSMC_TFT = src_filter=+<src/HAL/STM32/tft/tft_fsmc.cpp> +<src/HAL/STM32F1/tft/tft_fsmc.cpp>
|
||||||
HAS_SPI_TFT = src_filter=+<src/HAL/STM32/tft/tft_spi.cpp> +<src/HAL/STM32F1/tft/tft_spi.cpp>
|
HAS_SPI_TFT = src_filter=+<src/HAL/STM32/tft/tft_spi.cpp> +<src/HAL/STM32F1/tft/tft_spi.cpp>
|
||||||
I2C_EEPROM = src_filter=+<src/HAL/shared/eeprom_if_i2c.cpp>
|
I2C_EEPROM = src_filter=+<src/HAL/shared/eeprom_if_i2c.cpp>
|
||||||
|
|
|
@ -28,3 +28,28 @@ platform = ${common_stm32.platform}
|
||||||
extends = common_stm32
|
extends = common_stm32
|
||||||
board = remram_v1
|
board = remram_v1
|
||||||
build_flags = ${common_stm32.build_flags}
|
build_flags = ${common_stm32.build_flags}
|
||||||
|
|
||||||
|
#
|
||||||
|
# BigTreeTech SKR SE BX (STM32H743IIT6 ARM Cortex-M7)
|
||||||
|
#
|
||||||
|
[env:BTT_SKR_SE_BX]
|
||||||
|
platform = ${common_stm32.platform}
|
||||||
|
platform_packages = ${stm_flash_drive.platform_packages}
|
||||||
|
extends = common_stm32
|
||||||
|
board = BTT_SKR_SE_BX
|
||||||
|
extra_scripts = ${common.extra_scripts}
|
||||||
|
pre:buildroot/share/PlatformIO/scripts/generic_create_variant.py
|
||||||
|
build_flags = ${common_stm32.build_flags}
|
||||||
|
${stm_flash_drive.build_flags}
|
||||||
|
-DUSE_USBHOST_HS
|
||||||
|
-DUSE_USB_HS_IN_FS
|
||||||
|
#-DUSBD_USE_CDC_MSC
|
||||||
|
-DVECT_TAB_OFFSET=0x20000
|
||||||
|
-DHAL_DMA2D_MODULE_ENABLED
|
||||||
|
-DHAL_LTDC_MODULE_ENABLED
|
||||||
|
-DHAL_SDRAM_MODULE_ENABLED
|
||||||
|
-DHAL_QSPI_MODULE_ENABLED
|
||||||
|
-DHAL_MDMA_MODULE_ENABLED
|
||||||
|
-DHAL_SD_MODULE_ENABLED
|
||||||
|
upload_protocol = cmsis-dap
|
||||||
|
debug_tool = cmsis-dap
|
||||||
|
|
Loading…
Reference in a new issue